From 394d741a75840a6a4579c73f4c00f6764ce14f6e Mon Sep 17 00:00:00 2001 From: bocchino Date: Wed, 15 Jun 2022 22:01:43 -0700 Subject: [PATCH 001/169] Add unit tests for F Prime framing --- Svc/FramingProtocol/CMakeLists.txt | 6 + Svc/FramingProtocol/test/ut/FramingTester.cpp | 154 ++++++++++++++++ Svc/FramingProtocol/test/ut/FramingTester.hpp | 166 ++++++++++++++++++ Svc/FramingProtocol/test/ut/main.cpp | 22 +++ 4 files changed, 348 insertions(+) create mode 100644 Svc/FramingProtocol/test/ut/FramingTester.cpp create mode 100644 Svc/FramingProtocol/test/ut/FramingTester.hpp create mode 100644 Svc/FramingProtocol/test/ut/main.cpp diff --git a/Svc/FramingProtocol/CMakeLists.txt b/Svc/FramingProtocol/CMakeLists.txt index 3182586cde..0f9c38fbaf 100644 --- a/Svc/FramingProtocol/CMakeLists.txt +++ b/Svc/FramingProtocol/CMakeLists.txt @@ -21,3 +21,9 @@ set(MOD_DEPS register_fprime_module() +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/test/ut/FramingTester.cpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/main.cpp" +) +set(UT_MOD_DEPS STest) +register_fprime_ut() diff --git a/Svc/FramingProtocol/test/ut/FramingTester.cpp b/Svc/FramingProtocol/test/ut/FramingTester.cpp new file mode 100644 index 0000000000..5d8c35a251 --- /dev/null +++ b/Svc/FramingProtocol/test/ut/FramingTester.cpp @@ -0,0 +1,154 @@ +// ====================================================================== +// \title FramingTester.cpp +// \author bocchino +// \brief cpp file for FramingTester class +// ====================================================================== + +#include "STest/Pick/Pick.hpp" +#include "Svc/FramingProtocol/test/ut/FramingTester.hpp" + +namespace Svc { + + // ---------------------------------------------------------------------- + // Construction + // ---------------------------------------------------------------------- + + FramingTester :: + FramingTester(Fw::ComPacket::ComPacketType packetType) : + // Pick a random data size + dataSize(STest::Pick::lowerUpper(1, MAX_DATA_SIZE)), + packetType(packetType), + interface(*this) + { + FW_ASSERT(this->dataSize <= MAX_DATA_SIZE); + this->fprimeFraming.setup(this->interface); + // Fill in random data + for (U32 i = 0; i < sizeof(this->data); ++i) { + this->data[i] = STest::Pick::lowerUpper(0, 0xFF); + } + memset(this->bufferStorage, 0, sizeof this->bufferStorage); + } + + // ---------------------------------------------------------------------- + // Public member functions + // ---------------------------------------------------------------------- + + void FramingTester :: + check() + { + this->fprimeFraming.frame( + this->data, + this->dataSize, + this->packetType + ); + // Check that we received a buffer + Fw::Buffer *const sentBuffer = this->interface.getSentBuffer(); + ASSERT_NE(sentBuffer, nullptr); + if (sentBuffer != nullptr) { + // Check the start word + this->checkStartWord(); + // Check the packet size + const U32 packetSize = this->getPacketSize(); + this->checkPacketSize(packetSize); + // Check the packet type + // TODO + // Check the data + // TODO + // Check the hash value + // TODO + } + } + + // ---------------------------------------------------------------------- + // Private member functions + // ---------------------------------------------------------------------- + + FpFrameHeader::TokenType FramingTester :: + getPacketSize() + { + FpFrameHeader::TokenType packetSize = 0; + Fw::SerialBuffer sb( + &this->bufferStorage[PACKET_SIZE_OFFSET], + sizeof packetSize + ); + sb.fill(); + const Fw::SerializeStatus status = sb.deserialize(packetSize); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); + return packetSize; + } + + void FramingTester :: + checkPacketSize(FpFrameHeader::TokenType packetSize) + { + U32 expectedPacketSize = packetSize; + if (this->packetType == Fw::ComPacket::FW_PACKET_UNKNOWN) { + // Packet type is stored in header + packetSize += sizeof(SerialPacketType); + } + ASSERT_EQ(packetSize, expectedPacketSize); + } + + void FramingTester :: + checkPacketType() + { + SerialPacketType serialPacketType = 0; + Fw::SerialBuffer sb( + &this->bufferStorage[PACKET_TYPE_OFFSET], + sizeof serialPacketType + ); + sb.fill(); + const Fw::SerializeStatus status = sb.deserialize(serialPacketType); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); + typedef Fw::ComPacket::ComPacketType PacketType; + const PacketType pt = static_cast(serialPacketType); + ASSERT_EQ(pt, this->packetType); + } + + void FramingTester :: + checkStartWord() + { + FpFrameHeader::TokenType startWord = 0; + Fw::SerialBuffer sb( + &this->bufferStorage[START_WORD_OFFSET], + sizeof startWord + ); + sb.fill(); + const Fw::SerializeStatus status = sb.deserialize(startWord); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); + ASSERT_EQ(startWord, FpFrameHeader::START_WORD); + } + + void FramingTester :: + checkData() + { + U32 dataOffset = PACKET_TYPE_OFFSET; + if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { + // Packet type is stored in header + dataOffset += sizeof(SerialPacketType); + } + const I32 result = memcmp( + this->data, + &this->bufferStorage[dataOffset], + this->dataSize + ); + ASSERT_EQ(result, 0); + } + + void FramingTester :: + checkHash(FpFrameHeader::TokenType packetSize) + { + Utils::Hash hash; + Utils::HashBuffer hashBuffer; + const U32 dataSize = FpFrameHeader::SIZE + packetSize; + hash.update(this->bufferStorage, dataSize); + hash.final(hashBuffer); + const U8 *const hashAddr = hashBuffer.getBuffAddr(); + const I32 result = memcmp( + &this->bufferStorage[dataSize], + hashAddr, + HASH_DIGEST_LENGTH + ); + ASSERT_EQ(result, 0); + } + +} diff --git a/Svc/FramingProtocol/test/ut/FramingTester.hpp b/Svc/FramingProtocol/test/ut/FramingTester.hpp new file mode 100644 index 0000000000..d8701ae2d5 --- /dev/null +++ b/Svc/FramingProtocol/test/ut/FramingTester.hpp @@ -0,0 +1,166 @@ +// ====================================================================== +// \title FramingTester.hpp +// \author bocchino +// \brief hpp file for FramingTester class +// ====================================================================== + +#include "Fw/Types/Assert.hpp" +#include "Fw/Types/SerialBuffer.hpp" +#include "Svc/FramingProtocol/FprimeProtocol.hpp" +#include "Svc/FramingProtocol/FramingProtocol.hpp" +#include "Utils/Hash/Hash.hpp" +#include "gtest/gtest.h" + +namespace Svc { + + //! A harness for checking framing + class FramingTester { + + private: + + // ---------------------------------------------------------------------- + // Constants and types + // ---------------------------------------------------------------------- + + //! The serialized packet type + typedef I32 SerialPacketType; + + //! Constants + enum Constants { + //! The maximum buffer size + MAX_BUFFER_SIZE = 1024, + //! The maximum allowed data size + MAX_DATA_SIZE = MAX_BUFFER_SIZE - + sizeof FpFrameHeader::START_WORD - + sizeof(SerialPacketType) - + HASH_DIGEST_LENGTH, + //! The offset of the start word in an F Prime protocol frame + START_WORD_OFFSET = 0, + //! The offset of the packet size in an F Prime protocol frame + PACKET_SIZE_OFFSET = START_WORD_OFFSET + + sizeof FpFrameHeader::START_WORD, + //! The offset of the packet type in an F Prime protocol frame + PACKET_TYPE_OFFSET = FpFrameHeader::SIZE, + }; + + //! The framing protocol interface + class Interface : + public FramingProtocolInterface + { + + public: + + //! Construct an Interface + Interface( + FramingTester& framingChecker //!< The enclosing FramingTester + ) : + framingChecker(framingChecker), + sentBuffer(nullptr) + { + + } + + public: + + //! Allocate the buffer + Fw::Buffer allocate(const U32 size) { + FW_ASSERT(size <= MAX_BUFFER_SIZE); + Fw::Buffer buffer(this->framingChecker.bufferStorage, size); + return buffer; + } + + //! Send the buffer + void send(Fw::Buffer& outgoing) { + this->sentBuffer = &outgoing; + } + + //! Get the sent buffer + Fw::Buffer *getSentBuffer() { + return this->sentBuffer; + } + + private: + + //! The enclosing FramingTester + FramingTester& framingChecker; + + //! The sent buffer + Fw::Buffer *sentBuffer; + + }; + + public: + + // ---------------------------------------------------------------------- + // Construction + // ---------------------------------------------------------------------- + + //! Construct a framing checker + FramingTester( + Fw::ComPacket::ComPacketType packetType //!< The packet type + ); + + public: + + // ---------------------------------------------------------------------- + // Public member functions + // ---------------------------------------------------------------------- + + //! Check framing + void check(); + + // ---------------------------------------------------------------------- + // Private member functions + // ---------------------------------------------------------------------- + + private: + + //! Get the packet size from the buffer + FpFrameHeader::TokenType getPacketSize(); + + //! Check the packet size in the buffer + void checkPacketSize( + FpFrameHeader::TokenType packetSize //!< The packet size + ); + + //! Check the packet type in the buffer + void checkPacketType(); + + //! Check the start word in the buffer + void checkStartWord(); + + //! Check the data in the buffer + void checkData(); + + //! Check the hash value in the buffer + void checkHash( + FpFrameHeader::TokenType packetSize //!< The packet size + ); + + private: + + // ---------------------------------------------------------------------- + // Private member variables + // ---------------------------------------------------------------------- + + //! The data to frame + U8 data[MAX_DATA_SIZE]; + + //! The data size in bytes + const U32 dataSize; + + //! The packet type + Fw::ComPacket::ComPacketType packetType; + + //! Storage for the buffer + U8 bufferStorage[MAX_BUFFER_SIZE]; + + //! The framing protocol interface + Interface interface; + + //! The F Prime framing protocol + FprimeFraming fprimeFraming; + + }; + +} diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp new file mode 100644 index 0000000000..b8950a0ae0 --- /dev/null +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -0,0 +1,22 @@ +#include "gtest/gtest.h" +#include "Svc/FramingProtocol/test/ut/FramingTester.hpp" +#include "STest/Random/Random.hpp" + +// ---------------------------------------------------------------------- +// Tests +// ---------------------------------------------------------------------- + +TEST(Framing, CommandPacket) { + Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); + tester.check(); +} + +// ---------------------------------------------------------------------- +// Main function +// ---------------------------------------------------------------------- + +int main(int argc, char **argv) { + ::testing::InitGoogleTest(&argc, argv); + STest::Random::seed(); + return RUN_ALL_TESTS(); +} From e968e7a45e5b25b40427bfe23dab0b08c5c274a8 Mon Sep 17 00:00:00 2001 From: bocchino Date: Wed, 15 Jun 2022 22:18:56 -0700 Subject: [PATCH 002/169] Revise F Prime framing unit tests --- Svc/FramingProtocol/test/ut/FramingTester.cpp | 14 ++++++++------ Svc/FramingProtocol/test/ut/main.cpp | 10 ++++++++++ 2 files changed, 18 insertions(+), 6 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/FramingTester.cpp b/Svc/FramingProtocol/test/ut/FramingTester.cpp index 5d8c35a251..a8a26f672b 100644 --- a/Svc/FramingProtocol/test/ut/FramingTester.cpp +++ b/Svc/FramingProtocol/test/ut/FramingTester.cpp @@ -51,11 +51,13 @@ namespace Svc { const U32 packetSize = this->getPacketSize(); this->checkPacketSize(packetSize); // Check the packet type - // TODO + if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { + this->checkPacketType(); + } // Check the data - // TODO + this->checkData(); // Check the hash value - // TODO + this->checkHash(packetSize); } } @@ -80,10 +82,10 @@ namespace Svc { void FramingTester :: checkPacketSize(FpFrameHeader::TokenType packetSize) { - U32 expectedPacketSize = packetSize; - if (this->packetType == Fw::ComPacket::FW_PACKET_UNKNOWN) { + U32 expectedPacketSize = this->dataSize; + if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { // Packet type is stored in header - packetSize += sizeof(SerialPacketType); + expectedPacketSize += sizeof(SerialPacketType); } ASSERT_EQ(packetSize, expectedPacketSize); } diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index b8950a0ae0..e437b82ca6 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -11,6 +11,16 @@ TEST(Framing, CommandPacket) { tester.check(); } +TEST(Framing, FilePacket) { + Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_FILE); + tester.check(); +} + +TEST(Framing, UnknownPacket) { + Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_UNKNOWN); + tester.check(); +} + // ---------------------------------------------------------------------- // Main function // ---------------------------------------------------------------------- From b305965d60d4894e4649cf9220a748f0f9de5899 Mon Sep 17 00:00:00 2001 From: bocchino Date: Tue, 21 Jun 2022 10:42:54 -0700 Subject: [PATCH 003/169] Revise SDD for Framing Protocol Replace Inspection with Unit test --- Svc/FramingProtocol/docs/sdd.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Svc/FramingProtocol/docs/sdd.md b/Svc/FramingProtocol/docs/sdd.md index 67183c18ad..83e1545fbb 100644 --- a/Svc/FramingProtocol/docs/sdd.md +++ b/Svc/FramingProtocol/docs/sdd.md @@ -28,9 +28,9 @@ defined in the `FramingProtocol` library. Requirement | Description | Verification Method ----------- | ----------- | ------------------- -FramingProtocol-001 | `Svc::FramingProtocol` shall provide the interface to a protocol for wrapping data in frames for transmission to the ground|Inspection -FramingProtocol-002 | `Svc::FramingProtocol` shall provide the interface to a protocol for extracting data from frames received from the ground|Inspection -FramingProtocol-003 | `Svc::FramingProtocol` shall implement the framing and deframing protocols used by the F Prime GDS|Inspection +FramingProtocol-001 | `Svc::FramingProtocol` shall provide the interface to a protocol for wrapping data in frames for transmission to the ground|Unit test +FramingProtocol-002 | `Svc::FramingProtocol` shall provide the interface to a protocol for extracting data from frames received from the ground|Unit test +FramingProtocol-003 | `Svc::FramingProtocol` shall implement the framing and deframing protocols used by the F Prime GDS|Unit test ## 2. Using the Interface From bd3b224b8767eb2ea1d6c55f06a1783b26907456 Mon Sep 17 00:00:00 2001 From: bocchino Date: Tue, 21 Jun 2022 10:51:32 -0700 Subject: [PATCH 004/169] Refactor Framing Protocol tests --- Svc/FramingProtocol/test/ut/FramingTester.cpp | 1 + Svc/FramingProtocol/test/ut/FramingTester.hpp | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/Svc/FramingProtocol/test/ut/FramingTester.cpp b/Svc/FramingProtocol/test/ut/FramingTester.cpp index a8a26f672b..8b25340139 100644 --- a/Svc/FramingProtocol/test/ut/FramingTester.cpp +++ b/Svc/FramingProtocol/test/ut/FramingTester.cpp @@ -6,6 +6,7 @@ #include "STest/Pick/Pick.hpp" #include "Svc/FramingProtocol/test/ut/FramingTester.hpp" +#include "gtest/gtest.h" namespace Svc { diff --git a/Svc/FramingProtocol/test/ut/FramingTester.hpp b/Svc/FramingProtocol/test/ut/FramingTester.hpp index d8701ae2d5..0a2e31dfd3 100644 --- a/Svc/FramingProtocol/test/ut/FramingTester.hpp +++ b/Svc/FramingProtocol/test/ut/FramingTester.hpp @@ -9,7 +9,6 @@ #include "Svc/FramingProtocol/FprimeProtocol.hpp" #include "Svc/FramingProtocol/FramingProtocol.hpp" #include "Utils/Hash/Hash.hpp" -#include "gtest/gtest.h" namespace Svc { From 9f4e4ac190ab059f69deef2a718e24bfebd02f0d Mon Sep 17 00:00:00 2001 From: bocchino Date: Tue, 21 Jun 2022 11:58:23 -0700 Subject: [PATCH 005/169] Start to add deframing tests --- .../test/ut/DeframingTester.cpp | 159 ++++++++++++++++ .../test/ut/DeframingTester.hpp | 178 ++++++++++++++++++ Svc/FramingProtocol/test/ut/FramingTester.hpp | 10 +- Svc/FramingProtocol/test/ut/main.cpp | 1 + 4 files changed, 343 insertions(+), 5 deletions(-) create mode 100644 Svc/FramingProtocol/test/ut/DeframingTester.cpp create mode 100644 Svc/FramingProtocol/test/ut/DeframingTester.hpp diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp new file mode 100644 index 0000000000..97921857ee --- /dev/null +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -0,0 +1,159 @@ +// ====================================================================== +// \title DeframingTester.cpp +// \author bocchino +// \brief cpp file for DeframingTester class +// ====================================================================== + +#include "STest/Pick/Pick.hpp" +#include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" +#include "gtest/gtest.h" + +namespace Svc { + +#if 0 + // ---------------------------------------------------------------------- + // Construction + // ---------------------------------------------------------------------- + + DeframingTester :: + DeframingTester(Fw::ComPacket::ComPacketType packetType) : + // Pick a random data size + dataSize(STest::Pick::lowerUpper(1, MAX_DATA_SIZE)), + packetType(packetType), + interface(*this) + { + FW_ASSERT(this->dataSize <= MAX_DATA_SIZE); + this->fprimeDeframing.setup(this->interface); + // Fill in random data + for (U32 i = 0; i < sizeof(this->data); ++i) { + this->data[i] = STest::Pick::lowerUpper(0, 0xFF); + } + memset(this->bufferStorage, 0, sizeof this->bufferStorage); + } + + // ---------------------------------------------------------------------- + // Public member functions + // ---------------------------------------------------------------------- + + void DeframingTester :: + check() + { + this->fprimeDeframing.frame( + this->data, + this->dataSize, + this->packetType + ); + // Check that we received a buffer + Fw::Buffer *const sentBuffer = this->interface.getSentBuffer(); + ASSERT_NE(sentBuffer, nullptr); + if (sentBuffer != nullptr) { + // Check the start word + this->checkStartWord(); + // Check the packet size + const U32 packetSize = this->getPacketSize(); + this->checkPacketSize(packetSize); + // Check the packet type + if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { + this->checkPacketType(); + } + // Check the data + this->checkData(); + // Check the hash value + this->checkHash(packetSize); + } + } + + // ---------------------------------------------------------------------- + // Private member functions + // ---------------------------------------------------------------------- + + FpFrameHeader::TokenType DeframingTester :: + getPacketSize() + { + FpFrameHeader::TokenType packetSize = 0; + Fw::SerialBuffer sb( + &this->bufferStorage[PACKET_SIZE_OFFSET], + sizeof packetSize + ); + sb.fill(); + const Fw::SerializeStatus status = sb.deserialize(packetSize); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); + return packetSize; + } + + void DeframingTester :: + checkPacketSize(FpFrameHeader::TokenType packetSize) + { + U32 expectedPacketSize = this->dataSize; + if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { + // Packet type is stored in header + expectedPacketSize += sizeof(SerialPacketType); + } + ASSERT_EQ(packetSize, expectedPacketSize); + } + + void DeframingTester :: + checkPacketType() + { + SerialPacketType serialPacketType = 0; + Fw::SerialBuffer sb( + &this->bufferStorage[PACKET_TYPE_OFFSET], + sizeof serialPacketType + ); + sb.fill(); + const Fw::SerializeStatus status = sb.deserialize(serialPacketType); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); + typedef Fw::ComPacket::ComPacketType PacketType; + const PacketType pt = static_cast(serialPacketType); + ASSERT_EQ(pt, this->packetType); + } + + void DeframingTester :: + checkStartWord() + { + FpFrameHeader::TokenType startWord = 0; + Fw::SerialBuffer sb( + &this->bufferStorage[START_WORD_OFFSET], + sizeof startWord + ); + sb.fill(); + const Fw::SerializeStatus status = sb.deserialize(startWord); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); + ASSERT_EQ(startWord, FpFrameHeader::START_WORD); + } + + void DeframingTester :: + checkData() + { + U32 dataOffset = PACKET_TYPE_OFFSET; + if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { + // Packet type is stored in header + dataOffset += sizeof(SerialPacketType); + } + const I32 result = memcmp( + this->data, + &this->bufferStorage[dataOffset], + this->dataSize + ); + ASSERT_EQ(result, 0); + } + + void DeframingTester :: + checkHash(FpFrameHeader::TokenType packetSize) + { + Utils::Hash hash; + Utils::HashBuffer hashBuffer; + const U32 dataSize = FpFrameHeader::SIZE + packetSize; + hash.update(this->bufferStorage, dataSize); + hash.final(hashBuffer); + const U8 *const hashAddr = hashBuffer.getBuffAddr(); + const I32 result = memcmp( + &this->bufferStorage[dataSize], + hashAddr, + HASH_DIGEST_LENGTH + ); + ASSERT_EQ(result, 0); + } +#endif + +} diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp new file mode 100644 index 0000000000..dbafa5406f --- /dev/null +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -0,0 +1,178 @@ +// ====================================================================== +// \title DeframingTester.hpp +// \author bocchino +// \brief hpp file for DeframingTester class +// ====================================================================== + +#include "Fw/Types/Assert.hpp" +#include "Fw/Types/SerialBuffer.hpp" +#include "Svc/FramingProtocol/FprimeProtocol.hpp" +#include "Svc/FramingProtocol/DeframingProtocol.hpp" +#include "Utils/Hash/Hash.hpp" +#include "Utils/Types/CircularBuffer.hpp" + +namespace Svc { + + //! A harness for checking deframing + class DeframingTester { + + private: + + // ---------------------------------------------------------------------- + // Constants and types + // ---------------------------------------------------------------------- + +#if 0 + //! The serialized packet type + typedef I32 SerialPacketType; +#endif + + //! Constants + enum Constants { + //! The maximum buffer size + MAX_BUFFER_SIZE = 1024, +#if 0 + //! The maximum allowed data size + MAX_DATA_SIZE = MAX_BUFFER_SIZE - + sizeof FpFrameHeader::START_WORD - + sizeof(SerialPacketType) - + HASH_DIGEST_LENGTH, + //! The offset of the start word in an F Prime protocol frame + START_WORD_OFFSET = 0, + //! The offset of the packet size in an F Prime protocol frame + PACKET_SIZE_OFFSET = START_WORD_OFFSET + + sizeof FpFrameHeader::START_WORD, + //! The offset of the packet type in an F Prime protocol frame + PACKET_TYPE_OFFSET = FpFrameHeader::SIZE, +#endif + }; + + //! The deframing protocol interface + class Interface : + public DeframingProtocolInterface + { + + public: + + //! Construct an Interface + Interface( + DeframingTester& deframingTester //!< The enclosing DeframingTester + ) : + deframingTester(deframingTester), + routedBuffer(nullptr) + { + + } + + public: + + //! Allocate the buffer + Fw::Buffer allocate(const U32 size) { + FW_ASSERT(size <= MAX_BUFFER_SIZE); + Fw::Buffer buffer(this->deframingTester.bufferStorage, size); + return buffer; + } + + //! Route the buffer + void route(Fw::Buffer& data) { + this->routedBuffer = &data; + } + + //! Get the routed buffer + Fw::Buffer *getRoutedBuffer() { + return this->routedBuffer; + } + + private: + + //! The enclosing DeframingTester + DeframingTester& deframingTester; + + //! The routed buffer + Fw::Buffer *routedBuffer; + + }; + +#if 0 + public: + + // ---------------------------------------------------------------------- + // Construction + // ---------------------------------------------------------------------- + + //! Construct a DeframingTester + DeframingTester( + Fw::ComPacket::ComPacketType packetType //!< The packet type + ); +#endif + +#if 0 + public: + + // ---------------------------------------------------------------------- + // Public member functions + // ---------------------------------------------------------------------- + + //! Check framing + void check(); +#endif + +#if 0 + // ---------------------------------------------------------------------- + // Private member functions + // ---------------------------------------------------------------------- + + private: + + //! Get the packet size from the buffer + FpFrameHeader::TokenType getPacketSize(); + + //! Check the packet size in the buffer + void checkPacketSize( + FpFrameHeader::TokenType packetSize //!< The packet size + ); + + //! Check the packet type in the buffer + void checkPacketType(); + + //! Check the start word in the buffer + void checkStartWord(); + + //! Check the data in the buffer + void checkData(); + + //! Check the hash value in the buffer + void checkHash( + FpFrameHeader::TokenType packetSize //!< The packet size + ); +#endif + + private: + + // ---------------------------------------------------------------------- + // Private member variables + // ---------------------------------------------------------------------- + +#if 0 + //! The data to frame + U8 data[MAX_DATA_SIZE]; + + //! The data size in bytes + const U32 dataSize; + + //! The packet type + Fw::ComPacket::ComPacketType packetType; +#endif + + //! Storage for the buffer + U8 bufferStorage[MAX_BUFFER_SIZE]; + + //! The framing protocol interface + Interface interface; + + //! The F Prime framing protocol + FprimeDeframing fprimeDeframing; + + }; + +} diff --git a/Svc/FramingProtocol/test/ut/FramingTester.hpp b/Svc/FramingProtocol/test/ut/FramingTester.hpp index 0a2e31dfd3..28867ba3ed 100644 --- a/Svc/FramingProtocol/test/ut/FramingTester.hpp +++ b/Svc/FramingProtocol/test/ut/FramingTester.hpp @@ -51,9 +51,9 @@ namespace Svc { //! Construct an Interface Interface( - FramingTester& framingChecker //!< The enclosing FramingTester + FramingTester& framingTester //!< The enclosing FramingTester ) : - framingChecker(framingChecker), + framingTester(framingTester), sentBuffer(nullptr) { @@ -64,7 +64,7 @@ namespace Svc { //! Allocate the buffer Fw::Buffer allocate(const U32 size) { FW_ASSERT(size <= MAX_BUFFER_SIZE); - Fw::Buffer buffer(this->framingChecker.bufferStorage, size); + Fw::Buffer buffer(this->framingTester.bufferStorage, size); return buffer; } @@ -81,7 +81,7 @@ namespace Svc { private: //! The enclosing FramingTester - FramingTester& framingChecker; + FramingTester& framingTester; //! The sent buffer Fw::Buffer *sentBuffer; @@ -94,7 +94,7 @@ namespace Svc { // Construction // ---------------------------------------------------------------------- - //! Construct a framing checker + //! Construct a FramingTester FramingTester( Fw::ComPacket::ComPacketType packetType //!< The packet type ); diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index e437b82ca6..2f00071891 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -1,4 +1,5 @@ #include "gtest/gtest.h" +#include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" #include "Svc/FramingProtocol/test/ut/FramingTester.hpp" #include "STest/Random/Random.hpp" From d7c6b421276750dd9075498bec068e9f2aff61dd Mon Sep 17 00:00:00 2001 From: bocchino Date: Tue, 21 Jun 2022 13:48:25 -0700 Subject: [PATCH 006/169] Revise deframing tests --- Svc/FramingProtocol/CMakeLists.txt | 1 + .../test/ut/DeframingTester.cpp | 22 ++++++++-------- .../test/ut/DeframingTester.hpp | 25 +++++++++++-------- 3 files changed, 26 insertions(+), 22 deletions(-) diff --git a/Svc/FramingProtocol/CMakeLists.txt b/Svc/FramingProtocol/CMakeLists.txt index 0f9c38fbaf..635f4c08e6 100644 --- a/Svc/FramingProtocol/CMakeLists.txt +++ b/Svc/FramingProtocol/CMakeLists.txt @@ -22,6 +22,7 @@ set(MOD_DEPS register_fprime_module() set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/test/ut/DeframingTester.cpp" "${CMAKE_CURRENT_LIST_DIR}/test/ut/FramingTester.cpp" "${CMAKE_CURRENT_LIST_DIR}/test/ut/main.cpp" ) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 97921857ee..c6e246f1ff 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -10,27 +10,27 @@ namespace Svc { -#if 0 // ---------------------------------------------------------------------- // Construction // ---------------------------------------------------------------------- DeframingTester :: - DeframingTester(Fw::ComPacket::ComPacketType packetType) : - // Pick a random data size - dataSize(STest::Pick::lowerUpper(1, MAX_DATA_SIZE)), - packetType(packetType), + DeframingTester(U32 cbStoreSize) : + cbStorage(new U8[cbStoreSize]), + circularBuffer(this->cbStorage, cbStoreSize), interface(*this) { - FW_ASSERT(this->dataSize <= MAX_DATA_SIZE); - this->fprimeDeframing.setup(this->interface); - // Fill in random data - for (U32 i = 0; i < sizeof(this->data); ++i) { - this->data[i] = STest::Pick::lowerUpper(0, 0xFF); - } memset(this->bufferStorage, 0, sizeof this->bufferStorage); + memset(this->cbStorage, 0, cbStoreSize); } + DeframingTester :: + ~DeframingTester() + { + delete[](this->cbStorage); + } + +#if 0 // ---------------------------------------------------------------------- // Public member functions // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index dbafa5406f..f2ccf1cec4 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -31,12 +31,11 @@ namespace Svc { enum Constants { //! The maximum buffer size MAX_BUFFER_SIZE = 1024, -#if 0 - //! The maximum allowed data size + //! The maximum allowed packet size MAX_DATA_SIZE = MAX_BUFFER_SIZE - sizeof FpFrameHeader::START_WORD - - sizeof(SerialPacketType) - HASH_DIGEST_LENGTH, +#if 0 //! The offset of the start word in an F Prime protocol frame START_WORD_OFFSET = 0, //! The offset of the packet size in an F Prime protocol frame @@ -93,29 +92,27 @@ namespace Svc { }; -#if 0 public: // ---------------------------------------------------------------------- - // Construction + // Construction and destruction // ---------------------------------------------------------------------- //! Construct a DeframingTester DeframingTester( - Fw::ComPacket::ComPacketType packetType //!< The packet type + U32 cbStoreSize = MAX_BUFFER_SIZE //!< The circular buffer store size ); -#endif -#if 0 + //! Destroy a DeframingTester + ~DeframingTester(); + public: // ---------------------------------------------------------------------- // Public member functions // ---------------------------------------------------------------------- - //! Check framing - void check(); -#endif + // TODO #if 0 // ---------------------------------------------------------------------- @@ -166,6 +163,12 @@ namespace Svc { //! Storage for the buffer U8 bufferStorage[MAX_BUFFER_SIZE]; + + //! Storage for the circular buffer + U8* cbStorage; + + //! The circular buffer + Types::CircularBuffer circularBuffer; //! The framing protocol interface Interface interface; From fe0014625084415cd950aea4566676085ee69371 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 08:46:23 -0700 Subject: [PATCH 007/169] Revise F Prime protocol unit tests --- .../test/ut/DeframingTester.cpp | 44 ++++++------ .../test/ut/DeframingTester.hpp | 21 +++--- Svc/FramingProtocol/test/ut/main.cpp | 71 +++++++++++++++++++ 3 files changed, 100 insertions(+), 36 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index c6e246f1ff..1fb8ac2d81 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -4,6 +4,7 @@ // \brief cpp file for DeframingTester class // ====================================================================== +#include "Fw/Types/SerialBuffer.hpp" #include "STest/Pick/Pick.hpp" #include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" #include "gtest/gtest.h" @@ -20,6 +21,7 @@ namespace Svc { circularBuffer(this->cbStorage, cbStoreSize), interface(*this) { + this->fprimeDeframing.setup(this->interface); memset(this->bufferStorage, 0, sizeof this->bufferStorage); memset(this->cbStorage, 0, cbStoreSize); } @@ -30,39 +32,33 @@ namespace Svc { delete[](this->cbStorage); } -#if 0 // ---------------------------------------------------------------------- // Public member functions // ---------------------------------------------------------------------- + DeframingProtocol::DeframingStatus DeframingTester :: + deframe(U32& needed) + { + return this->fprimeDeframing.deframe(this->circularBuffer, needed); + } + void DeframingTester :: - check() + serializeTokenType(FpFrameHeader::TokenType v) { - this->fprimeDeframing.frame( - this->data, - this->dataSize, - this->packetType - ); - // Check that we received a buffer - Fw::Buffer *const sentBuffer = this->interface.getSentBuffer(); - ASSERT_NE(sentBuffer, nullptr); - if (sentBuffer != nullptr) { - // Check the start word - this->checkStartWord(); - // Check the packet size - const U32 packetSize = this->getPacketSize(); - this->checkPacketSize(packetSize); - // Check the packet type - if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { - this->checkPacketType(); - } - // Check the data - this->checkData(); - // Check the hash value - this->checkHash(packetSize); + U8 buffer[sizeof v]; + Fw::SerialBuffer sb(buffer, sizeof buffer); + { + const Fw::SerializeStatus status = sb.serialize(v); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); + } + { + const Fw::SerializeStatus status = + this->circularBuffer.serialize(buffer, sizeof buffer); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); } } +#if 0 // ---------------------------------------------------------------------- // Private member functions // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index f2ccf1cec4..6d85e5230f 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -112,7 +112,15 @@ namespace Svc { // Public member functions // ---------------------------------------------------------------------- - // TODO + //! Call the deframe function of the deframer + DeframingProtocol::DeframingStatus deframe( + U32& needed //!< The number of bytes needed (output) + ); + + //! Serialize a value of token type into the circular buffer + void serializeTokenType( + FpFrameHeader::TokenType v //!< The value + ); #if 0 // ---------------------------------------------------------------------- @@ -150,17 +158,6 @@ namespace Svc { // Private member variables // ---------------------------------------------------------------------- -#if 0 - //! The data to frame - U8 data[MAX_DATA_SIZE]; - - //! The data size in bytes - const U32 dataSize; - - //! The packet type - Fw::ComPacket::ComPacketType packetType; -#endif - //! Storage for the buffer U8 bufferStorage[MAX_BUFFER_SIZE]; diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index 2f00071891..7e103b0866 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -1,3 +1,5 @@ +#include + #include "gtest/gtest.h" #include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" #include "Svc/FramingProtocol/test/ut/FramingTester.hpp" @@ -7,6 +9,75 @@ // Tests // ---------------------------------------------------------------------- +TEST(Deframing, IncompleteHeader) { + Svc::DeframingTester tester; + // Start word + tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); + U32 needed = 0; + const Svc::DeframingProtocol::DeframingStatus status = + tester.deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_MORE_NEEDED); +} + +TEST(Deframing, InvalidStartWord) { + Svc::DeframingTester tester; + // Start word + tester.serializeTokenType(Svc::FpFrameHeader::START_WORD + 1); + // Packet size + tester.serializeTokenType(0); + U32 needed = 0; + const Svc::DeframingProtocol::DeframingStatus status = + tester.deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_INVALID_FORMAT); +} + +TEST(Deframing, InvalidSizeIntegerOverflow) { + Svc::DeframingTester tester; + // Start word + tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); + // Packet size + const U32 maxU32 = std::numeric_limits::max(); + const U32 maxSize = maxU32 - (Svc::FpFrameHeader::SIZE + HASH_DIGEST_LENGTH); + // Make size too big + tester.serializeTokenType(maxSize + 1); + U32 needed = 0; + const Svc::DeframingProtocol::DeframingStatus status = + tester.deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_INVALID_SIZE); +} + +TEST(Deframing, InvalidSizeBufferOverflow) { + const Svc::FpFrameHeader::TokenType packetSize = 10; + const U32 frameSize = + Svc::FpFrameHeader::SIZE + packetSize + HASH_DIGEST_LENGTH; + // Make the circular buffer too small to hold the frame + Svc::DeframingTester tester(frameSize - 1); + // Start word + tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); + // Packet size + tester.serializeTokenType(packetSize); + U32 needed = 0; + const Svc::DeframingProtocol::DeframingStatus status = + tester.deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_INVALID_SIZE); +} + +TEST(Deframing, IncompleteFrame) { + const Svc::FpFrameHeader::TokenType packetSize = 1; + Svc::DeframingTester tester; + // Start word + tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); + // Packet size + tester.serializeTokenType(packetSize); + U32 needed = 0; + const Svc::DeframingProtocol::DeframingStatus status = + tester.deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_MORE_NEEDED); + const U32 expectedFrameSize = + Svc::FpFrameHeader::SIZE + packetSize + HASH_DIGEST_LENGTH; + ASSERT_EQ(needed, expectedFrameSize); +} + TEST(Framing, CommandPacket) { Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); From 9722c862687c68aeb3dc1f16e6bf502ba4d71769 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 09:09:15 -0700 Subject: [PATCH 008/169] Revise deframing protocol unit tests --- .../test/ut/DeframingTester.cpp | 100 ++---------------- .../test/ut/DeframingTester.hpp | 44 +------- 2 files changed, 15 insertions(+), 129 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 1fb8ac2d81..4c208ce21b 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -58,98 +58,18 @@ namespace Svc { } } -#if 0 - // ---------------------------------------------------------------------- - // Private member functions - // ---------------------------------------------------------------------- - - FpFrameHeader::TokenType DeframingTester :: - getPacketSize() - { - FpFrameHeader::TokenType packetSize = 0; - Fw::SerialBuffer sb( - &this->bufferStorage[PACKET_SIZE_OFFSET], - sizeof packetSize - ); - sb.fill(); - const Fw::SerializeStatus status = sb.deserialize(packetSize); - FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); - return packetSize; - } - - void DeframingTester :: - checkPacketSize(FpFrameHeader::TokenType packetSize) - { - U32 expectedPacketSize = this->dataSize; - if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { - // Packet type is stored in header - expectedPacketSize += sizeof(SerialPacketType); - } - ASSERT_EQ(packetSize, expectedPacketSize); - } - - void DeframingTester :: - checkPacketType() - { - SerialPacketType serialPacketType = 0; - Fw::SerialBuffer sb( - &this->bufferStorage[PACKET_TYPE_OFFSET], - sizeof serialPacketType - ); - sb.fill(); - const Fw::SerializeStatus status = sb.deserialize(serialPacketType); - FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); - typedef Fw::ComPacket::ComPacketType PacketType; - const PacketType pt = static_cast(serialPacketType); - ASSERT_EQ(pt, this->packetType); - } - - void DeframingTester :: - checkStartWord() - { - FpFrameHeader::TokenType startWord = 0; - Fw::SerialBuffer sb( - &this->bufferStorage[START_WORD_OFFSET], - sizeof startWord - ); - sb.fill(); - const Fw::SerializeStatus status = sb.deserialize(startWord); - FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); - ASSERT_EQ(startWord, FpFrameHeader::START_WORD); - } - - void DeframingTester :: - checkData() - { - U32 dataOffset = PACKET_TYPE_OFFSET; - if (this->packetType != Fw::ComPacket::FW_PACKET_UNKNOWN) { - // Packet type is stored in header - dataOffset += sizeof(SerialPacketType); - } - const I32 result = memcmp( - this->data, - &this->bufferStorage[dataOffset], - this->dataSize - ); - ASSERT_EQ(result, 0); - } - void DeframingTester :: - checkHash(FpFrameHeader::TokenType packetSize) + serializeRandomPacket(U32 packetSize) { - Utils::Hash hash; - Utils::HashBuffer hashBuffer; - const U32 dataSize = FpFrameHeader::SIZE + packetSize; - hash.update(this->bufferStorage, dataSize); - hash.final(hashBuffer); - const U8 *const hashAddr = hashBuffer.getBuffAddr(); - const I32 result = memcmp( - &this->bufferStorage[dataSize], - hashAddr, - HASH_DIGEST_LENGTH - ); - ASSERT_EQ(result, 0); + FW_ASSERT(packetSize <= MAX_PACKET_SIZE, packetSize, MAX_PACKET_SIZE); + // Start word + this->serializeTokenType(Svc::FpFrameHeader::START_WORD); + // Packet size + this->serializeTokenType(packetSize); + // Packet data + // TODO + // Hash value + // TODO } -#endif } diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index 6d85e5230f..b5afce5b52 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -22,28 +22,19 @@ namespace Svc { // Constants and types // ---------------------------------------------------------------------- -#if 0 - //! The serialized packet type - typedef I32 SerialPacketType; -#endif - //! Constants enum Constants { //! The maximum buffer size MAX_BUFFER_SIZE = 1024, //! The maximum allowed packet size - MAX_DATA_SIZE = MAX_BUFFER_SIZE - + MAX_PACKET_SIZE = MAX_BUFFER_SIZE - sizeof FpFrameHeader::START_WORD - HASH_DIGEST_LENGTH, -#if 0 //! The offset of the start word in an F Prime protocol frame START_WORD_OFFSET = 0, //! The offset of the packet size in an F Prime protocol frame PACKET_SIZE_OFFSET = START_WORD_OFFSET + - sizeof FpFrameHeader::START_WORD, - //! The offset of the packet type in an F Prime protocol frame - PACKET_TYPE_OFFSET = FpFrameHeader::SIZE, -#endif + sizeof FpFrameHeader::START_WORD, }; //! The deframing protocol interface @@ -122,35 +113,10 @@ namespace Svc { FpFrameHeader::TokenType v //!< The value ); -#if 0 - // ---------------------------------------------------------------------- - // Private member functions - // ---------------------------------------------------------------------- - - private: - - //! Get the packet size from the buffer - FpFrameHeader::TokenType getPacketSize(); - - //! Check the packet size in the buffer - void checkPacketSize( - FpFrameHeader::TokenType packetSize //!< The packet size - ); - - //! Check the packet type in the buffer - void checkPacketType(); - - //! Check the start word in the buffer - void checkStartWord(); - - //! Check the data in the buffer - void checkData(); - - //! Check the hash value in the buffer - void checkHash( - FpFrameHeader::TokenType packetSize //!< The packet size + //! Serialize a random packet into the circular buffer + void serializeRandomPacket( + U32 packetSize //!< The packet size ); -#endif private: From c499df08d947a0289afa0530d10672bf9044898c Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 09:58:19 -0700 Subject: [PATCH 009/169] Revise deframing tester --- .../test/ut/DeframingTester.cpp | 63 ++++++++++++++++--- .../test/ut/DeframingTester.hpp | 22 +++++-- 2 files changed, 72 insertions(+), 13 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 4c208ce21b..7c3cfb041d 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -4,9 +4,12 @@ // \brief cpp file for DeframingTester class // ====================================================================== +#include + #include "Fw/Types/SerialBuffer.hpp" #include "STest/Pick/Pick.hpp" #include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" +#include "Utils/Hash/Hash.hpp" #include "gtest/gtest.h" namespace Svc { @@ -17,12 +20,14 @@ namespace Svc { DeframingTester :: DeframingTester(U32 cbStoreSize) : + frameSize(0), cbStorage(new U8[cbStoreSize]), circularBuffer(this->cbStorage, cbStoreSize), interface(*this) { this->fprimeDeframing.setup(this->interface); memset(this->bufferStorage, 0, sizeof this->bufferStorage); + memset(this->frameData, 0, sizeof this->frameData); memset(this->cbStorage, 0, cbStoreSize); } @@ -58,18 +63,58 @@ namespace Svc { } } - void DeframingTester :: - serializeRandomPacket(U32 packetSize) + Fw::ByteArray DeframingTester :: + constructRandomFrame(U32 packetSize) { FW_ASSERT(packetSize <= MAX_PACKET_SIZE, packetSize, MAX_PACKET_SIZE); - // Start word - this->serializeTokenType(Svc::FpFrameHeader::START_WORD); - // Packet size - this->serializeTokenType(packetSize); - // Packet data - // TODO - // Hash value + Fw::SerialBuffer sb(this->frameData, sizeof this->frameData); + Fw::SerializeStatus status = Fw::FW_SERIALIZE_OK; + // Serialize the start word + status = sb.serialize(Svc::FpFrameHeader::START_WORD); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); + // Serialize the packet size + status = sb.serialize(static_cast(packetSize)); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); + // Construct the packet data + for (U32 i = 0; i < packetSize; ++i) { + const U8 byte = static_cast(STest::Pick::lowerUpper(0, 0xFF)); + status = sb.serialize(byte); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); + } + const U32 buffLength = sb.getBuffLength(); + const U32 dataSize = FpFrameHeader::SIZE + packetSize; + FW_ASSERT(buffLength == dataSize, buffLength, dataSize); + // Compute the hash value + Utils::Hash hash; + Utils::HashBuffer hashBuffer; + hash.init(); + hash.update(&this->frameData, dataSize); + hash.final(hashBuffer); + // Copy the hash value into place + const U8 *const buffAddr = hashBuffer.getBuffAddr(); + this->frameSize = dataSize + HASH_DIGEST_LENGTH; + FW_ASSERT(this->frameSize <= MAX_FRAME_SIZE); + memcpy(&this->frameData[dataSize], buffAddr, HASH_DIGEST_LENGTH); + // Return the byte array + return Fw::ByteArray(this->frameData, this->frameSize); + } + + void DeframingTester :: + pushFrameOntoCB(Fw::ByteArray frame) + { // TODO +#if 0 + // Clear the circular buffer + this->circularBuffer.rotate(this->circularBuffer.get_allocated_size()); + // Serialize the hash value + { + const U8 *const buffAddr = hashBuffer.getBuffAddr(); + const Fw::SerializeStatus status = + this->circularBuffer.serialize(buffAddr, HASH_DIGEST_LENGTH); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); + } +#endif + } } diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index b5afce5b52..c5e1ce173e 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -5,6 +5,7 @@ // ====================================================================== #include "Fw/Types/Assert.hpp" +#include "Fw/Types/ByteArray.hpp" #include "Fw/Types/SerialBuffer.hpp" #include "Svc/FramingProtocol/FprimeProtocol.hpp" #include "Svc/FramingProtocol/DeframingProtocol.hpp" @@ -26,10 +27,11 @@ namespace Svc { enum Constants { //! The maximum buffer size MAX_BUFFER_SIZE = 1024, + //! The maximum frame size + MAX_FRAME_SIZE = MAX_BUFFER_SIZE, //! The maximum allowed packet size MAX_PACKET_SIZE = MAX_BUFFER_SIZE - - sizeof FpFrameHeader::START_WORD - - HASH_DIGEST_LENGTH, + FpFrameHeader::SIZE - HASH_DIGEST_LENGTH, //! The offset of the start word in an F Prime protocol frame START_WORD_OFFSET = 0, //! The offset of the packet size in an F Prime protocol frame @@ -113,11 +115,17 @@ namespace Svc { FpFrameHeader::TokenType v //!< The value ); - //! Serialize a random packet into the circular buffer - void serializeRandomPacket( + //! Construct a random frame + //! \return An array pointing to frame data owned by DeframingTester. + Fw::ByteArray constructRandomFrame( U32 packetSize //!< The packet size ); + //! Push a frame onto the circular buffer + void pushFrameOntoCB( + Fw::ByteArray frame //!< The frame + ); + private: // ---------------------------------------------------------------------- @@ -127,6 +135,12 @@ namespace Svc { //! Storage for the buffer U8 bufferStorage[MAX_BUFFER_SIZE]; + //! The frame data + U8 frameData[MAX_FRAME_SIZE]; + + //! The frame size + U32 frameSize; + //! Storage for the circular buffer U8* cbStorage; From 4e5993069b7519ff238be94325ec8e68956857cf Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 12:58:20 -0700 Subject: [PATCH 010/169] Revise deframing unit tests --- Svc/FramingProtocol/test/ut/DeframingTester.cpp | 16 +++------------- 1 file changed, 3 insertions(+), 13 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 7c3cfb041d..428ad8ed38 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -102,19 +102,9 @@ namespace Svc { void DeframingTester :: pushFrameOntoCB(Fw::ByteArray frame) { - // TODO -#if 0 - // Clear the circular buffer - this->circularBuffer.rotate(this->circularBuffer.get_allocated_size()); - // Serialize the hash value - { - const U8 *const buffAddr = hashBuffer.getBuffAddr(); - const Fw::SerializeStatus status = - this->circularBuffer.serialize(buffAddr, HASH_DIGEST_LENGTH); - FW_ASSERT(status == Fw::FW_SERIALIZE_OK); - } -#endif - + const Fw::SerializeStatus status = + this->circularBuffer.serialize(frame.bytes, frame.size); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK); } } From 5d5a1e7d5daae09848efb1f1aac1f09d98029232 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 13:09:54 -0700 Subject: [PATCH 011/169] Revise deframing tester --- Svc/FramingProtocol/test/ut/DeframingTester.hpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index c5e1ce173e..10655476c0 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -25,12 +25,10 @@ namespace Svc { //! Constants enum Constants { - //! The maximum buffer size - MAX_BUFFER_SIZE = 1024, //! The maximum frame size - MAX_FRAME_SIZE = MAX_BUFFER_SIZE, + MAX_FRAME_SIZE = 1024, //! The maximum allowed packet size - MAX_PACKET_SIZE = MAX_BUFFER_SIZE - + MAX_PACKET_SIZE = MAX_FRAME_SIZE - FpFrameHeader::SIZE - HASH_DIGEST_LENGTH, //! The offset of the start word in an F Prime protocol frame START_WORD_OFFSET = 0, @@ -60,7 +58,7 @@ namespace Svc { //! Allocate the buffer Fw::Buffer allocate(const U32 size) { - FW_ASSERT(size <= MAX_BUFFER_SIZE); + FW_ASSERT(size <= MAX_FRAME_SIZE); Fw::Buffer buffer(this->deframingTester.bufferStorage, size); return buffer; } @@ -93,7 +91,7 @@ namespace Svc { //! Construct a DeframingTester DeframingTester( - U32 cbStoreSize = MAX_BUFFER_SIZE //!< The circular buffer store size + U32 cbStoreSize = MAX_FRAME_SIZE //!< The circular buffer store size ); //! Destroy a DeframingTester @@ -133,7 +131,7 @@ namespace Svc { // ---------------------------------------------------------------------- //! Storage for the buffer - U8 bufferStorage[MAX_BUFFER_SIZE]; + U8 bufferStorage[MAX_FRAME_SIZE]; //! The frame data U8 frameData[MAX_FRAME_SIZE]; From 46546dc01c3afb8f97e88e408daac9570c05164c Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 13:21:27 -0700 Subject: [PATCH 012/169] Revise F Prime protocol unit tests --- Svc/FramingProtocol/test/ut/DeframingTester.hpp | 2 +- Svc/FramingProtocol/test/ut/FramingTester.hpp | 4 ++-- Svc/FramingProtocol/test/ut/main.cpp | 11 +++++++++++ 3 files changed, 14 insertions(+), 3 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index 10655476c0..f55ba7e090 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -17,7 +17,7 @@ namespace Svc { //! A harness for checking deframing class DeframingTester { - private: + public: // ---------------------------------------------------------------------- // Constants and types diff --git a/Svc/FramingProtocol/test/ut/FramingTester.hpp b/Svc/FramingProtocol/test/ut/FramingTester.hpp index 28867ba3ed..99215c74ec 100644 --- a/Svc/FramingProtocol/test/ut/FramingTester.hpp +++ b/Svc/FramingProtocol/test/ut/FramingTester.hpp @@ -30,7 +30,7 @@ namespace Svc { MAX_BUFFER_SIZE = 1024, //! The maximum allowed data size MAX_DATA_SIZE = MAX_BUFFER_SIZE - - sizeof FpFrameHeader::START_WORD - + FpFrameHeader::SIZE - sizeof(SerialPacketType) - HASH_DIGEST_LENGTH, //! The offset of the start word in an F Prime protocol frame @@ -63,7 +63,7 @@ namespace Svc { //! Allocate the buffer Fw::Buffer allocate(const U32 size) { - FW_ASSERT(size <= MAX_BUFFER_SIZE); + FW_ASSERT(size <= MAX_BUFFER_SIZE, size, MAX_BUFFER_SIZE); Fw::Buffer buffer(this->framingTester.bufferStorage, size); return buffer; } diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index 7e103b0866..f9ec7bff44 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -3,6 +3,7 @@ #include "gtest/gtest.h" #include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" #include "Svc/FramingProtocol/test/ut/FramingTester.hpp" +#include "STest/Pick/Pick.hpp" #include "STest/Random/Random.hpp" // ---------------------------------------------------------------------- @@ -78,6 +79,16 @@ TEST(Deframing, IncompleteFrame) { ASSERT_EQ(needed, expectedFrameSize); } +TEST(Deframing, RandomPacketSize) { + Svc::DeframingTester tester; + const U32 packetSize = STest::Pick::lowerUpper( + 0, + Svc::DeframingTester::MAX_PACKET_SIZE + ); + const Fw::ByteArray frame = tester.constructRandomFrame(packetSize); + (void) frame; +} + TEST(Framing, CommandPacket) { Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); From 6dae68894a99a4e78bdd4906cb92c852cb22ccad Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 13:43:09 -0700 Subject: [PATCH 013/169] Revise deframing tester --- Svc/FramingProtocol/test/ut/DeframingTester.cpp | 6 ++++++ Svc/FramingProtocol/test/ut/DeframingTester.hpp | 4 ++++ Svc/FramingProtocol/test/ut/main.cpp | 9 ++++++++- 3 files changed, 18 insertions(+), 1 deletion(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 428ad8ed38..2ed3905b40 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -107,4 +107,10 @@ namespace Svc { FW_ASSERT(status == Fw::FW_SERIALIZE_OK); } + Fw::ByteArray DeframingTester :: + getFrame() + { + return Fw::ByteArray(this->frameData, this->frameSize); + } + } diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index f55ba7e090..c643283013 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -124,6 +124,10 @@ namespace Svc { Fw::ByteArray frame //!< The frame ); + //! Get the frame + //! \return The frame + Fw::ByteArray getFrame(); + private: // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index f9ec7bff44..23824117e8 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -61,6 +61,7 @@ TEST(Deframing, InvalidSizeBufferOverflow) { const Svc::DeframingProtocol::DeframingStatus status = tester.deframe(needed); ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_INVALID_SIZE); + ASSERT_EQ(needed, frameSize); } TEST(Deframing, IncompleteFrame) { @@ -86,7 +87,13 @@ TEST(Deframing, RandomPacketSize) { Svc::DeframingTester::MAX_PACKET_SIZE ); const Fw::ByteArray frame = tester.constructRandomFrame(packetSize); - (void) frame; + tester.pushFrameOntoCB(frame); + U32 needed; + const Svc::DeframingProtocol::DeframingStatus status = + tester.deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_STATUS_SUCCESS); + ASSERT_EQ(needed, frame.size); + // TODO: Check packet data } TEST(Framing, CommandPacket) { From b2c551e93723e2bdcc801da80d6d63432174425c Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 14:01:45 -0700 Subject: [PATCH 014/169] Revise deframing unit tests --- .../test/ut/DeframingTester.cpp | 24 +++++++++++++++++++ .../test/ut/DeframingTester.hpp | 19 ++++++++------- Svc/FramingProtocol/test/ut/main.cpp | 4 ++-- 3 files changed, 37 insertions(+), 10 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 2ed3905b40..6c99eb6392 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -113,4 +113,28 @@ namespace Svc { return Fw::ByteArray(this->frameData, this->frameSize); } + void DeframingTester :: + checkPacketData() + { + FW_ASSERT( + this->frameSize <= MAX_FRAME_SIZE, + this->frameSize, + MAX_FRAME_SIZE + ); + FW_ASSERT( + this->frameSize >= NON_PACKET_DATA_SIZE, + this->frameSize, + NON_PACKET_DATA_SIZE + ); + const U32 packetSize = this->frameSize - NON_PACKET_DATA_SIZE; + Fw::Buffer buffer = this->interface.getRoutedBuffer(); + ASSERT_EQ(buffer.getSize(), packetSize); + const int result = memcmp( + &this->frameData[FpFrameHeader::SIZE], + buffer.getData(), + packetSize + ); + ASSERT_EQ(result, 0); + } + } diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index c643283013..3deea0668a 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -27,9 +27,10 @@ namespace Svc { enum Constants { //! The maximum frame size MAX_FRAME_SIZE = 1024, + //! The size of non-packet data in a frame + NON_PACKET_DATA_SIZE = FpFrameHeader::SIZE + HASH_DIGEST_LENGTH, //! The maximum allowed packet size - MAX_PACKET_SIZE = MAX_FRAME_SIZE - - FpFrameHeader::SIZE - HASH_DIGEST_LENGTH, + MAX_PACKET_SIZE = MAX_FRAME_SIZE - NON_PACKET_DATA_SIZE, //! The offset of the start word in an F Prime protocol frame START_WORD_OFFSET = 0, //! The offset of the packet size in an F Prime protocol frame @@ -48,8 +49,7 @@ namespace Svc { Interface( DeframingTester& deframingTester //!< The enclosing DeframingTester ) : - deframingTester(deframingTester), - routedBuffer(nullptr) + deframingTester(deframingTester) { } @@ -65,11 +65,11 @@ namespace Svc { //! Route the buffer void route(Fw::Buffer& data) { - this->routedBuffer = &data; + this->routedBuffer = data; } //! Get the routed buffer - Fw::Buffer *getRoutedBuffer() { + Fw::Buffer getRoutedBuffer() { return this->routedBuffer; } @@ -79,7 +79,7 @@ namespace Svc { DeframingTester& deframingTester; //! The routed buffer - Fw::Buffer *routedBuffer; + Fw::Buffer routedBuffer; }; @@ -124,10 +124,13 @@ namespace Svc { Fw::ByteArray frame //!< The frame ); - //! Get the frame + //! Get the stored frame //! \return The frame Fw::ByteArray getFrame(); + //! Check the packet data + void checkPacketData(); + private: // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index 23824117e8..828181b801 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -80,7 +80,7 @@ TEST(Deframing, IncompleteFrame) { ASSERT_EQ(needed, expectedFrameSize); } -TEST(Deframing, RandomPacketSize) { +TEST(Deframing, FixedPacketSize) { Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -93,7 +93,7 @@ TEST(Deframing, RandomPacketSize) { tester.deframe(needed); ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_STATUS_SUCCESS); ASSERT_EQ(needed, frame.size); - // TODO: Check packet data + tester.checkPacketData(); } TEST(Framing, CommandPacket) { From 38b07fd7c0f57f35ffed598ddf1d4f558b53e9e4 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 14:23:51 -0700 Subject: [PATCH 015/169] Revise deframing protocol tests --- Svc/FramingProtocol/test/ut/DeframingTester.cpp | 13 +++++++++++++ Svc/FramingProtocol/test/ut/DeframingTester.hpp | 6 ++++++ Svc/FramingProtocol/test/ut/main.cpp | 13 ++++--------- 3 files changed, 23 insertions(+), 9 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 6c99eb6392..35d15b3ce9 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -137,4 +137,17 @@ namespace Svc { ASSERT_EQ(result, 0); } + void DeframingTester :: + testNominalDeframing(U32 packetSize) + { + const Fw::ByteArray frame = this->constructRandomFrame(packetSize); + this->pushFrameOntoCB(frame); + U32 needed; + const Svc::DeframingProtocol::DeframingStatus status = + this->deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_STATUS_SUCCESS); + ASSERT_EQ(needed, frame.size); + this->checkPacketData(); + } + } diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index 3deea0668a..bbc49d4957 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -131,6 +131,12 @@ namespace Svc { //! Check the packet data void checkPacketData(); + //! Test nominal deframing with a valid frame containing random + //! packet data + void testNominalDeframing( + U32 packetSize //!< The packet size + ); + private: // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index 828181b801..f2e4c861d4 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -72,28 +72,23 @@ TEST(Deframing, IncompleteFrame) { // Packet size tester.serializeTokenType(packetSize); U32 needed = 0; + // Deframe const Svc::DeframingProtocol::DeframingStatus status = tester.deframe(needed); + // Check results ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_MORE_NEEDED); const U32 expectedFrameSize = Svc::FpFrameHeader::SIZE + packetSize + HASH_DIGEST_LENGTH; ASSERT_EQ(needed, expectedFrameSize); } -TEST(Deframing, FixedPacketSize) { +TEST(Deframing, RandomPacketSize) { Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, Svc::DeframingTester::MAX_PACKET_SIZE ); - const Fw::ByteArray frame = tester.constructRandomFrame(packetSize); - tester.pushFrameOntoCB(frame); - U32 needed; - const Svc::DeframingProtocol::DeframingStatus status = - tester.deframe(needed); - ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_STATUS_SUCCESS); - ASSERT_EQ(needed, frame.size); - tester.checkPacketData(); + tester.testNominalDeframing(packetSize); } TEST(Framing, CommandPacket) { From da79cb0a9e48693be1992a9b75335fe915249a36 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 15:08:44 -0700 Subject: [PATCH 016/169] Add deframing protocol unit tests --- Svc/FramingProtocol/test/ut/main.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index f2e4c861d4..e47be098d1 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -82,6 +82,12 @@ TEST(Deframing, IncompleteFrame) { ASSERT_EQ(needed, expectedFrameSize); } +TEST(Deframing, ZeroPacketSize) { + Svc::DeframingTester tester; + const U32 packetSize = 0; + tester.testNominalDeframing(packetSize); +} + TEST(Deframing, RandomPacketSize) { Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( @@ -91,6 +97,12 @@ TEST(Deframing, RandomPacketSize) { tester.testNominalDeframing(packetSize); } +TEST(Deframing, MaxPacketSize) { + Svc::DeframingTester tester; + const U32 packetSize = Svc::DeframingTester::MAX_PACKET_SIZE; + tester.testNominalDeframing(packetSize); +} + TEST(Framing, CommandPacket) { Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); From 9e6a0c9301bb39eeda821d81c5e0ff5e15218fc2 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 15:18:45 -0700 Subject: [PATCH 017/169] Revise deframing protocol unit tests --- Svc/FramingProtocol/test/ut/DeframingTester.cpp | 13 +++++++++++++ Svc/FramingProtocol/test/ut/DeframingTester.hpp | 5 +++++ Svc/FramingProtocol/test/ut/main.cpp | 9 +++++++++ 3 files changed, 27 insertions(+) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index 35d15b3ce9..f194e0ce15 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -150,4 +150,17 @@ namespace Svc { this->checkPacketData(); } + void DeframingTester :: + testBadChecksum(U32 packetSize) + { + const Fw::ByteArray frame = this->constructRandomFrame(packetSize); + const U32 hashOffset = FpFrameHeader::SIZE + packetSize; + ++frame.bytes[hashOffset]; + this->pushFrameOntoCB(frame); + U32 needed; + const Svc::DeframingProtocol::DeframingStatus status = + this->deframe(needed); + ASSERT_EQ(status, Svc::DeframingProtocol::DEFRAMING_INVALID_CHECKSUM); + } + } diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index bbc49d4957..d5bb350090 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -137,6 +137,11 @@ namespace Svc { U32 packetSize //!< The packet size ); + //! Test deframing with a frame containing a bad checksum + void testBadChecksum( + U32 packetSize //!< The packet size + ); + private: // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index e47be098d1..7350610c37 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -103,6 +103,15 @@ TEST(Deframing, MaxPacketSize) { tester.testNominalDeframing(packetSize); } +TEST(Deframing, BadChecksum) { + Svc::DeframingTester tester; + const U32 packetSize = STest::Pick::lowerUpper( + 0, + Svc::DeframingTester::MAX_PACKET_SIZE + ); + tester.testBadChecksum(packetSize); +} + TEST(Framing, CommandPacket) { Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); From 06622bf86957797e444d28703e12088806481c45 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 15:42:49 -0700 Subject: [PATCH 018/169] Add comments to tests --- Svc/FramingProtocol/test/ut/main.cpp | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index 7350610c37..d692c30109 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -1,16 +1,18 @@ #include -#include "gtest/gtest.h" -#include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" -#include "Svc/FramingProtocol/test/ut/FramingTester.hpp" +#include "Fw/Test/UnitTest.hpp" #include "STest/Pick/Pick.hpp" #include "STest/Random/Random.hpp" +#include "Svc/FramingProtocol/test/ut/DeframingTester.hpp" +#include "Svc/FramingProtocol/test/ut/FramingTester.hpp" +#include "gtest/gtest.h" // ---------------------------------------------------------------------- // Tests // ---------------------------------------------------------------------- TEST(Deframing, IncompleteHeader) { + COMMENT("Apply deframing to a frame with an incomplete header"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); @@ -21,6 +23,7 @@ TEST(Deframing, IncompleteHeader) { } TEST(Deframing, InvalidStartWord) { + COMMENT("Apply deframing to a frame with an invalid start word"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD + 1); @@ -33,6 +36,7 @@ TEST(Deframing, InvalidStartWord) { } TEST(Deframing, InvalidSizeIntegerOverflow) { + COMMENT("Apply deframing to a frame with an invalid packet size due to integer overflow"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); @@ -48,6 +52,7 @@ TEST(Deframing, InvalidSizeIntegerOverflow) { } TEST(Deframing, InvalidSizeBufferOverflow) { + COMMENT("Apply deframing to a frame with an invalid packet size due to buffer overflow"); const Svc::FpFrameHeader::TokenType packetSize = 10; const U32 frameSize = Svc::FpFrameHeader::SIZE + packetSize + HASH_DIGEST_LENGTH; @@ -65,6 +70,7 @@ TEST(Deframing, InvalidSizeBufferOverflow) { } TEST(Deframing, IncompleteFrame) { + COMMENT("Apply deframing to an incomplete frame"); const Svc::FpFrameHeader::TokenType packetSize = 1; Svc::DeframingTester tester; // Start word @@ -83,12 +89,14 @@ TEST(Deframing, IncompleteFrame) { } TEST(Deframing, ZeroPacketSize) { + COMMENT("Apply deframing to a valid frame with packet size zero"); Svc::DeframingTester tester; const U32 packetSize = 0; tester.testNominalDeframing(packetSize); } TEST(Deframing, RandomPacketSize) { + COMMENT("Apply deframing to a valid frame with a random packet size"); Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -98,12 +106,14 @@ TEST(Deframing, RandomPacketSize) { } TEST(Deframing, MaxPacketSize) { + COMMENT("Apply deframing to a valid frame with maximum packet size for the test buffer"); Svc::DeframingTester tester; const U32 packetSize = Svc::DeframingTester::MAX_PACKET_SIZE; tester.testNominalDeframing(packetSize); } TEST(Deframing, BadChecksum) { + COMMENT("Apply deframing to a frame with a bad checksum"); Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -113,16 +123,19 @@ TEST(Deframing, BadChecksum) { } TEST(Framing, CommandPacket) { + COMMENT("Apply framing to a command packet"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); } TEST(Framing, FilePacket) { + COMMENT("Apply framing to a file packet"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_FILE); tester.check(); } TEST(Framing, UnknownPacket) { + COMMENT("Apply framing to a packet of unkown type"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_UNKNOWN); tester.check(); } From 04d4ea7e361b420566f423609bc5e2111996222f Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 15:48:19 -0700 Subject: [PATCH 019/169] Add requirement annotations to unit tests --- Svc/FramingProtocol/test/ut/main.cpp | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index d692c30109..51eee8c52d 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -13,6 +13,8 @@ TEST(Deframing, IncompleteHeader) { COMMENT("Apply deframing to a frame with an incomplete header"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); @@ -24,6 +26,8 @@ TEST(Deframing, IncompleteHeader) { TEST(Deframing, InvalidStartWord) { COMMENT("Apply deframing to a frame with an invalid start word"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD + 1); @@ -37,6 +41,8 @@ TEST(Deframing, InvalidStartWord) { TEST(Deframing, InvalidSizeIntegerOverflow) { COMMENT("Apply deframing to a frame with an invalid packet size due to integer overflow"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); @@ -53,6 +59,8 @@ TEST(Deframing, InvalidSizeIntegerOverflow) { TEST(Deframing, InvalidSizeBufferOverflow) { COMMENT("Apply deframing to a frame with an invalid packet size due to buffer overflow"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); const Svc::FpFrameHeader::TokenType packetSize = 10; const U32 frameSize = Svc::FpFrameHeader::SIZE + packetSize + HASH_DIGEST_LENGTH; @@ -71,6 +79,8 @@ TEST(Deframing, InvalidSizeBufferOverflow) { TEST(Deframing, IncompleteFrame) { COMMENT("Apply deframing to an incomplete frame"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); const Svc::FpFrameHeader::TokenType packetSize = 1; Svc::DeframingTester tester; // Start word @@ -90,6 +100,8 @@ TEST(Deframing, IncompleteFrame) { TEST(Deframing, ZeroPacketSize) { COMMENT("Apply deframing to a valid frame with packet size zero"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = 0; tester.testNominalDeframing(packetSize); @@ -97,6 +109,8 @@ TEST(Deframing, ZeroPacketSize) { TEST(Deframing, RandomPacketSize) { COMMENT("Apply deframing to a valid frame with a random packet size"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -107,6 +121,8 @@ TEST(Deframing, RandomPacketSize) { TEST(Deframing, MaxPacketSize) { COMMENT("Apply deframing to a valid frame with maximum packet size for the test buffer"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = Svc::DeframingTester::MAX_PACKET_SIZE; tester.testNominalDeframing(packetSize); @@ -114,6 +130,8 @@ TEST(Deframing, MaxPacketSize) { TEST(Deframing, BadChecksum) { COMMENT("Apply deframing to a frame with a bad checksum"); + REQUIREMENT("FramingProtocol-002"); + REQUIREMENT("FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -124,18 +142,24 @@ TEST(Deframing, BadChecksum) { TEST(Framing, CommandPacket) { COMMENT("Apply framing to a command packet"); + REQUIREMENT("FramingProtocol-001"); + REQUIREMENT("FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); } TEST(Framing, FilePacket) { COMMENT("Apply framing to a file packet"); + REQUIREMENT("FramingProtocol-001"); + REQUIREMENT("FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_FILE); tester.check(); } TEST(Framing, UnknownPacket) { COMMENT("Apply framing to a packet of unkown type"); + REQUIREMENT("FramingProtocol-001"); + REQUIREMENT("FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_UNKNOWN); tester.check(); } From babdaa2d9b0b4cb851a4c078be0c4db71e98c426 Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 17:41:32 -0700 Subject: [PATCH 020/169] Add assertion checks to F Prime deframing --- Svc/FramingProtocol/FprimeProtocol.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Svc/FramingProtocol/FprimeProtocol.cpp b/Svc/FramingProtocol/FprimeProtocol.cpp index 8be912cb73..1355dda18a 100644 --- a/Svc/FramingProtocol/FprimeProtocol.cpp +++ b/Svc/FramingProtocol/FprimeProtocol.cpp @@ -65,7 +65,8 @@ bool FprimeDeframing::validate(Types::CircularBuffer& ring, U32 size) { hash.init(); for (U32 i = 0; i < size; i++) { char byte; - ring.peek(byte, i); + const Fw::SerializeStatus status = ring.peek(byte, i); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); hash.update(&byte, 1); } hash.final(hashBuffer); @@ -73,7 +74,8 @@ bool FprimeDeframing::validate(Types::CircularBuffer& ring, U32 size) { for (U32 i = 0; i < HASH_DIGEST_LENGTH; i++) { char calc = static_cast(hashBuffer.getBuffAddr()[i]); char sent = 0; - ring.peek(sent, size + i); + const Fw::SerializeStatus status = ring.peek(sent, size + i); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); if (calc != sent) { return false; } @@ -127,6 +129,7 @@ DeframingProtocol::DeframingStatus FprimeDeframing::deframe(Types::CircularBuffe FW_ASSERT(buffer.getSize() >= size); buffer.setSize(size); ring.peek(buffer.getData(), size, FpFrameHeader::SIZE); + FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); m_interface->route(buffer); return DeframingProtocol::DEFRAMING_STATUS_SUCCESS; } From 1d812b4d15ec3897ddf30ddcbe82366ef96bcd1b Mon Sep 17 00:00:00 2001 From: bocchino Date: Mon, 27 Jun 2022 17:45:31 -0700 Subject: [PATCH 021/169] Remove trailing spaces --- Svc/FramingProtocol/test/ut/DeframingTester.cpp | 2 +- Svc/FramingProtocol/test/ut/DeframingTester.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.cpp b/Svc/FramingProtocol/test/ut/DeframingTester.cpp index f194e0ce15..1020a992f7 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.cpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.cpp @@ -22,7 +22,7 @@ namespace Svc { DeframingTester(U32 cbStoreSize) : frameSize(0), cbStorage(new U8[cbStoreSize]), - circularBuffer(this->cbStorage, cbStoreSize), + circularBuffer(this->cbStorage, cbStoreSize), interface(*this) { this->fprimeDeframing.setup(this->interface); diff --git a/Svc/FramingProtocol/test/ut/DeframingTester.hpp b/Svc/FramingProtocol/test/ut/DeframingTester.hpp index d5bb350090..44b17f07ab 100644 --- a/Svc/FramingProtocol/test/ut/DeframingTester.hpp +++ b/Svc/FramingProtocol/test/ut/DeframingTester.hpp @@ -150,7 +150,7 @@ namespace Svc { //! Storage for the buffer U8 bufferStorage[MAX_FRAME_SIZE]; - + //! The frame data U8 frameData[MAX_FRAME_SIZE]; From f71aa76ce3e7e3da4aea321a298a75598d4e2645 Mon Sep 17 00:00:00 2001 From: bocchino Date: Wed, 29 Jun 2022 14:25:59 -0700 Subject: [PATCH 022/169] Add Svc prefix to requirement names --- Svc/FramingProtocol/docs/sdd.md | 6 ++-- Svc/FramingProtocol/test/ut/main.cpp | 48 ++++++++++++++-------------- 2 files changed, 27 insertions(+), 27 deletions(-) diff --git a/Svc/FramingProtocol/docs/sdd.md b/Svc/FramingProtocol/docs/sdd.md index 83e1545fbb..79a6ef89ed 100644 --- a/Svc/FramingProtocol/docs/sdd.md +++ b/Svc/FramingProtocol/docs/sdd.md @@ -28,9 +28,9 @@ defined in the `FramingProtocol` library. Requirement | Description | Verification Method ----------- | ----------- | ------------------- -FramingProtocol-001 | `Svc::FramingProtocol` shall provide the interface to a protocol for wrapping data in frames for transmission to the ground|Unit test -FramingProtocol-002 | `Svc::FramingProtocol` shall provide the interface to a protocol for extracting data from frames received from the ground|Unit test -FramingProtocol-003 | `Svc::FramingProtocol` shall implement the framing and deframing protocols used by the F Prime GDS|Unit test +Svc-FramingProtocol-001 | `Svc::FramingProtocol` shall provide the interface to a protocol for wrapping data in frames for transmission to the ground|Unit test +Svc-FramingProtocol-002 | `Svc::FramingProtocol` shall provide the interface to a protocol for extracting data from frames received from the ground|Unit test +Svc-FramingProtocol-003 | `Svc::FramingProtocol` shall implement the framing and deframing protocols used by the F Prime GDS|Unit test ## 2. Using the Interface diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index 51eee8c52d..d42a6869bb 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -13,8 +13,8 @@ TEST(Deframing, IncompleteHeader) { COMMENT("Apply deframing to a frame with an incomplete header"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); @@ -26,8 +26,8 @@ TEST(Deframing, IncompleteHeader) { TEST(Deframing, InvalidStartWord) { COMMENT("Apply deframing to a frame with an invalid start word"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD + 1); @@ -41,8 +41,8 @@ TEST(Deframing, InvalidStartWord) { TEST(Deframing, InvalidSizeIntegerOverflow) { COMMENT("Apply deframing to a frame with an invalid packet size due to integer overflow"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; // Start word tester.serializeTokenType(Svc::FpFrameHeader::START_WORD); @@ -59,8 +59,8 @@ TEST(Deframing, InvalidSizeIntegerOverflow) { TEST(Deframing, InvalidSizeBufferOverflow) { COMMENT("Apply deframing to a frame with an invalid packet size due to buffer overflow"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); const Svc::FpFrameHeader::TokenType packetSize = 10; const U32 frameSize = Svc::FpFrameHeader::SIZE + packetSize + HASH_DIGEST_LENGTH; @@ -79,8 +79,8 @@ TEST(Deframing, InvalidSizeBufferOverflow) { TEST(Deframing, IncompleteFrame) { COMMENT("Apply deframing to an incomplete frame"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); const Svc::FpFrameHeader::TokenType packetSize = 1; Svc::DeframingTester tester; // Start word @@ -100,8 +100,8 @@ TEST(Deframing, IncompleteFrame) { TEST(Deframing, ZeroPacketSize) { COMMENT("Apply deframing to a valid frame with packet size zero"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = 0; tester.testNominalDeframing(packetSize); @@ -109,8 +109,8 @@ TEST(Deframing, ZeroPacketSize) { TEST(Deframing, RandomPacketSize) { COMMENT("Apply deframing to a valid frame with a random packet size"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -121,8 +121,8 @@ TEST(Deframing, RandomPacketSize) { TEST(Deframing, MaxPacketSize) { COMMENT("Apply deframing to a valid frame with maximum packet size for the test buffer"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = Svc::DeframingTester::MAX_PACKET_SIZE; tester.testNominalDeframing(packetSize); @@ -130,8 +130,8 @@ TEST(Deframing, MaxPacketSize) { TEST(Deframing, BadChecksum) { COMMENT("Apply deframing to a frame with a bad checksum"); - REQUIREMENT("FramingProtocol-002"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-002"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::DeframingTester tester; const U32 packetSize = STest::Pick::lowerUpper( 0, @@ -142,24 +142,24 @@ TEST(Deframing, BadChecksum) { TEST(Framing, CommandPacket) { COMMENT("Apply framing to a command packet"); - REQUIREMENT("FramingProtocol-001"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-001"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_COMMAND); tester.check(); } TEST(Framing, FilePacket) { COMMENT("Apply framing to a file packet"); - REQUIREMENT("FramingProtocol-001"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-001"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_FILE); tester.check(); } TEST(Framing, UnknownPacket) { COMMENT("Apply framing to a packet of unkown type"); - REQUIREMENT("FramingProtocol-001"); - REQUIREMENT("FramingProtocol-003"); + REQUIREMENT("Svc-FramingProtocol-001"); + REQUIREMENT("Svc-FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_UNKNOWN); tester.check(); } From 2adea3d38a9c1f97e9da66e4cbf4d303f10cbdc8 Mon Sep 17 00:00:00 2001 From: bocchino Date: Wed, 29 Jun 2022 14:46:29 -0700 Subject: [PATCH 023/169] Fix spelling --- Svc/FramingProtocol/test/ut/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Svc/FramingProtocol/test/ut/main.cpp b/Svc/FramingProtocol/test/ut/main.cpp index d42a6869bb..a8a9f548e3 100644 --- a/Svc/FramingProtocol/test/ut/main.cpp +++ b/Svc/FramingProtocol/test/ut/main.cpp @@ -157,7 +157,7 @@ TEST(Framing, FilePacket) { } TEST(Framing, UnknownPacket) { - COMMENT("Apply framing to a packet of unkown type"); + COMMENT("Apply framing to a packet of unknown type"); REQUIREMENT("Svc-FramingProtocol-001"); REQUIREMENT("Svc-FramingProtocol-003"); Svc::FramingTester tester(Fw::ComPacket::FW_PACKET_UNKNOWN); From 20b78b5bac2e5b909d429e0c224ef6c7cf85c2b9 Mon Sep 17 00:00:00 2001 From: bocchino Date: Wed, 29 Jun 2022 17:15:10 -0700 Subject: [PATCH 024/169] Add status return check --- Svc/FramingProtocol/FprimeProtocol.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Svc/FramingProtocol/FprimeProtocol.cpp b/Svc/FramingProtocol/FprimeProtocol.cpp index 1355dda18a..666d48c2b5 100644 --- a/Svc/FramingProtocol/FprimeProtocol.cpp +++ b/Svc/FramingProtocol/FprimeProtocol.cpp @@ -128,7 +128,7 @@ DeframingProtocol::DeframingStatus FprimeDeframing::deframe(Types::CircularBuffe // That causes issues in routing; adjust size. FW_ASSERT(buffer.getSize() >= size); buffer.setSize(size); - ring.peek(buffer.getData(), size, FpFrameHeader::SIZE); + status = ring.peek(buffer.getData(), size, FpFrameHeader::SIZE); FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); m_interface->route(buffer); return DeframingProtocol::DEFRAMING_STATUS_SUCCESS; From 9837cdf4b8fd242961603f39e9e78a94d1700c70 Mon Sep 17 00:00:00 2001 From: Anthony Limiero Date: Thu, 7 Jul 2022 17:00:46 -0700 Subject: [PATCH 025/169] Cmake changes to enable custom autocoder registration --- cmake/API.cmake | 40 +++++++++++++++++++++++ cmake/target/build.cmake | 3 +- docs/UsersGuide/dev/target-integration.md | 2 +- 3 files changed, 43 insertions(+), 2 deletions(-) diff --git a/cmake/API.cmake b/cmake/API.cmake index dd89e4c3c3..e71e87bd3d 100644 --- a/cmake/API.cmake +++ b/cmake/API.cmake @@ -13,6 +13,7 @@ #### set(FPRIME_TARGET_LIST "" CACHE INTERNAL "FPRIME_TARGET_LIST: custom fprime targets" FORCE) set(FPRIME_UT_TARGET_LIST "" CACHE INTERNAL "FPRIME_UT_TARGET_LIST: custom fprime targets" FORCE) +set(FPRIME_AUTOCODER_TARGET_LIST "" CACHE INTERNAL "FPRIME_AUTOCODER_TARGET_LIST: custom fprime targets" FORCE) #### # Function `add_fprime_subdirectory`: # @@ -467,6 +468,45 @@ macro(register_fprime_target_helper TARGET_FILE_PATH TARGET_LIST) endmacro(register_fprime_target_helper) +#### +# Macro `register_fprime_autocoder`: +# +# Identical to the above `register_fprime_target` function +# +### +macro(register_fprime_autocoder TARGET_FILE_PATH) + # Normal registered targets don't run in prescan + message(STATUS "Registering custom autocoder: ${TARGET_FILE_PATH}") + if (NOT DEFINED FPRIME_PRESCAN) + register_fprime_autocoder_helper("${TARGET_FILE_PATH}" FPRIME_AUTOCODER_TARGET_LIST) + endif() +endmacro(register_fprime_autocoder) + + +#### +# Macro `register_fprime_autocoder_helper`: +# +# Helper function to do the actual registration. +# +#### +macro(register_fprime_autocoder_helper TARGET_FILE_PATH TARGET_LIST) + include("${TARGET_FILE_PATH}") + # Prevent out-of-order setups + get_property(MODULE_DETECTION_STARTED GLOBAL PROPERTY MODULE_DETECTION SET) + if (MODULE_DETECTION_STARTED) + message(FATAL_ERROR "Cannot register fprime autocoder after including subdirectories or FPrime-Code.cmake'") + endif() + # Get the target list to add this target to or use default + set(LIST_NAME FPRIME_AUTOCODER_TARGET_LIST) + if (${ARGC} GREATER 1) + set(LIST_NAME "${ARGV1}") + endif() + get_property(TARGETS GLOBAL PROPERTY "${TARGET_LIST}") + if (NOT TARGET_FILE_PATH IN_LIST TARGETS) + set_property(GLOBAL APPEND PROPERTY "${LIST_NAME}" "${TARGET_FILE_PATH}") + endif() +endmacro(register_fprime_autocoder_helper) + #### Documentation links # Next Topics: # - Setting Options: [Options](Options.md) are used to vary a CMake build. diff --git a/cmake/target/build.cmake b/cmake/target/build.cmake index 81f000bfde..03c3fa0152 100644 --- a/cmake/target/build.cmake +++ b/cmake/target/build.cmake @@ -114,7 +114,8 @@ endfunction() function(build_add_module_target MODULE TARGET SOURCES DEPENDENCIES) get_target_property(MODULE_TYPE "${MODULE}" FP_TYPE) message(STATUS "Adding ${MODULE_TYPE}: ${MODULE}") - run_ac_set("${SOURCES}" autocoder/fpp autocoder/ai_xml) + get_property(CUSTOM_AUTOCODERS GLOBAL PROPERTY FPRIME_AUTOCODER_TARGET_LIST) + run_ac_set("${SOURCES}" autocoder/fpp autocoder/ai_xml ${CUSTOM_AUTOCODERS}) resolve_dependencies(RESOLVED ${DEPENDENCIES} ${AC_DEPENDENCIES} ) build_setup_build_module("${MODULE}" "${SOURCES}" "${AC_GENERATED}" "${AC_SOURCES}" "${RESOLVED}") # Special flags applied to modules when compiling with testing enabled diff --git a/docs/UsersGuide/dev/target-integration.md b/docs/UsersGuide/dev/target-integration.md index 3823f3f347..98a4f77d19 100644 --- a/docs/UsersGuide/dev/target-integration.md +++ b/docs/UsersGuide/dev/target-integration.md @@ -11,7 +11,7 @@ globally. Module targets run on every module defining the `_register_fpr targets run on deployments defined with the `_register_fprime_deployment` calls, and global targets run once. Targets are CMake files that define three functions, one for each level, and are described below. The filename of this -CMake without the `.cmake` extension is determines the`` name. e.g. `utility.cmake` will define the `utility` +CMake without the `.cmake` extension determines the`` name. e.g. `utility.cmake` will define the `utility` target. Targets stages are defined in the following order: From a946f1d61d8d089d8d1ca7e37b6bc581d04c4c2a Mon Sep 17 00:00:00 2001 From: Anthony Limiero Date: Tue, 19 Jul 2022 17:39:09 -0700 Subject: [PATCH 026/169] Simplifies and improves CMake for custom targets and custom autocoders --- cmake/API.cmake | 64 ++++++++++++++-------------------------- cmake/FPrime.cmake | 2 ++ cmake/target/build.cmake | 2 +- 3 files changed, 25 insertions(+), 43 deletions(-) diff --git a/cmake/API.cmake b/cmake/API.cmake index e71e87bd3d..4d9cfa23e2 100644 --- a/cmake/API.cmake +++ b/cmake/API.cmake @@ -424,7 +424,8 @@ endfunction(register_fprime_ut) macro(register_fprime_target TARGET_FILE_PATH) # Normal registered targets don't run in prescan if (NOT DEFINED FPRIME_PRESCAN) - register_fprime_target_helper("${TARGET_FILE_PATH}" FPRIME_TARGET_LIST) + register_fprime_list_helper("${TARGET_FILE_PATH}" FPRIME_TARGET_LIST) + setup_global_target("${TARGET_FILE_PATH}") endif() endmacro(register_fprime_target) @@ -439,73 +440,52 @@ endmacro(register_fprime_target) macro(register_fprime_ut_target TARGET_FILE_PATH) # UT targets only allowed when testing if (BUILD_TESTING AND NOT DEFINED FPRIME_PRESCAN) - register_fprime_target_helper("${TARGET_FILE_PATH}" FPRIME_UT_TARGET_LIST) + register_fprime_list_helper("${TARGET_FILE_PATH}" FPRIME_UT_TARGET_LIST) + setup_global_target("${TARGET_FILE_PATH}") endif() endmacro(register_fprime_ut_target) #### -# Macro `register_fprime_target_helper`: +# Macro `register_fprime_list_helper`: # # Helper function to do the actual registration. Also used to side-load prescan to bypass the not-on-prescan check. #### -macro(register_fprime_target_helper TARGET_FILE_PATH TARGET_LIST) +macro(register_fprime_list_helper TARGET_FILE_PATH TARGET_LIST) include("${TARGET_FILE_PATH}") # Prevent out-of-order setups get_property(MODULE_DETECTION_STARTED GLOBAL PROPERTY MODULE_DETECTION SET) if (MODULE_DETECTION_STARTED) message(FATAL_ERROR "Cannot register fprime target after including subdirectories or FPrime-Code.cmake'") endif() - # Get the target list to add this target to or use default - set(LIST_NAME FPRIME_TARGET_LIST) - if (${ARGC} GREATER 1) - set(LIST_NAME "${ARGV1}") - endif() get_property(TARGETS GLOBAL PROPERTY "${TARGET_LIST}") if (NOT TARGET_FILE_PATH IN_LIST TARGETS) set_property(GLOBAL APPEND PROPERTY "${LIST_NAME}" "${TARGET_FILE_PATH}") - setup_global_target("${TARGET_FILE_PATH}") endif() -endmacro(register_fprime_target_helper) +endmacro(register_fprime_list_helper) #### -# Macro `register_fprime_autocoder`: -# -# Identical to the above `register_fprime_target` function +# Macro `register_fprime_build_autocoder`: # +# This function allows users to register custom autocoders into the build system. These autocoders will execute during +# the build process. An autocoder is defined in a CMake file and must do three things: +# 1. Call one of `autocoder_setup_for_individual_sources()` or `autocoder_setup_for_multiple_sources()` from file scope +# 2. Implement `_is_supported(AC_POSSIBLE_INPUT_FILE)` returning true the autocoder processes given source +# 3. Implement `_setup_autocode AC_INPUT_FILE)` to run the autocoder on files filter by item 2. +# See: [Autocoders](dev/autocoder_integration.md). +# +# This function takes in either a file path to a CMake file defining an autocoder target, or an short include path that accomplishes +# the same thing. Note: make sure the directory is on the CMake include path to use the second form. +# +# **TARGET_FILE_PATH:** include path or file path file defining above functions ### -macro(register_fprime_autocoder TARGET_FILE_PATH) +macro(register_fprime_build_autocoder TARGET_FILE_PATH) # Normal registered targets don't run in prescan message(STATUS "Registering custom autocoder: ${TARGET_FILE_PATH}") if (NOT DEFINED FPRIME_PRESCAN) - register_fprime_autocoder_helper("${TARGET_FILE_PATH}" FPRIME_AUTOCODER_TARGET_LIST) - endif() -endmacro(register_fprime_autocoder) - - -#### -# Macro `register_fprime_autocoder_helper`: -# -# Helper function to do the actual registration. -# -#### -macro(register_fprime_autocoder_helper TARGET_FILE_PATH TARGET_LIST) - include("${TARGET_FILE_PATH}") - # Prevent out-of-order setups - get_property(MODULE_DETECTION_STARTED GLOBAL PROPERTY MODULE_DETECTION SET) - if (MODULE_DETECTION_STARTED) - message(FATAL_ERROR "Cannot register fprime autocoder after including subdirectories or FPrime-Code.cmake'") - endif() - # Get the target list to add this target to or use default - set(LIST_NAME FPRIME_AUTOCODER_TARGET_LIST) - if (${ARGC} GREATER 1) - set(LIST_NAME "${ARGV1}") - endif() - get_property(TARGETS GLOBAL PROPERTY "${TARGET_LIST}") - if (NOT TARGET_FILE_PATH IN_LIST TARGETS) - set_property(GLOBAL APPEND PROPERTY "${LIST_NAME}" "${TARGET_FILE_PATH}") + register_fprime_list_helper("${TARGET_FILE_PATH}" FPRIME_AUTOCODER_TARGET_LIST) endif() -endmacro(register_fprime_autocoder_helper) +endmacro(register_fprime_build_autocoder) #### Documentation links # Next Topics: diff --git a/cmake/FPrime.cmake b/cmake/FPrime.cmake index e859782589..b389e00d7a 100644 --- a/cmake/FPrime.cmake +++ b/cmake/FPrime.cmake @@ -71,6 +71,8 @@ endif() # FPP locations must come at the front of the list, then build register_fprime_target(target/fpp_locs) register_fprime_target(target/build) +register_fprime_build_autocoder(autocoder/fpp) +register_fprime_build_autocoder(autocoder/ai_xml) register_fprime_target(target/noop) register_fprime_target(target/version) register_fprime_target(target/dict) diff --git a/cmake/target/build.cmake b/cmake/target/build.cmake index 03c3fa0152..366ba8f68f 100644 --- a/cmake/target/build.cmake +++ b/cmake/target/build.cmake @@ -115,7 +115,7 @@ function(build_add_module_target MODULE TARGET SOURCES DEPENDENCIES) get_target_property(MODULE_TYPE "${MODULE}" FP_TYPE) message(STATUS "Adding ${MODULE_TYPE}: ${MODULE}") get_property(CUSTOM_AUTOCODERS GLOBAL PROPERTY FPRIME_AUTOCODER_TARGET_LIST) - run_ac_set("${SOURCES}" autocoder/fpp autocoder/ai_xml ${CUSTOM_AUTOCODERS}) + run_ac_set("${SOURCES}" ${CUSTOM_AUTOCODERS}) resolve_dependencies(RESOLVED ${DEPENDENCIES} ${AC_DEPENDENCIES} ) build_setup_build_module("${MODULE}" "${SOURCES}" "${AC_GENERATED}" "${AC_SOURCES}" "${RESOLVED}") # Special flags applied to modules when compiling with testing enabled From e734c98987feff1988f125adcb43c158ec36da81 Mon Sep 17 00:00:00 2001 From: Anthony Limiero Date: Tue, 19 Jul 2022 18:08:28 -0700 Subject: [PATCH 027/169] Ref actually builds now... --- cmake/API.cmake | 2 +- cmake/FPrime.cmake | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/cmake/API.cmake b/cmake/API.cmake index 4d9cfa23e2..a7688192e1 100644 --- a/cmake/API.cmake +++ b/cmake/API.cmake @@ -459,7 +459,7 @@ macro(register_fprime_list_helper TARGET_FILE_PATH TARGET_LIST) endif() get_property(TARGETS GLOBAL PROPERTY "${TARGET_LIST}") if (NOT TARGET_FILE_PATH IN_LIST TARGETS) - set_property(GLOBAL APPEND PROPERTY "${LIST_NAME}" "${TARGET_FILE_PATH}") + set_property(GLOBAL APPEND PROPERTY "${TARGET_LIST}" "${TARGET_FILE_PATH}") endif() endmacro(register_fprime_list_helper) diff --git a/cmake/FPrime.cmake b/cmake/FPrime.cmake index b389e00d7a..20d493a1b1 100644 --- a/cmake/FPrime.cmake +++ b/cmake/FPrime.cmake @@ -61,9 +61,10 @@ endforeach() include_directories("${FPRIME_FRAMEWORK_PATH}") include_directories("${FPRIME_CONFIG_DIR}") -# To prescan, either we register the prescan target or we run the prescan CMake +# To prescan,register target process around safety check if (DEFINED FPRIME_PRESCAN) - register_fprime_target_helper(target/prescan FPRIME_TARGET_LIST) + register_fprime_list_helper(target/prescan FPRIME_TARGET_LIST) + setup_global_target(target/prescan) else() perform_prescan() endif() From 8027bce7b57d8bf9c8888be40686c9ef05505249 Mon Sep 17 00:00:00 2001 From: Anthony Limiero Date: Thu, 7 Jul 2022 17:01:41 -0700 Subject: [PATCH 028/169] Bug fix regarding fpp autocoder -i flag --- cmake/autocoder/fpp.cmake | 25 ++++++++++++------------- 1 file changed, 12 insertions(+), 13 deletions(-) diff --git a/cmake/autocoder/fpp.cmake b/cmake/autocoder/fpp.cmake index 81630b2195..c1312495bc 100644 --- a/cmake/autocoder/fpp.cmake +++ b/cmake/autocoder/fpp.cmake @@ -91,7 +91,7 @@ endfunction(fpp_get_framework_dependency_helper) # - GENERATED_FILES: a list of files generated for the given input sources # - MODULE_DEPENDENCIES: inter-module dependencies determined from the given input sources # - FILE_DEPENDENCIES: specific file dependencies of the given input sources -# - EXTRAS: used to publish the 'imported' file dependencies of the given input files +# - FPP_IMPORTS: The fpp model dependencies, which end up being the input to the -i flag for the fpp-to-cpp and fpp-to-xml tools # # Note: although this function is only required to set `GENERATED_FILES`, the remaining information is also set as # setting this information now will prevent a duplicated call to the tooling. @@ -142,13 +142,13 @@ function(fpp_info AC_INPUT_FILES) list(APPEND MODULE_DEPENDENCIES ${FRAMEWORK}) list(REMOVE_DUPLICATES MODULE_DEPENDENCIES) # File dependencies are any files that this depends on - set(FILE_DEPENDENCIES ${AC_INPUT_FILES} ${STDOUT}) + set(FILE_DEPENDENCIES ${AC_INPUT_FILES} ${INCLUDED}) # Should have been inherited from previous call to `get_generated_files` set(GENERATED_FILES "${GENERATED_FILES}" PARENT_SCOPE) set(MODULE_DEPENDENCIES "${MODULE_DEPENDENCIES}" PARENT_SCOPE) set(FILE_DEPENDENCIES "${FILE_DEPENDENCIES}" PARENT_SCOPE) - set(IMPORTED "${IMPORTED}" PARENT_SCOPE) + set(FPP_IMPORTS "${STDOUT}" PARENT_SCOPE) endfunction(fpp_info) @@ -165,12 +165,11 @@ function(fpp_setup_autocode AC_INPUT_FILES) message(FATAL_ERROR "fpp tools not found, please install them onto your system path") endif() fpp_info("${AC_INPUT_FILES}") - string(REGEX REPLACE ";" "," FPRIME_BUILD_LOCATIONS_SEP_FPP "${FPRIME_BUILD_LOCATIONS}") - string(REGEX REPLACE ";" "," FPP_IMPORTED_SEP "${IMPORTED}") - set(INCLUDES) - if (FPP_IMPORTED_SEP) - set(INCLUDES "-i" "${FPP_IMPORTED_SEP}") + string(REGEX REPLACE ";" "," FPP_IMPORTS_SEP "${FPP_IMPORTS}") + set(IMPORTS) + if (FPP_IMPORTS_SEP) + set(IMPORTS "-i" "${FPP_IMPORTS_SEP}") endif() # Separate the source files into the CPP and XML steps set(GENERATED_AI) @@ -187,18 +186,18 @@ function(fpp_setup_autocode AC_INPUT_FILES) if (GENERATED_AI) add_custom_command( OUTPUT ${GENERATED_AI} - COMMAND ${FPP_TO_XML} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${FILE_DEPENDENCIES} + COMMAND ${FPP_TO_XML} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${IMPORTS} ${AC_INPUT_FILES} "-p" "${FPRIME_BUILD_LOCATIONS_SEP_FPP}" - DEPENDS ${IMPORTED} ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} + DEPENDS ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} ) endif() # Add in steps for CPP generation if (GENERATED_CPP) add_custom_command( OUTPUT ${GENERATED_CPP} - COMMAND ${REMOVAL_FILE} ${FPP_TO_CPP} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${FILE_DEPENDENCIES} - "-p" "${FPRIME_BUILD_LOCATIONS_SEP_FPP},${CMAKE_BINARY_DIR}" - DEPENDS ${IMPORTED} ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} + COMMAND ${FPP_TO_CPP} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${IMPORTS} ${AC_INPUT_FILES} + "-p" "${FPRIME_BUILD_LOCATIONS_SEP_FPP},${CMAKE_BINARY_DIR}" + DEPENDS ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} ) endif() set(AUTOCODER_GENERATED ${GENERATED_AI} ${GENERATED_CPP} PARENT_SCOPE) From 9d00863f6da138377a4d1159810451b9117c15a4 Mon Sep 17 00:00:00 2001 From: Anthony Limiero Date: Tue, 19 Jul 2022 17:46:05 -0700 Subject: [PATCH 029/169] Updates CMake variable names to be suffixed with _COMMA_SEP instead of just _SEP --- cmake/autocoder/fpp.cmake | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/cmake/autocoder/fpp.cmake b/cmake/autocoder/fpp.cmake index c1312495bc..b17f79f925 100644 --- a/cmake/autocoder/fpp.cmake +++ b/cmake/autocoder/fpp.cmake @@ -165,11 +165,11 @@ function(fpp_setup_autocode AC_INPUT_FILES) message(FATAL_ERROR "fpp tools not found, please install them onto your system path") endif() fpp_info("${AC_INPUT_FILES}") - string(REGEX REPLACE ";" "," FPRIME_BUILD_LOCATIONS_SEP_FPP "${FPRIME_BUILD_LOCATIONS}") - string(REGEX REPLACE ";" "," FPP_IMPORTS_SEP "${FPP_IMPORTS}") + string(REGEX REPLACE ";" "," FPRIME_BUILD_LOCATIONS_COMMA_SEP "${FPRIME_BUILD_LOCATIONS}") + string(REGEX REPLACE ";" "," FPP_IMPORTS_COMMA_SEP "${FPP_IMPORTS}") set(IMPORTS) - if (FPP_IMPORTS_SEP) - set(IMPORTS "-i" "${FPP_IMPORTS_SEP}") + if (FPP_IMPORTS_COMMA_SEP) + set(IMPORTS "-i" "${FPP_IMPORTS_COMMA_SEP}") endif() # Separate the source files into the CPP and XML steps set(GENERATED_AI) @@ -187,7 +187,7 @@ function(fpp_setup_autocode AC_INPUT_FILES) add_custom_command( OUTPUT ${GENERATED_AI} COMMAND ${FPP_TO_XML} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${IMPORTS} ${AC_INPUT_FILES} - "-p" "${FPRIME_BUILD_LOCATIONS_SEP_FPP}" + "-p" "${FPRIME_BUILD_LOCATIONS_COMMA_SEP}" DEPENDS ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} ) endif() @@ -196,7 +196,7 @@ function(fpp_setup_autocode AC_INPUT_FILES) add_custom_command( OUTPUT ${GENERATED_CPP} COMMAND ${FPP_TO_CPP} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${IMPORTS} ${AC_INPUT_FILES} - "-p" "${FPRIME_BUILD_LOCATIONS_SEP_FPP},${CMAKE_BINARY_DIR}" + "-p" "${FPRIME_BUILD_LOCATIONS_COMMA_SEP},${CMAKE_BINARY_DIR}" DEPENDS ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} ) endif() From c1ec5bc71b5884d0e05131aa3f426194d30b3f82 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 21 Jul 2022 12:21:19 -0700 Subject: [PATCH 030/169] lestarch: adding numerical types (planned) design (#1571) * lestarch: adding numerical types (planned) design * lestarch: review comments --- docs/Design/general.md | 9 +++ docs/Design/numerical-types.md | 136 +++++++++++++++++++++++++++++++++ docs/latest.md | 11 +-- 3 files changed, 151 insertions(+), 5 deletions(-) create mode 100644 docs/Design/general.md create mode 100644 docs/Design/numerical-types.md diff --git a/docs/Design/general.md b/docs/Design/general.md new file mode 100644 index 0000000000..61f98d3006 --- /dev/null +++ b/docs/Design/general.md @@ -0,0 +1,9 @@ +# Design and Philosophy of F´ + +This section of the documentation captures the design and philosophy of F´, the F´ framework, and flight software as +viewed through F´. + + +| Table of Contents | +|------------------------------------------------| +| [Numerical Types Design](./numerical-types.md) | \ No newline at end of file diff --git a/docs/Design/numerical-types.md b/docs/Design/numerical-types.md new file mode 100644 index 0000000000..3ff26d721e --- /dev/null +++ b/docs/Design/numerical-types.md @@ -0,0 +1,136 @@ +# F´ Numerical Types + +On physical hardware, numerical types have a size in bits. The sizes of these integers are either explicitly set by the +programmer or implicitly set by the compiler. i.e. `uint32_t` is explicitly 32-bits whereas `int` is implicitly set by +the compiler. Flight software practice encourages use of explicitly sized types because there are fewer mistake made when the +programmer uses an integer of a known size. However, in-practice it is nice to also use logical types that represent +concepts in the system (e.g. size) and are set by the platform supporter to a known size. + +This document describes: fixed-width types and logical types. + +## Fixed Width Types + +In F´, fixed width types map to the standard definitions either in the C standard or in the `stdint.h` header as seen +below. Since compilers are not guaranteed to support all types (e.g. 64bits integers) these types can be turned off +by setting a configuration field to `0` in `FpConfig.hpp`. These types are by default on and users must turn off types +their compiler does not support. + + +| F´ Type | Equivalent | `FpConfig.hpp` Configuration Field | +|---------|--------------|------------------------------------| +| I8 | int8_t | n/a | +| I16 | int16_t | FW_HAS_16_BIT | +| I32 | int32_t | FW_HAS_32_BIT | +| I64 | int64_t | FW_HAS_64_BIT | +| U8 | uint8_t | n/a | +| U16 | uint16_t | FW_HAS_16_BIT | +| U32 | uint32_t | FW_HAS_32_BIT | +| U64 | uint64_t | FW_HAS_64_BIT | +| F32 | float | n/a | +| F64 | double | FW_HAS_F64 | + +Platform developers should include `stdint.h` or equivalent in their `StandardTypes.hpp` file provided alongside their +platform. If for some reason that header does not exist or does not define all types, then developers must define all +"Equivalent" definitions above. + +To print these types, users may use the standard C++ PRI macros as shown described: +[https://cplusplus.com/reference/cinttypes/](https://cplusplus.com/reference/cinttypes/). + +```c++ +U32 value = 10; +printf("My value: %" PRId32, value); // Uses string constant concatenation +``` + +## F´ Logical Integer Type Design + + +Typically, in flight software we try to use fixed-sized types wherever possible as this produces consistent results +across platforms. However, when building components for use on multiple different architectures it is nice to be able +to use logical integer types whose exact widths are determined by the platform and project instead of needing +to pick a one-size-fits-all fixed with type. For example, representing a size as an unsigned 64-bit integer is logical +on some systems that have 64-bit data widths, but will not compile on systems that do not define 64-bit integers at all +(8-bit systems often lack this data size). + +Thus, for these logical types the actual data size needs to be configured. This configuration needs to be available +from two sources: a given project, and a given platform. Platforms need to set the idea size for these types, and +projects need to be able to control these sizes when operating across multiple platforms. + +### Platform Configured Types + +Platform developers should define the following logical types in the `StandardTypes.hpp` header provided alongside +their CMake platform and toolchain files. Each must also define a compiler directive to indicate the type was defined. +If the type is not specified as seen through the compiler directive the `DefaultTypes.hpp` header will fill in a default +definition. Each also defines a format specifier for use with the `printf` family of functions. Additionally, each +defines a pair of constants of the form `_MIN` and `_MAX` to define the minimum and maximum values. + +| Platform Logical Type | Compiler Directive | Default | Format Specifier | Notes | +|-------------------------|------------------------------------|------------------|-----------------------|-----------------------------| +| PlatformIndexType | PLATFORM_INDEX_TYPE_DEFINED | PlatformIntType | PRI_PlatformIndexType | Ports indices | +| PlatformSizeType | PLATFORM_SIZE_TYPE_DEFINED | PlatformUIntType | PRI_PlatformSizeType | Sizes | +| PlatformPointerCastType | PLATFORM_POINTER_CAST_TYPE_DEFINED | PlatformIntType | PRI_PointerCastType | Pointers stored as integers | +| PlatformAssertArgType | PLATFORM_ASSERT_ARG_TYPE_DEFINED | PlatformIntType | PRI_AssertArgType | Argument to FW_ASSERT | +| PlatformIntType | PLATFORM_INT_TYPE_DEFINED | int | PRI_PlatformIntType | Deprecated (see note) | +| PlatformUIntType | PLATFORM_UINT_TYPE_DEFINED | unsigned int | PRI_PlatformUIntType | Deprecated (see note) | + +A complete definition of a type as a platform should supply within `StandardTypes.hpp` is shown below. Notice the type +is defined along with a compiler directive announcing it is defined, and a format specifier. + +```c++ +typedef int32_t PlatformIndexType; +const PlatformIndexType PlatformIndexType_MIN = 0; +const PlatformIndexType PlatformIndexType_MAX = INT32_MAX; +#define PLATFORM_INDEX_TYPE_DEFINED +#define PRI_PlatformIndexType PRId32 +``` + +In order to print these types, developers can use the following example as a basis: + +```c++ +PlatformIndexType index = 3; +printf("Index: %" PRI_PlatformIndexType " is the index", index); // Uses string constant concatenation +``` + +**Note:** in order for F´ to compile without warnings it is necessary that each of the platform types are elements in +the set of integers supplied by the C standard int header. i.e. each type is an `int8_t`, `int16_t`, `int32_t`, +`int64_t` or unsigned equivalents. On some compilers `int` and `unsigned int` are not members of that set and on those +platforms it is imperative that both `PlatformIntType` and `PlatformUIntType` be set to some fixed size type instead. + +### Configurable Integer Types + +Project may configure the framework types that the framework and components use for implementation through +`FpConfig.hpp`. The default configuration uses the above platform types where applicable. `_MIN` and `_MAX` +to define the minimum and maximum values. + +| Framework Type | Logical Usage | Default | Format Specifier | Notes | +|------------------------|----------------------------|-----------------------|----------------------|------------| +| FwIndexType | Port indices | PlatformIndexType | PRI_FwIndexType | | +| FwSizeType | Sizes | PlatformSizeType | PRI_FwSizeType | | +| FwAssertArg | Arguments to asserts | PlatformAssertArgType | PRI_FwAssertArgType | | +| FwNativeIntType | `int` | PlatformIntType | PRI_FwNativeIntType | Deprecated | +| FwNativeUIntType | `unsigned int` | PlatformUIntType | PRI_FwNativeUIntType | Deprecated | + +There is also a set of framework types that are used across F´ deployments and specifically interact with ground data +systems. `_MIN` and `_MAX` to define the minimum and maximum values. These GDS types are based on +configurable platform independent fixed-widths as shown below: + +| GDS Type | Logical Usage | Default | Format Specifier | +|------------------------|----------------------------|-----------------------|----------------------------| +| FwBuffSizeType | `Fw::Buffer` sizes | U16 | PRI_FwBuffSizeType | +| FwEnumStoreType | Enumeration values | I32 | PRI_FwEnumStoreType | +| FwTimeBaseStoreType | Time base | U16 | PRI_FwTimeBaseStoreType | +| FwTimeContextStoreType | Time context | U8 | PRI_FwTimeContextStoreType | +| FwPacketDescriptorType | F´ packet descriptor field | U32 | PRI_FwPacketDescriptorType | +| FwOpcodeType | F´ command opcodes | U32 | PRI_FwOpcodeType | +| FwChanIdType | F´ channel ids | U32 | PRI_FwChanIdType | +| FwEventIdType | F´ event ids | U32 | PRI_FwEventIdType | +| FwPrmIdType | F´ parameter ids | U32 | PRI_FwPrmIdType | +| FwTlmPacketizeIdType | F´ telemetry packet ids | U16 | PRI_FwTlmPacketizeIdType | + +A complete definition of a framework/GDS type in `FpConfig.hpp` would look like: + +```c++ +typedef uint32_t FwSizeType; +const FwSizeType PlatformIndexType_MIN = 0; +const FwSizeType PlatformIndexType_MAX = UINT32_MAX; +#define PRI_FwSizeType PRIu32 +``` diff --git a/docs/latest.md b/docs/latest.md index 6fcac070a1..c57694af34 100644 --- a/docs/latest.md +++ b/docs/latest.md @@ -5,8 +5,9 @@ layout: default This is the documentation for the latest F´ framework. It is kept consistent with the `devel` branch. -| F´ Resources | | -|---|---| -| Installation | [INSTALL.md](./INSTALL.md) | -| Tutorials | [Tutorials](./Tutorials/README.md) | -| User Guide | [User Guide](./UsersGuide/guide.md) | +| F´ Resources | | +|-----------------------|-------------------------------------| +| Installation | [INSTALL.md](./INSTALL.md) | +| Tutorials | [Tutorials](./Tutorials/README.md) | +| User Guide | [User Guide](./UsersGuide/guide.md) | +| Design and Philosophy | [Design](./Design/general.md) | From dd4b2fea5cf82996e71486850ffc0287acc3e4dd Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Mon, 25 Jul 2022 21:43:16 +0200 Subject: [PATCH 031/169] Replace manual loop counters by `enumerate()` call (#1552) * Replace loop cnt w/ `enumerate()` in `InstanceEventVisitor.py` * Replace loop cnt w/ `enumerate()` in `EventVisitor.py` * Replace loop cnt w/ `enumerate()` in `ComponentVisitorBase.py` * Replace loop cnt w/ `enumerate()` in `CommandVisitor.py` * Replace loop cnt w/ `enumerate()` in `ChannelVisitor.py` * Replace loop cnt w/ `enumerate()` in `formatters.py` * Replace loop cnt w/ `enumerate()` in `tlmLayout.py` * Reformatting the % string with %d in the refactored statement --- Autocoders/Python/bin/tlmLayout.py | 4 +-- .../src/fprime_ac/generators/formatters.py | 14 ++------ .../generators/visitors/ChannelVisitor.py | 12 ++----- .../generators/visitors/CommandVisitor.py | 32 +++++-------------- .../visitors/ComponentVisitorBase.py | 10 +++--- .../generators/visitors/EventVisitor.py | 13 ++------ .../visitors/InstanceEventVisitor.py | 5 +-- 7 files changed, 23 insertions(+), 67 deletions(-) diff --git a/Autocoders/Python/bin/tlmLayout.py b/Autocoders/Python/bin/tlmLayout.py index 27cc67b476..1f4dd18c02 100644 --- a/Autocoders/Python/bin/tlmLayout.py +++ b/Autocoders/Python/bin/tlmLayout.py @@ -472,9 +472,7 @@ def packet_complete(self): print("") print("Number of items in packet item list: ", len(self.m_item_list)) - i = 0 - for item in self.m_item_list: - i += 1 + for i, item in enumerate(self.m_item_list, start=1): print("Item # ", i) print("\tis_reserve: ", item.m_is_reserve) print("\tis_constant: ", item.m_is_constant) diff --git a/Autocoders/Python/src/fprime_ac/generators/formatters.py b/Autocoders/Python/src/fprime_ac/generators/formatters.py index 80418ec56f..200696af4b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/formatters.py +++ b/Autocoders/Python/src/fprime_ac/generators/formatters.py @@ -103,14 +103,10 @@ def _getStartExcludingNewlines(self, line_list): Returns -1 if everything is a newline """ - count = 0 - - for item in line_list: + for count, item in enumerate(line_list): item = item.strip() if item != "": return count - count += 1 - return -1 def _getEndsExcludingNewlines(self, line_list): @@ -1078,15 +1074,13 @@ def formatFunCommentOldVersion(self, name, args, proto=True, indent=0): cpos = apos + type_max + 1 # place args and comments and put together the string. - i = 0 func_arg_list = [] - for a in format_func_list[1:]: + for i, a in enumerate(format_func_list[1:]): pad = (cpos - (apos + len(a.strip()))) * " " str = ( apad + a.strip() + pad + comment_list[i] + "\n" ) # + pad + comment_list[i] func_arg_list.append(str) - i += 1 # # print 'Last arg: ',func_arg_list[-1].replace(') ',');') # TODO: add switch so a ; is inserted - end of last arg after ). @@ -1216,11 +1210,9 @@ def argStringAlign(self, type_list, arg_list, pad_spaces=4): max_type_length = max(list(map(len, type_list))) - i = 0 - for type in type_list: + for i, type in enumerate(type_list): pad = (max_type_length + pad_spaces) - len(type) str = type + pad * " " + arg_list[i] - i += 1 str_list.append(str) return str_list diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py index 281e9b9126..85b5b049c5 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py @@ -103,10 +103,8 @@ def DictStartVisit(self, obj): raise Exception(f"Could not open {pyfile} file.") self.__fp.append(fd) else: - inst = 0 - for id in obj.get_ids(): + for inst, id in enumerate(obj.get_ids()): pyfile = "%s/%s_%d.py" % (output_dir, obj.get_name(), inst) - inst += 1 DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") if fd is None: @@ -118,23 +116,20 @@ def DictHeaderVisit(self, obj): """ Defined to generate header for channel python class. """ - inst = 0 - for id in obj.get_ids(): + for inst, id in enumerate(obj.get_ids()): c = ChannelHeader.ChannelHeader() d = datetime.datetime.now() c.date = d.strftime("%A, %d %B %Y") c.user = getuser() c.source = obj.get_xml_filename() self._writeTmpl(c, self.__fp[inst], "channelHeaderVisit") - inst += 1 def DictBodyVisit(self, obj): """ Defined to generate the body of the Python channel class @param obj: the instance of the channel model to operation on. """ - inst = 0 - for id in obj.get_ids(): + for inst, id in enumerate(obj.get_ids()): c = ChannelBody.ChannelBody() if len(obj.get_ids()) > 1: c.name = obj.get_name() + "_%d" % inst @@ -169,4 +164,3 @@ def DictBodyVisit(self, obj): self._writeTmpl(c, self.__fp[inst], "channelBodyVisit") self.__fp[inst].close() - inst += 1 diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py index 8a820e71b7..70f769c610 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py @@ -112,10 +112,8 @@ def DictStartVisit(self, obj): raise Exception(f"Could not open {pyfile} file.") self.__fp1.append(fd) else: - inst = 0 - for opcode in obj.get_opcodes(): + for inst, opcode in enumerate(obj.get_opcodes()): pyfile = "%s/%s_%d.py" % (output_dir, obj.get_mnemonic(), inst) - inst += 1 DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") if fd is None: @@ -144,8 +142,7 @@ def DictStartVisit(self, obj): raise Exception(f"Could not open {pyfile} file.") self.__fp2.append(fd) else: - inst = 0 - for opcode in obj.get_set_opcodes(): + for inst, opcode in enumerate(obj.get_set_opcodes()): pyfile = "%s/%s_%d_PRM_SET.py" % (output_dir, self.__stem, inst) DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") @@ -160,7 +157,6 @@ def DictStartVisit(self, obj): if fd is None: raise Exception(f"Could not open {pyfile} file.") self.__fp2.append(fd) - inst += 1 DEBUG.info(f"Completed {pyfile} open") else: @@ -175,38 +171,32 @@ def DictHeaderVisit(self, obj): @param obj: the instance of the command model to visit. """ if type(obj) is Command.Command: - inst = 0 - for opcode in obj.get_opcodes(): + for inst, opcode in enumerate(obj.get_opcodes()): c = CommandHeader.CommandHeader() d = datetime.datetime.now() c.date = d.strftime("%A, %d %B %Y") c.user = getuser() c.source = obj.get_xml_filename() self._writeTmpl(c, self.__fp1[inst], "commandHeaderVisit") - inst += 1 elif type(obj) is Parameter.Parameter: # SET Command header - inst = 0 - for opcode in obj.get_set_opcodes(): + for inst, opcode in enumerate(obj.get_set_opcodes()): c = CommandHeader.CommandHeader() d = datetime.datetime.now() c.date = d.strftime("%A, %d %B %Y") c.user = getuser() c.source = obj.get_xml_filename() self._writeTmpl(c, self.__fp1[inst], "commandHeaderVisit") - inst += 1 # SAVE Command header - inst = 0 - for opcode in obj.get_save_opcodes(): + for inst, opcode in enumerate(obj.get_save_opcodes()): c = CommandHeader.CommandHeader() d = datetime.datetime.now() c.date = d.strftime("%A, %d %B %Y") c.user = getuser() c.source = obj.get_xml_filename() self._writeTmpl(c, self.__fp2[inst], "commandHeaderVisit") - inst += 1 def DictBodyVisit(self, obj): """ @@ -214,8 +204,7 @@ def DictBodyVisit(self, obj): @param obj: the instance of the command model to operation on. """ if type(obj) is Command.Command: - inst = 0 - for opcode in obj.get_opcodes(): + for inst, opcode in enumerate(obj.get_opcodes()): c = CommandBody.CommandBody() # only add the suffix if there is more than one opcode per command if len(obj.get_opcodes()) > 1: @@ -247,10 +236,8 @@ def DictBodyVisit(self, obj): ) self._writeTmpl(c, self.__fp1[inst], "commandBodyVisit") self.__fp1[inst].close() - inst += 1 if type(obj) is Parameter.Parameter: - inst = 0 - for opcode in obj.get_set_opcodes(): + for inst, opcode in enumerate(obj.get_set_opcodes()): # Set Command c = CommandBody.CommandBody() if len(obj.get_set_opcodes()) > 1: @@ -279,10 +266,8 @@ def DictBodyVisit(self, obj): c.arglist.append((obj.get_name(), obj.get_comment(), type_string)) self._writeTmpl(c, self.__fp1[inst], "commandBodyVisit") self.__fp1[inst].close() - inst += 1 - inst = 0 - for opcode in obj.get_save_opcodes(): + for inst, opcode in enumerate(obj.get_save_opcodes()): # Save Command c = CommandBody.CommandBody() if len(obj.get_save_opcodes()) > 1: @@ -298,4 +283,3 @@ def DictBodyVisit(self, obj): self._writeTmpl(c, self.__fp2[inst], "commandBodyVisit") self.__fp2[inst].close() - inst += 1 diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py b/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py index d5a8dece3a..fc9db5ac11 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py @@ -379,12 +379,10 @@ def g(xxx_todo_changeme3): if len(opcodes) == 1: return f"CMD_{mnemonic.upper()}" else: - mlist = [] - inst = 0 - for opcode in opcodes: - mlist.append("CMD_" + mnemonic.upper() + "_%d" % inst) - inst += 1 - return mlist + return [ + f"CMD_{mnemonic.upper()}_{inst}" + for inst, opcode in enumerate(opcodes) + ] else: return None diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py index bf05a074b5..ee4c5c802b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py @@ -121,23 +121,20 @@ def DictHeaderVisit(self, obj): Defined to generate header for event python class. @param obj: the instance of the event model to operation on. """ - inst = 0 - for id in obj.get_ids(): + for inst, id in enumerate(obj.get_ids()): c = EventHeader.EventHeader() d = datetime.datetime.now() c.date = d.strftime("%A, %d %B %Y") c.user = getuser() c.source = obj.get_xml_filename() self._writeTmpl(c, self.__fp[inst], "eventHeaderVisit") - inst += 1 def DictBodyVisit(self, obj): """ Defined to generate the body of the Python event class @param obj: the instance of the event model to operation on. """ - inst = 0 - for id in obj.get_ids(): + for inst, id in enumerate(obj.get_ids()): c = EventBody.EventBody() if len(obj.get_ids()) > 1: c.name = obj.get_name() + "_%d" % inst @@ -151,9 +148,7 @@ def DictBodyVisit(self, obj): c.arglist = [] c.ser_import_list = [] - arg_num = 0 - - for arg_obj in obj.get_args(): + for arg_num, arg_obj in enumerate(obj.get_args()): n = arg_obj.get_name() t = arg_obj.get_type() s = arg_obj.get_size() @@ -185,7 +180,5 @@ def DictBodyVisit(self, obj): c.format_string = format_string c.arglist.append((n, d, type_string)) - arg_num += 1 self._writeTmpl(c, self.__fp[inst], "eventBodyVisit") self.__fp[inst].close() - inst += 1 diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py index 41b82789a0..3e78bb438b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py @@ -196,9 +196,7 @@ def DictBodyVisit(self, obj, topology_model): c.arglist = [] c.ser_import_list = [] - arg_num = 0 - - for arg_obj in obj.get_args(): + for arg_num, arg_obj in enumerate(obj.get_args()): n = arg_obj.get_name() t = arg_obj.get_type() s = arg_obj.get_size() @@ -230,6 +228,5 @@ def DictBodyVisit(self, obj, topology_model): c.format_string = format_string c.arglist.append((n, d, type_string)) - arg_num += 1 self._writeTmpl(c, self.__fp[fname], "eventBodyVisit") self.__fp[fname].close() From 60334b12c1e7e2045dee6e1c6ccba71c13ead939 Mon Sep 17 00:00:00 2001 From: Simone Morettini Date: Mon, 25 Jul 2022 21:45:17 +0200 Subject: [PATCH 032/169] Added missing headers and removed where not needed (#1572) Co-authored-by: Simone Morettini --- config/ActiveLoggerImplCfg.hpp | 2 -- config/UdpReceiverComponentImplCfg.hpp | 2 ++ config/UdpSenderComponentImplCfg.hpp | 2 ++ 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/config/ActiveLoggerImplCfg.hpp b/config/ActiveLoggerImplCfg.hpp index 9639304977..e24f973b51 100644 --- a/config/ActiveLoggerImplCfg.hpp +++ b/config/ActiveLoggerImplCfg.hpp @@ -8,8 +8,6 @@ #ifndef ACTIVELOGGER_ACTIVELOGGERIMPLCFG_HPP_ #define ACTIVELOGGER_ACTIVELOGGERIMPLCFG_HPP_ -#include - // set default filters enum { diff --git a/config/UdpReceiverComponentImplCfg.hpp b/config/UdpReceiverComponentImplCfg.hpp index efe900898a..c32d8e8e78 100644 --- a/config/UdpReceiverComponentImplCfg.hpp +++ b/config/UdpReceiverComponentImplCfg.hpp @@ -8,6 +8,8 @@ #ifndef SVC_UDPRECEIVER_UDPRECEIVERCOMPONENTIMPLCFG_HPP_ #define SVC_UDPRECEIVER_UDPRECEIVERCOMPONENTIMPLCFG_HPP_ +#include "Fw/Types/BasicTypes.hpp" + namespace Svc { const static NATIVE_UINT_TYPE UDP_RECEIVER_MSG_SIZE = 256; } diff --git a/config/UdpSenderComponentImplCfg.hpp b/config/UdpSenderComponentImplCfg.hpp index 5641580934..a39be283dc 100644 --- a/config/UdpSenderComponentImplCfg.hpp +++ b/config/UdpSenderComponentImplCfg.hpp @@ -8,6 +8,8 @@ #ifndef SVC_UDPSENDER_UDPSENDERCOMPONENTIMPLCFG_HPP_ #define SVC_UDPSENDER_UDPSENDERCOMPONENTIMPLCFG_HPP_ +#include "Fw/Types/BasicTypes.hpp" + namespace Svc { static const NATIVE_UINT_TYPE UDP_SENDER_MSG_SIZE = 256; } From dbb6240d20e9a3c7ed080a385646c95573e0903e Mon Sep 17 00:00:00 2001 From: pelmini <37095187+pelmini@users.noreply.github.com> Date: Mon, 25 Jul 2022 16:01:26 -0700 Subject: [PATCH 033/169] Linux i2c refactor (#1582) * Change LinuxI2cDriverComponentImpl to LinuxI2cDriver * Refactor change * lestarch: fixing improperly named include Co-authored-by: M Starch --- Drv/LinuxI2cDriver/CMakeLists.txt | 4 +-- ...erComponentImpl.cpp => LinuxI2cDriver.cpp} | 25 +++++++++---------- ...erComponentImpl.hpp => LinuxI2cDriver.hpp} | 10 ++++---- ...entImplStub.cpp => LinuxI2cDriverStub.cpp} | 24 ++++++++---------- Drv/LinuxI2cDriver/test/ut/Tester.hpp | 4 +-- Drv/LinuxI2cDriver/test/ut/main.cpp | 4 +-- 6 files changed, 34 insertions(+), 37 deletions(-) rename Drv/LinuxI2cDriver/{LinuxI2cDriverComponentImpl.cpp => LinuxI2cDriver.cpp} (92%) rename Drv/LinuxI2cDriver/{LinuxI2cDriverComponentImpl.hpp => LinuxI2cDriver.hpp} (90%) rename Drv/LinuxI2cDriver/{LinuxI2cDriverComponentImplStub.cpp => LinuxI2cDriverStub.cpp} (78%) diff --git a/Drv/LinuxI2cDriver/CMakeLists.txt b/Drv/LinuxI2cDriver/CMakeLists.txt index 3d89deb124..4e4deb9c40 100644 --- a/Drv/LinuxI2cDriver/CMakeLists.txt +++ b/Drv/LinuxI2cDriver/CMakeLists.txt @@ -9,13 +9,13 @@ if(FPRIME_USE_STUBBED_DRIVERS) add_definitions(-DSTUBBED_LINUX_I2C_DRIVER) set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriver.fpp" - "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriverComponentImplStub.cpp" + "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriverStub.cpp" ) register_fprime_module() elseif(${CMAKE_SYSTEM_NAME} STREQUAL "Linux") set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriver.fpp" - "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriverComponentImpl.cpp" + "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriver.cpp" ) register_fprime_module() else() diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp similarity index 92% rename from Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.cpp rename to Drv/LinuxI2cDriver/LinuxI2cDriver.cpp index 8519d4bc1e..b821dd44a0 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp @@ -10,11 +10,10 @@ // // ====================================================================== - -#include -#include -#include "Fw/Types/BasicTypes.hpp" #include "Fw/Types/Assert.hpp" +#include "Fw/Types/BasicTypes.hpp" +#include +#include #include // required for I2C device access #include // required for I2C device configuration @@ -31,8 +30,8 @@ namespace Drv { // Construction, initialization, and destruction // ---------------------------------------------------------------------- - LinuxI2cDriverComponentImpl :: - LinuxI2cDriverComponentImpl( + LinuxI2cDriver :: + LinuxI2cDriver( const char *const compName ) : LinuxI2cDriverComponentBase(compName), m_fd(-1) @@ -40,7 +39,7 @@ namespace Drv { } - void LinuxI2cDriverComponentImpl :: + void LinuxI2cDriver :: init( const NATIVE_INT_TYPE instance ) @@ -48,15 +47,15 @@ namespace Drv { LinuxI2cDriverComponentBase::init(instance); } - LinuxI2cDriverComponentImpl :: - ~LinuxI2cDriverComponentImpl() + LinuxI2cDriver:: + ~LinuxI2cDriver() { if (-1 != this->m_fd) { // check if file is open ::close(this->m_fd); } } - bool LinuxI2cDriverComponentImpl::open(const char* device) { + bool LinuxI2cDriver::open(const char* device) { FW_ASSERT(device); this->m_fd = ::open(device, O_RDWR); return (-1 != this->m_fd); @@ -69,7 +68,7 @@ namespace Drv { // Note this port handler is guarded, so we can make the ioctl call - Drv::I2cStatus LinuxI2cDriverComponentImpl :: + Drv::I2cStatus LinuxI2cDriver :: write_handler( const NATIVE_INT_TYPE portNum, U32 addr, @@ -108,7 +107,7 @@ namespace Drv { return I2cStatus::I2C_OK; } - Drv::I2cStatus LinuxI2cDriverComponentImpl :: + Drv::I2cStatus LinuxI2cDriver :: read_handler( const NATIVE_INT_TYPE portNum, U32 addr, @@ -149,7 +148,7 @@ namespace Drv { return I2cStatus::I2C_OK; } - Drv::I2cStatus LinuxI2cDriverComponentImpl :: + Drv::I2cStatus LinuxI2cDriver :: writeRead_handler( const NATIVE_INT_TYPE portNum, /*!< The port number*/ U32 addr, diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.hpp b/Drv/LinuxI2cDriver/LinuxI2cDriver.hpp similarity index 90% rename from Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.hpp rename to Drv/LinuxI2cDriver/LinuxI2cDriver.hpp index d5d17b2e85..02fdafd9c0 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.hpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriver.hpp @@ -1,5 +1,5 @@ // ====================================================================== -// \title LinuxI2cDriverComponentImpl.hpp +// \title LinuxI2cDriver.hpp // \author tcanham // \brief hpp file for LinuxI2cDriver component implementation class // @@ -17,7 +17,7 @@ namespace Drv { - class LinuxI2cDriverComponentImpl : + class LinuxI2cDriver : public LinuxI2cDriverComponentBase { @@ -29,7 +29,7 @@ namespace Drv { //! Construct object LinuxI2cDriver //! - LinuxI2cDriverComponentImpl(const char *const compName); + LinuxI2cDriver(const char *const compName); //! Initialize object LinuxI2cDriver //! @@ -40,7 +40,7 @@ namespace Drv { bool open(const char* device); //! Destroy object LinuxI2cDriver //! - ~LinuxI2cDriverComponentImpl(); + ~LinuxI2cDriver(); PRIVATE: @@ -66,7 +66,7 @@ namespace Drv { //! Handler implementation for writeRead //! - Drv::I2cStatus writeRead_handler( + I2cStatus writeRead_handler( const NATIVE_INT_TYPE portNum, /*!< The port number*/ U32 addr, Fw::Buffer &writeBuffer, diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriverComponentImplStub.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp similarity index 78% rename from Drv/LinuxI2cDriver/LinuxI2cDriverComponentImplStub.cpp rename to Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp index 91fdabd58e..780491ae6d 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriverComponentImplStub.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp @@ -1,5 +1,5 @@ // ====================================================================== -// \title LinuxI2cDriverComponentImpl.cpp +// \title LinuxI2cDriver.cpp // \author tcanham // \brief cpp file for LinuxI2cDriver component implementation class // @@ -10,10 +10,9 @@ // // ====================================================================== - -#include -#include "Fw/Types/BasicTypes.hpp" #include "Fw/Types/Assert.hpp" +#include "Fw/Types/BasicTypes.hpp" +#include #define DEBUG_PRINT 0 @@ -23,15 +22,14 @@ namespace Drv { // Construction, initialization, and destruction // ---------------------------------------------------------------------- - LinuxI2cDriverComponentImpl :: - LinuxI2cDriverComponentImpl( +LinuxI2cDriver ::LinuxI2cDriver( const char *const compName ) : LinuxI2cDriverComponentBase(compName) { } - void LinuxI2cDriverComponentImpl :: + void LinuxI2cDriver :: init( const NATIVE_INT_TYPE instance ) @@ -39,13 +37,13 @@ namespace Drv { LinuxI2cDriverComponentBase::init(instance); } - LinuxI2cDriverComponentImpl :: - ~LinuxI2cDriverComponentImpl() + LinuxI2cDriver :: + ~LinuxI2cDriver() { } - bool LinuxI2cDriverComponentImpl::open(const char* device) { + bool LinuxI2cDriver::open(const char* device) { return true; } @@ -56,7 +54,7 @@ namespace Drv { // Note this port handler is guarded, so we can make the ioctl call - I2cStatus LinuxI2cDriverComponentImpl :: + I2cStatus LinuxI2cDriver :: write_handler( const NATIVE_INT_TYPE portNum, U32 addr, @@ -66,7 +64,7 @@ namespace Drv { return I2cStatus::I2C_OK; } - Drv::I2cStatus LinuxI2cDriverComponentImpl :: + Drv::I2cStatus LinuxI2cDriver :: read_handler( const NATIVE_INT_TYPE portNum, U32 addr, @@ -76,7 +74,7 @@ namespace Drv { return I2cStatus::I2C_OK; } - Drv::I2cStatus LinuxI2cDriverComponentImpl :: + Drv::I2cStatus LinuxI2cDriver :: writeRead_handler( const NATIVE_INT_TYPE portNum, /*!< The port number*/ U32 addr, diff --git a/Drv/LinuxI2cDriver/test/ut/Tester.hpp b/Drv/LinuxI2cDriver/test/ut/Tester.hpp index 51f8c73a71..b4a42ba83c 100644 --- a/Drv/LinuxI2cDriver/test/ut/Tester.hpp +++ b/Drv/LinuxI2cDriver/test/ut/Tester.hpp @@ -13,8 +13,8 @@ #ifndef TESTER_HPP #define TESTER_HPP +#include "Drv/LinuxI2cDriver/LinuxI2cDriver.hpp" #include "GTestBase.hpp" -#include "Drv/LinuxI2cDriver/LinuxI2cDriverComponentImpl.hpp" namespace Drv { @@ -70,7 +70,7 @@ namespace Drv { //! The component under test //! - LinuxI2cDriverComponentImpl component; + LinuxI2cDriver component; }; diff --git a/Drv/LinuxI2cDriver/test/ut/main.cpp b/Drv/LinuxI2cDriver/test/ut/main.cpp index b58acd8367..e989722b86 100644 --- a/Drv/LinuxI2cDriver/test/ut/main.cpp +++ b/Drv/LinuxI2cDriver/test/ut/main.cpp @@ -1,9 +1,9 @@ -#include #include -#include +#include #include #include #include +#include TEST(TestNominal,Nominal) { From 80d0dff499f319af2ae4728f610c06f245896bfd Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Tue, 26 Jul 2022 01:04:15 +0200 Subject: [PATCH 034/169] Switch CmdDispatcher doc to mermaid (#1588) --- .../docs/img/CommandDispatch.jpg | Bin 59402 -> 0 bytes .../docs/img/CommandRegistration.jpg | Bin 63300 -> 0 bytes Svc/CmdDispatcher/docs/sdd.md | 31 ++++++++++++++++-- 3 files changed, 29 insertions(+), 2 deletions(-) delete mode 100644 Svc/CmdDispatcher/docs/img/CommandDispatch.jpg delete mode 100644 Svc/CmdDispatcher/docs/img/CommandRegistration.jpg diff --git a/Svc/CmdDispatcher/docs/img/CommandDispatch.jpg b/Svc/CmdDispatcher/docs/img/CommandDispatch.jpg deleted file mode 100644 index c530be989135f790884216514b38f3aed61b9c4d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 59402 zcmeFZ2~<=0_a_)vM8t^fsH7AT0U;_Nh#~nY1r(q}b^#@Y6tam?fih}LRQAnO6(AN{ z3Nc1Nj0h1$OoRkdN?`;7K~O>x71`uHmGC4B^Q>P_&zx>&PW5#Er_Y>eI5{4_z-{yV?EUgW>?5{nisJVEHKSp41M zmrE9HLM+x>v_x;w0v~}wAQmnA_q7rK>1)yAB}yQV0G8_8P?EMN5_}Ub}zN<4CnziI~+ZIS$n0Cv5Bdf zt*>$|T6_lnEYVxK zY~zmQYxnwVMV->$wDZymgMGhNHMD74I0OKOM^E>xG}`PawFJM4_P1pJOt8!Uk0krg zg8d(I4Ix%7Sp+}4C3*-PLNm&7C8y+#<`Y)c*K(o{|{)7omA>T3)B=Bp8r)pCU?G zhLGH&hkKMT%u-Z}T6Lr3ge8!B+lc*R^|dBpTFXG$A5d-*ezciJrY6-*#LL$WBatLp zI|T=D(xiiTQgc+Hqo|zZSMPPDC&->QnMT+?JzVU806}Q^msqEjVLwL{bTknqOX-L2xVrrw*|Ap@0e%Ukb$(CP~+UHw5nw`zh$^Q6!UxY zipESloUOe*?dX0B2%eAX*aG4PStI5`;gmL%dYy>+U$6ClF;;pmAlf1p5Qzor6jXIB z{RyFw*pAGgZoul34b?O(4zdXD=f)i&%JAt-$W9qe67xs2UpNf|lExDkQ)cotD@7{X zGch$PH@Z7W;Qe`%WBy$;M3Z%GFvU2_sK>brh|5n@`|=dG#Z-7px*9&gfUr3M4F1g+Mf^M2nQxXgqg+;QiBuHIsTA$9aRojsO@b)>v1 zMHQ&Dqzi~8!}~zn>@}U-r5wkXs-&bq*fO)RXw@d1!RM}Ns({}3R?vRLVjp1Kj@KtW8YOn%bfNS7 zA%cLof%L(#0l30uk?ng@77+T91w^|8?LKqL$nu%!2>z#=eTl;^F>9H7AKa|YVQu?l z&&+7|z8z^FY~!o5kL?<4V`bu(!U*49#xxbBm*yp%w=unG&-O5!@yS@V<-qSpPnle+ zi2|DLvayXJMdFQ$tbeXi15G;>2u7Q0#F4wzr7AbM@MRir0kKSFr#wt~#?`|mpf8VD z05bw5J+Jgt_?dRXdev?Kb)|J9?4x4(Qi@R+|8&ya1Ds8~2@DDjg>SRA4 zv)=MKEm}dGj+M>i{5kFx+5OXonqc|N1C)MJ! z@>=RtxIXM=615Yz+E`$2Q6g2-Ge19e7f_ailB}l3=m4>k7I3xZRz&$n?Z9XzwgXKQLf38e7Rgn4yH6Hg8 z?GDVf%cT`a#S1vPQ8RETY8=6w{5?o7_>6kV3Voz5*Q_ArwGW(nHekL2Iv^)3g(Qm7 zffSZGiMqcT_>dz-UX(0tjk@!mvIR60=U`Wi8@He`geVym+A0+I3Ugg)m$9oU&&(Hr zf($gpx*G_566p*sAg0}FR68DlNLtnu9X9kKjV_+g(eJ^<;&UBHUQ#{ZUfslS@~?GSX)^ILW`FPx zK6-V2G{se8(~{nzalxd?E2BNSSqk<^(zV`~fpknfH`c7M&UFXVMzs6&4^ejq$FvOn zAK;a^4VV5pVtuPWbIFFZj(+A!m)z4O19YI5Yswu*;n*`8Bl=yh1%&4;>Kkih3n>w@ zAqr@@q2_uIA$R3^67mor=Hu6psIY*SQ|Z|_cFY3e5;_*jV`(}^^wmuYQkf^PfS4Kv z*S{yMc4RG{bX`ECrJ_yZTe5Pd)80`Ht4m)0V;!cBq9N;&PNX5pX4qd$jlpTf;q)|HRao_J8Vkx_l}mf6@q1?U z;wrJdxWpL)61Tll?=I9WFB4ugH-(d)Rh`O}-Zsbi4yraz$Dl!3J5uM_J(a5nYXMb7 z1LYuVdZRMnFpMkqa8D5PDjf#;q_pW}K%Icj7H5(-o|jeuN`aANl?6nV+Y!Bh%~)em zDh?42;RQoyGMoOq%>>>(mMwL95oj^m26|J5| zdHH9V0geq1kHwcoo$AfEupQlDvcKAJ+pbOagu^AaZC?6*l{Pm~Q*S*F*L~Pc^`KK?i!&X>P9mU1bUu z@{9>EU`W6tRoWo);;gSEo!;1d5o?gRfIyN1Zzi5IXGrUJX!PR&hd3Us=#wx>^PMkrjE*J?L`!UwCIKq0YIoVr%jk3XAiAlhrRPj<|PU-S$C7$g2 zLbLw;eY!b$5y(^g2w8%{(JS?%4Kg?Vj&t|xi2zRK+{QJBs6oxd%Q#bwHDM6S?b}=K zyk%Fh>!3}Zq1l6HFE6Oa(_XWF&I z)ud%8IG{R&ZSyoBWn+3xNUD{eW7YZ-D^0JgE3Kn9=GXpM>$RrZ+Vk+Qwe{WmTH`4f z|2aTaD!+#fDN>cFbX9FG?1=nMeGRjRrHTNIYLx%-0OeBW42lEU51cYz3(QTuPgzGZ zh8m?;tARWP9;ybt1lTqGP4JpmU<3T$*iqutB%uGKFY&%BQh>{stiX8HLB8G~{s!s1 zVo1#t@NqQF>ORdHl{Hjy8!A*heSux1`7_+S8Wco8XQhQwI`k7!ThqhYDuSPMtx$0S z-0~O>FWz^7$_f_gdgmCg(ggYTLv(eKndT0(qneyc@=}S zrvrBsR1~=;tAneratH6pJIvi$#o{LtfK9}B9;cYcg>RwXd z(e}DX1EybjwXbeKE8t+TL4nIC$mr%1vnuo6|QYo~PTw1<*ID z!f!3s0TGIe(0$lnsqsR?xN}}p52Xa!-2-(RQOo^@(nq=uZJ{VV)mc!h17{4oI>Auo zRCvH_?oz6o&qrRHxv9EPvoX%K{!WGL_u0oG0@<;0%{st2U*#c1BB9vuQR*@J5DW>8 zI5tphT_Q>g<0eJtR_+3w^Dx$<-Ck04R<_C_cJ#5WT&UVg%_ksKv9NXtZIVVm#wdde zMc-5f09I3Nve)_%FJ{~BB+%D5M$mG?e`WzZnJ_nFfL!=C;4PUIq@rWFU;HTLxBE(+ z+5JlDC{9&G`Amh~?Hh^rTgmt=fzQpynP9(DIjXbB=uw(Et_@|P8EnbQnpVYtgtkay zfR)Xj$vPLzotlvoY37^rq$lz~yf+L@E>5cgSqbL4Y3&-+BPd6T%O2WAtC}$Dm=$I@ zJr3#Ze771WV@_Kry){qIp|Uu}s8#Q&_p|s^9oRFK%6-r$nN_}u_=l$Z++)eq7~sy2 zG-|vOau@JwCz?T4oePMjfkp=D6K_6-o0WoJL0%47%5~4UgU;D^TD<|UA0EF@*`G>{ zZwpEtTea=S2E&b*@1=ef;U*Zv!-5UD!9fha%ymoBc=8=CEf1bbi`Qdy40C>)XQPkL zrf=}}G$>CvAk_8o$N$<_m(Le0OS}G>5NlT4KzcTKc#Bc7c1TTjNA$^S3I4_B?vzvD zg6*H0*Bh=r9Pd0Su90Ma5m^sNRvZM7S1{J+K|kW<%Ecg;wt$GA#!Cw%*<>>AC)f@( zVjzKH2~_4NUCI7s?YPwzz%tE4X#t+U%S@ct8k;09*zJAEp5ds)kgIdjMi;ZqRc8AgM%Yko2!tI8oIZDcv8}+@(?c|qTzTqbRKh{nnYD3 zL03}HS!SV^QY)x!EhYJmuig2a?bLPSu4dzOom7-Al;tm0*)lwA4t9v@Ru;)Gb=`e= ze@75AK%W;g$bXx`?`LkU{iWci5<6#9;@Q5un~adsqCOwi-IOt(>wG1??wMh{kKqLx zcy`Op(JyPuN*-Tl9GTwN$ecU#&#|{Qq@&SUhNMy4G(yR$JeC|rp(dgmVQA8uF)HkdSMEF8^ zs3{RvZ(;~}WwsJ-k^q6|d~+Kh_r%`?jC7ZeMXKXgH9sq$3+j?uoM={+;DsRwi6 z21Puw6{KchETX_NfioR}aacgC#D_wuxU?DaUeFW0f<%yaq?;QT$3UsK$X?(+fpqu0 zRXRWL*0^6qZ7qb^7GJY3ur5y^J4M=Wu8%Z%+Ukeai&&DI0z9C`A9-;d^eb(DW_Y8r zs3M;2Q*^SYQ&e&6R;`P*kHN?;F8gH4_LPa|28l=OwjQhs_bE76G@;BIFA^kH~qCvzl3!J%xlgAg^Hg6t@Z+{bS5{Yo9HfT zb-IabPtuV^2%|up-#v)O=&m8TheN3XpL*B2%_nZeb2jl}T=Hw2rw2BLaRTueW~SmA z{&sJ{ar@BSvIeIOUTO5ZHNH!7JH?ge6{I4$>9L;B!l$QP^09kf7h?%^W69Fl@RcnL zD<4kuY9Ig73{pT*g6x*Gw=`>z`VVzUp^`Vjg~ek?AS=1Vv3-S`>L0Dwk!SIQIk-k7 z?-n(-zzfE_1(=PX!@oq-_?et@C|-q8pImqm>q7YpwUo14rPtqTgz>sgVukeAYqV6J zkh5HZoVYp-c*$`cwn~&Hvean&)Kebe2U%& zFe+mFIGY?&w)$?^SCLRO;oXr?7Vs)D^f>uAhE<<4r0F~wsz6ZR=qEFj*GRDWxc^()y;nMCQ6%TR&^gcjVo zT|qHW`3{i1l|Q{lA>cNf9nv3?*Q+qVQ$VQN=?q8WIEg_5%8VQwt8^w6MncpZgCxA4 zxYa*8St?vbCWF`p5ZO5iypNwpUB>KAl-G8Ps7Y|~EPO&YXWQbkagE$8M^=_A;UYEa z7H21fIta<7HBN*}6nk|wE)Jj1UEJy+Bc=}t(m89POyZD*??aIzON+#uigXrhmOJ8f z9TSg)2s~eCEECPYgJKg;Rt21Db4DElUp!@a8cO=dw8yTkw~tC=9tlxUIszH_)xPU; z$_{NavMRk|VYs~T?5DQ&`XBt9qWmfnUWsnhDt&^Ior<2NJly^8_5M)DyQ1Pc830s} z?QBHyyAVQs024)Yp&qn7k^6Cya z-VI}uOPh}UR@f2s@phq0k@VSH(}P#_v29xqJagI*cXXr8!TgP`&B5nwL~&hVpvUq_}MGFm!8PX^Ib!*N_d46IN$*D)YaX-;`gZF+v)iBPbBSPe(fU0jqFXQyg0 zT;H@Gk+XCc5FHHlAIDWrQQ(<&N@zM6{|B6S3{#nDsy)VvnG$%IWuK<5ct?s3>xp^9 zInT0HHyv-ia0{AItZsy&WP}xPqH&;zIa@S5(3nO>)|0*99?V+}k8r=Jg|1+wVcb9+ zX=KA~HOuS3zD~gu#q9;Pk!@S&79v*$40K*t=RXPWOGgc(jQ4M;KcQ9oQ27$|_JrpQ zo8arxkP6p^ll2EWZ&!ZN{?sN6zT z7(n3DwV_YnLxq5(<7bWAC8uc{xm1!zwo9tITDHF@DMf8AljBSNWaFUC1eN|=5Mcf* zFhaOY*>o3pUT~ZIQ@^x~CxNFnaG!<)-KUR%kK`IL3!sQ#$5 zAczK3cT`#pa7;e|%SYhqP(O!%wEV{Kd^BJaWtJw>HHS&q$HBUk4==0mliX z=C>xY$Tp%(Cb(EKy5Ah#(}c_An!=4H-6*)hOfVotcPtQ$$SaDvY`3@fRLubH<&hTAT^B z5vw+jY=0oac$`X=qYQ*~lhk%&B|LiXd8YZ30Hxzhx${4YzO{B*AUWK?_Q)^rh?x=W zs95=XdMvZGp?~{eyxibUg9GnHG39K)O?i1hflE)WKg0B3dAyg;sY;`Q{aB+@m*;}+ zifluw_IXDZn6a$`Pi1&}j6fbrB&CbH7>!*vfm%s1p|;zeQ97wCK<*Rz0I{bnJL!2@$kn56$%FN?Dzs= zon{Fct-juBY!rpj9E?hxs)?s< zw;^RI6MozCC-y#geu|mNyqq56G8B-%JtaQsyRrnAgrN7EYxZqFoXLb+2O@R86H$wV zd(uo@nfl-}UMrHM0a=bS`P}uNsm7|kG}%ZEGm&bNLZhM9G|_T?#$wesFgw7KLp@DN zcsV+q8i!h|+7C2$Jeo#%KZNqCq0*$C9iwxO>T8k{`5>)xlEmpJI2bqAGx-# z)esm~8VR3_ST%wr8C9?i2?Rql1tAAcrxz9UM!TDgcL^ib+^cg>p^edrqx6Oe^qDBD zVmL!?zR!}46%wf10EtQ;t=JCG3RFmN2~VPniH@pQIrWnrWXMJFcA!#``xv51@oOR9 z(P4_P6rcNs;dB+tgL&t->h{HP5l8>Pqqj<+k|9)u02}7-GPIeK8?B+_N4` zmRn_$<7KbCWQ^$#H6W7j%I!q0f$tgwJ$23_ht^Fv&kxkd4ZzP7>!cGOrGMoH0a$^}FY&Xk=Lp|}A2BraWY2s+~nZLEd#_W}0T zhfq0=cx2ZFsomnC;bH1O1Qwwu>TQH0bzb_J9eqVGW|K&z)dsjG*7V*RFh0~H?*_*L?hR1T@r3o{_-b-YpDJFt zcNm%s?@Lj~h7hk%zJszH&vg{vsf)6!Q0cuwQ)PrfwBjguIMVruZ+j*7-a~LM53@)< zjXwl5!+okD{U@5ufP}^|g%*pYp&6?4Kx2ow4#fO}L>pyZv4RrgDwl$^eC+Cp%4Hym zPg~i2;X2tvqzaCzN!Whm0NmvwOwTMJylj;lsj@X+nSSGGaC_ogt44AyKfBJg{sHMn z{t)fh(Ye>9Zc9~O{we&Xy5p{J!ix>Yw zgr5jwh-*(3$wjxDrXz<1-U-dFc0%iKtK*xi!O!Z$f-1s997# z2Di&RAt=`7w2Jev8Cn;s^nMKwrz5MBZtDxJ3IfRMNruuJ`jye&jk1=rwIo zlYm{@_jz-R=)1dVyh7+SHG8_|_2jN;*#h5SIsOG*{6GUrB?6!Ik68biuorDwqnvw}RzvM|!{VbF??%#+;9 z;vI<~02NGlhIo^7zU|6nHR<`MFgB>$Ov7C#elw&V$``EHg{Wvy}FF71x9!bIJud1NpVkzM(@utGcZIs zH)8|?WaVLYkJ6Aw;zn!$WCtpv(h`W}bF(;B_mHVaG47*OBZzv4?kQpyEPtm+(hu)% zQoeeOhbewalZ27g0QJ%djltxp_m!(#LA5+GUSdkw{a%BH(oh|b1N{ax+s9Gn*p2b1 zwNr4=|A7=Ow{NJ98=`j-R%l*eEur6~#Jn>@*urGc*b8(Vipgse!>0U?KxV&z+$^Ac z+|n=D=6u3$H;XJ?N1hj;6X7f$q&RfW;PH*JlEx}eXHb&bWuN%X#TD7Y2S{_yI(WtDXUqcVGd!xXuX5FVX|3h&F8Ta2{5@mB$;pOa1 z3vG8afA8cr{Qo~Otxi-ZO@B(i2QTdE4erS~+)nKc*-p6j=ZTUuL(`1j2 zT`${9cJ@X-tK3q#t71?6g$hiJ*`WvfR1N%IW~6m+`Y|@A#+;Y z&}prwz{O}&QlXTYiwS0_PC=iP|DwFmxQRb-R+B2=nw+;!q_I?yV5SX9W+}c%HkLI~ zS#gq8gbpn!KfELx6LAWiag1n6VkwV_|1o3=?6yNWv@p`ISBw;${^DP`__t}_Wf(VY zsWt12u8l#A$KJlQ?55;IuMkE;zgdr{KBva!L2e`U1mj#|MR>pE+2ESpekTG7iTqZW z=&`gxUFw8dJV99j1QFJdcbGqtqb`QutgeH&a<6G^urTli76sDAWO+quzY4w990(+ z3e3oi7*abFk8Vu1yw!o6wpAXChuMdG!fNta(QP(8ZzxoNGK-U#rob&5%8Q>ht^-Z4 zabf*s@QfO}vD>^MCb4$VH)8E{5lIdAi z#@v@5&-;%BGl@{5!UE=WSxCFME8zmAWbpF^ul*4IX5wO^8F`;5^#E04z~om@<;E9N zS!+pYfndx#t_*K10P!7>mf&1IIr+}SxvYH6R#J6j|12?QelFjh_#txt%zuMFvQul> znYgq$Q3lmURBVZ-^wE(YR0nR6kx)UsDiT1p)6%((tPUe+67*2T zjw&mB#`r&DO@OSNlp|)s15g^8FI)}_Pbp(`%Y4uQWGO2p-yb}TW0#92L8Be8>wUA^#v_}RfUFS~M68<2@ z?%Y!rDY;E!O}#Q;b|&2p6Ty5>u@co|oX^U13RZXhFyQEYqA5l4vaW-(2Mo<>jaCN1 zwf0QsI9WeAwwAO`DoDewOQ33Nmd8=HHaxoep-V8&<<*~;5jxa~of@}3{7Ylrd`W)m zncL9$cH>>~^$@PTMJva$BpeqRVi4b+ZrjH&|KaGV*<{y=4}LdYIXd=TwV|gAPahuK z#p6!^sqUA;o3OB*k-v+cXv`(Ms=XJa?_;ctG4K!h?t1Q4#DC=Hn~iU$*=cfy(uw*MhTWIbs4qt#^aA3Lg<|6$NLJkS zT*Mb01zef`2KNz`et~K3k3pv9uGjQqLZtXlLK91Ml?Yi0)fF=ZxY^6Nq=|XO#g$vH z|9|HLOPBC(>6R`3Djh(8rJHj9Te`;3uhMOGhNZi_fPlq2YKE9sK) zt#ZI;ohI!YjsVB_aMb(2f@#3hu^ncSbOsL)%kWoXA2jzm;*3dKJ|yi+O|=+$<+E{+VQKJ2afBl;S(nGS*xuhE9)p|D4{c5bl)WpDGBkJq4 zRYEF40H5&t4GFH&;69%2kHK!#hz`&o7H3iZm?jR*$4cgs4bI0YN?vh=f3Z7EtdlYX zIAyZVyiE9LD=SMMrl`a7sqVedau+Mj4=BFF3%TaXPeGG%!cb1b0>T(Mio(tQ>u-S% z^eGys#|WpV=%3DB7wbtQ2lt=REP)9o?|9SCY-J)acKUlB4rt&ky0Qq~(jsux>;mFZ zxuGkmL~;E%wc}4{`A&xg#1=KUYW~y$!pdz1KZJf;qVa`Y!l-e6?eMZI=LpBmC75`{ z5kqidlFQbQ)z}lB?4Zpz3t=_s&mMJ)P+X^esgWQA-%+1FCcC?Nqduot^wQ$ER|#L> zsI)n*v4wbi^`0Z#SJW>}^AovWoQN;SwPHht$l`9`n#aO6wRXi zUvO_;Yc|sH^DTQP_tjjeMypET&D$NDi1=}b@D79&ufGuJLFS}=y>YDs(Fs4yU6bId z&nQL8b!G(h-&%?uHF+vfmC^YQ5_m(h(!%rm;Qg>ZoxR$)drySDAhG#z39O8VpT2;nbF`Tz>nK{s$L>^OR3f?bNG;|sO3}@Ve#PssIX_|ItXHIY z>nVfcL!Bq*Ci;qOPJe1=m^D_1tbJ27`YIu?h^YN+En9A7RJQec?y)uxgM*9y{*Yh_ zHK@~p)6wWpRN4dK@3r`KGFFDhwC^X-^Y>emu7=GjE3QGS>FA!W;b~iMF~;c@L7j#N z?fR$LY|f*bUrMejWDzv0zX~+rgaRB}e--RjQNSt~EtYNokqe0H|4O+%7P6gOziX;8 zuR6)Tt`W1XD|`Fy$Sp4Wzu)0dXJY`O9%k(J2&@ZWZ;cGB!;hS<3K+NgsgM}>IXqVd z;`0gYb-&=GJE7$cv@cckHS?8{kEflYD0URle%Ls*oBwt|v<$U?_`U-FZ~uGl)bTKR z7l$Y?JTY)2g-hSHy_5~2_S^$Ysnk1!}W{i{>rzB*+mUcH8zeS!Po?JY&m z15PSOL+Lzi5q8pY^6?6mePM0PR4;ZBUJrD`1>kH>#g7${T*&H(tuSb zk*Z&C*|9A3s~0!xJf;{B^`mEA&dDnS?eYr6+)27>;6jH7*@xqxzIAPs><($c%p9%1 zcmFz!V5kx8*HRrOUL?b&luw1S;D4$s4AixfukJ!nlGuEcvq@c~ ziKe&?+qk9Gs0myLWL|(WsdHml&0`_Phv8eqYK#a^a70KT{Cl&P|IeQHEMR!a6)NN* z7Mop2^C16H%AEdQ1wX&%&~n^|5zfX+2)=ujp=;#d5vm3EZ(jmoI~S^tn0&4tvQosr zuD5{r=&|kH&f!H@&JB~{IXdRlY=+^-XHS*>&8mLCt8zMlX0J|O^8T4E z+>SUllYbxXv*?oaWt)w|$@3#MQko98AStC{PiSAtV+(;X$M6MPxHfL+xLMED4+n7g zM*~ZLPOewf=nP-$N%b9%z8d|ZsITR~@m}iLVb9yPJ&eeT*RCRIh;AL$=hwgjvDdSH zv8RE*hr_@As|3#RR$u4Xll=j!D_9efgS1|JF+~FH$Jl~6{?GtJPJ<8Fbz%vs@8-Gf zk8S<#^-g_8Wt$_E=pncVfa6pu-hG(#7Y-(Ex;(O>?}rh*aVL5x7yqSPvxugIy+Wu_ z{c;;_9T(;Ww6Ld&+1|5>)n3A*P}!oi&d|0XW?sc{$C}PMhF{_3;&6ioJ^!M~KH^;J zAH#3&oe6!RUVWXjC=VvHd%=0~SIMXujR5)MzFzbX_>_>R`qmqPDwK{8!-=a@7tRs_ z_2CC|s+#kppW!U^*K z)i8XP1m5&P*T4W`q&M{qS5+cQT>mTpIz0t@Tl2lyFY+E3Ykcx*BjlS2vs=%C$)j`d zF+a%t5FFFRd_`V@Mh76|V%9MxI9ek36qFtKlUa91=0h156)~J(^fjiZ?EaC~(JM@b zWBR$TG5tBEq}FdjdE&N`8OxrpeuRv4$@RG%?P6uq^mb)=D^TNk`@Jarp{0wnS<%~d z?WgnWNl!a&ezmwC|4WPep8)xwK84^N>gBMeYg(*n91{#F?Kw{B25vv)xkN#*hXHq` z1{ab_%|e%GifB4H)HmK&KEqUyiQpwbr~;y9z>P-D(>!Gy517CYZXv*N*IY~}ls^O@ zb@`8KW`=;LfI_W0K)H9IR4SrNWvZY&X&jWce#iyXpBUTg0bcB}#BT=YruBeo>4B0d z2A~{8O&_SGz{iI1TvOFDE}+IgFFwqB8I-aAnC&*!wce`{5koy0>#?C%f2`}_OK%{wWq_CvNH>bJ~xdgwDz~F}4NP`5Fo%jDJ6BeSVdv zeer&)Plj^(Fix}5ScXqS8EdQ(aAr<$dGbg=UrHSU)~i33Rqr`ySMgdjyEjA){fRUHTAYUdC=AJ(4n?OjblZ5u?~+(}u}FA6(U6ZmQR6 zr|PuoOAF3O=i|^!|f;m#IeMk=xQQ{Gw8`VAv51BZ7FW z4Mm(Zile(P^ICA-8DzY#e@7L$P|> z7MvE|7_T3?tvX!quhUbaRhK34pkSoYAX+^ z4uir=)OdQf`MSPVOF+^-qAemLfyTBX36esly?(g!|Y`rxGOIuBi;ZFgF~&0WamF1G{216tU}+2pWniWPDFhmAK}78r4*W0pV;_A*Y zVPmzg?s_r0`{U5zUz16gU9km!f5wkry-lYWniwqmQ!0=mwYkNSoVH8C6;3 zcElJj^iA2@ZClXR9U}TpU;POCXQ0da1INlO0}PW_g*fOHR7?g{WnN}v@Zi_vMCfH} z;CkjL+RzK|m1ecG@(A~|@~JV@^_mw79Ng%?|QvP@Jx^1LOjV zHW)hHeREu64~^f@^w9NAw4VASUV{X@RNHX6Wa9@7;OaV=?|ZV2>^%!T)r5bHOArog zbr71hp1^0RX_v|R%D@OnIBI+myO`SM;KW)zLjLX^gp#3GCk%~s&KN??d)0rmTGo@U zPD;n}qQT|A%G?6?_a%{!NNb2;O}eo>2Wand+D*J1r!xVQD0^2Mpa?HYU!*6~Ss!7- z<-ja+)&3a2*7fhvwXJTe&+p4>cn+1g@O$ya&u*g39$d~edu;vmIaA?hc4yQ5Ek!lb zlOv471U9Ku6z`eote?Y*B)zK<-BDkc+N3q(PR=2V+>gRvq(T~4u# zuS5}ZD43p9Y9{Jlq8HHogt`Lb6nzW&{d2e06SKKC^r{F;37?QdUy8MAlj)DHk?1!w1&wa+w)|C zTxt~eWtZXvR4S$+E+5mt~7LMSE17nl$neBmg`((L5I?}fowgIM7qP0^Z@Zo&mb z#C%A(#TWf~`IjK+gwNW%4xd9E>-{3a`zYNlE{BJ=bUUoKI28~n+;x@kdm!tGNA%H8 zuTm0Zr(8AzhCde^vRPf>x;-O4D%nSm)#aDq)bP+ezVI#7;m6ob`LwkrzYBbjVBYiN ztB+)KBTotzp3T5@u^<~wv};0vOka7}UXb~ve~7?}enxyS2*p>YsKo^L95L4k52 zeB9fxRr@UCy@V~uq^y2VUEONTfSbn>)_4eK86>I8LuJynn{<(#=Q6rKo9()^-b`2U z*0>Ehe1Pl>#40?Ytl}_-xT#zs4WVlY)*9mJsPiwW& zk+@@oe93(Q4~0_UfSIXrFhLj&(ZLd_Rl4z$0oU%aOw1x8z?80TV8%u2iJsS}4}I@? zzFb4l)b`~yE4k7zPp93|Vl zZA9C#eRgGx{K_ba9~&KW>E`=~_+=phir#XY=Rq;{XQfiSo+rojeC$)RYvmrRLUtNd z+ElL7%bXWg;NIlP;X{f-#Zzdn(plvL5;_UF6f<=x1qbmo+8)Y1aP&q{P^2{J+@)6Z zg*%$wd0{6qXWpvgb*NN$S+g|`yAd?bO?|*wA4bNBTf>0nu!mqOmzT5&Om%brSC6Sv zk_YDlRImI&^LiHr2BVj`aJ?7?CU;^j*y?n$E-(|QhTB-jSgTZakhcuA8v4}1aZ~53 z&>$)@OSXfMKE&!|nGBN7bhh+D%C;6`-b_yAs)3nQc0b1L&JifBedjpVxJh%-!o+-Z zkp}my$pW?Ad=T}=otADt7pBh|MhJVGq8J%}wg-l331fq|#ft)hZu#oi6rV0%ZmV2d z^uC|xb12;8+%>DKu8whiGwm|#UcS_(OWQMOYe4%xj$!0MJ_Z}Xb6NS!=@c%!-p^_B zr$evKIC;x_+5rm~mSJNT!%zqryof%;8wFGE{I~ptA}2 zatZ%FUB@0nB?5smJ2tChkJ>^|xk3E^)@HnFKhzC(1hG&Is3T|b;kJtrIrff(^wv?B zOVycH9YJMKHj$9~L2dUOTXRp=n+g>j9dm;0ZOSA|0zLZ zgle~2E|v;%F^*}|pWjos((pA`PL0!Epn&?~@C28)Q{|PmdYLtQyZaKgJToJ%j@BN$ zS?#&DuqOLSNJnjMP#k6pP_arU^|jfZ!yo$=D!(^ZBFC$$Row;hNP z#&z>hSyfMGI`y9T7a04lz7=(nOD8N}K)l^ZWfRmF$$J(MwF1QnR!^>K402vTSnH^3 z;TMc7kxJAdxW-gUeyHQmR2f}Uvhl6t!>0wr-6`P(_yAK(9^C1__2GYS_hS#M@12G8 zNVthw&2z$h4|k>Qn27*!u97P3x`eit zPB!ypLeC%}ERs`^oNOoyj|_j+v}s*-#U~nPVyp6b(Z-NkTI+aV4K8+N@!Ch}R{pLh z%j-=KoWA+CO5Vq`Tp>F38`JuMXOfe4P`<%izn#!wQFvJ{`I+6W-$aT-p2oPbN@{!4 z(a6`pa<`|or>>-l3pJGD>J{U&Rv+bGWTlgDxIx^&n>rB+F3hggnjiiJDw91fq>~+*upy1#&vQ?mSLc@J-t&!b zyf^N9w~gnV3)q- zF1C&P8x0eDdg&YBWU-VVZy)!4MFVg-0tPbIPjE)! zNwwrARWB~C@ytTHl+XldlF~&e6`gShqL zUP@IVrKpX~Q2YD_u&W}0w}^1O)$akWcn)t+7LhTVX=Njmo({P=0b!v<18v5v zJt>b!om+tmk^g~1>+>94C*9&TopVf2YB&~dFW7Rh8oFU{Gl2YSxz4d8zS4u-BB#dD zN+%GL;p80YI~#%qU%aFl{d~`^z%wk>!}^Zjfs_88H!6*w8~&XOX9Phe@fd0C{(?As z(%T>%6FU>{-D>lG(o2YTVb+`YD79w@+ER;4N=(=I3o)rPDcz|b&{(|&-%l>TzIoqs zB&g0h-ao7?Xmi$C#ptms5xOBN2fE5nH)JV&G4jEA)K_&^r&?~l*kJGU^ik!*gp0Si ziE~Nyd8+RU)>=i}m~b@YtSx^xW@^1B>FJHEB!}v>lAxEO?RP#bYqj_~S*g1GYg~( z%cx-=rmx!PAk(93;i8HK=5R0Alw%G#^cuDc@L#5kHkgUKZ9{Np^+Qf4eCqx(cs%4w z$cMBur||EOjZ0ew2R|>KE8ttu%%~kgdheU^sTrQY>`v{6n@>5LZ)~l0Q+2eSALIMJ zaB~Xrbfi4Wo8Cpl1lwl~cPkEEB4H<=iLqcCGhIfAYh2@_iKNVx3*rdkw(AQPBFQBq z`w+89pewu37)Z)=sAhe{HNyz;IVu> zNwmm=f|#85ykWT(p!w))nz{gzJ?HaP;ujN)$mSc?=kyNzN8-;9g1W$IJs>+N0694T zEWS$gJmrTV`xp}FAa_xQ(v@@kwrG1-@pX*2g;;7ELH zxgRzz1xBTm_2|HKWpR7%N;pJ-AXvaOfuztJzRn&(Zh{y2Fw7|G;KE+)nH0=)C?I8u zyVQ(%2=W*-)?ja#+Cx7Wb(C3juqt<9?v;R&iPg>r2XoF_2WrP`*m|;D$8Shd|z} znKgWev+($&uJxmx*{xkP&zppwCmd^(305{H%`Uk+LvJ4E8Z4csUH3Ck$O#HfJ=5O~ zJt3;yc{tIcXQgQETFib>?JuIBwrX16*k0V1;gI?922Xzcyot-Pv*$KegplJc?ZhL< zq=G9gT*U{)HcJ&e>U4|1O1Q5#f)qP!DXJpave9b^W?(kbyooPz_lrt^B2B>mRn4MS zlxu{0OBamZSf-@Jp;uLRUQ$!)MX8M1^GJ%#jS$5eVk8)ss%~p4fN@B8913g_7I{8w!fMITNChfc^>+*^;3R~iYu$!=nfv+>brx5u0kDHQ<{gI zMgo7NfSiM`o4)i9g=F3l5W&1$NP2zeG*ppetL?E|z2^=;G~Q;TJm=NT)7SWW?|G&f z3;gstswVJuMs(^{_W)Br|J#C~H|ceiCdd1kuhTXf7PpwygiJN$2en&r35^_W>vBEo z%@qnCpU|B$JLQs^dYg5ktdvc3q9RZhIyXr-^|um-v5-@F7>C?~xf0#hirYl&pqs&9 zmtTd49R!gRNNJ%lgk>*}*Uhx86Nd4Um>#V9;C#YqppBJl1EvS)bd)Z~VTJGjJI1)# zQjHgo@FhO!v#$o!GF{jZQgM--L^?M!)CNML%j5~7HPpbZ1oPFQw8Jm~}}4O^|*vH^Yc`Z4%+;Q-+jq&OV{e$rT@ zDuz?+gB8Gz*H36yq5UG^}>mY>ka{NtnIM@$*$`7pqyHA{@qEG|UpH}5E;??#;xnQVD zog}HETW~)Fkv4{_*jr$l#kxHGOZ5lxJ&zB;49?;eBmL=AtdC$(yw-&)O_3!vqJ%5M z%7G_`V%v=J0Kpa>r3w%A5U}M!^L`XCQ{GB#=~R3-NnFX(qyGTa#?#6crrsYK_3>=y z%11NOG8S9Iyx#{Ub0#Sp1ET{bt?K5-$FEMZhK6gWSzpp5m)hoxGLVZVXN}g}v}L_K z|Bl`e<>_W%lERR_l!pp`C!+51KD{%;FQxf~=}9UoMn|@_6A>HE^DQ`5=6J$O#X-+V z=hi!>B4)LNhIO35leEBOD!Fi6pfU9TujlKLaWwz#gR2Q{dal3z-s~6kfbj!ivl199 zvEp8J@m)1FA;40I9dBt}FNL4ry#@eK${kQn0~0S;l*RbwZhZi_a1j*$=5D>|jbwi{*yaF{ z%??!YPJ>@X_-6)I@CW@t53#+mP;N~8da;$V+=zU%5OeXT)j;$8kH>jnffvKpPgM4y zlX-HDYMXdp5(A5@NQ<8_`nqZSd2B*S@T-t4Ti&jl@Ny1{}GVeOjk>|M*4!l@2TS9M9XZ_nG5rvJu;LOP(NywBwe8+CIC6*mEYvF z?*+50a;YBg8y1h$T%Tky^v#OZf_;4Z8!BiuePf>pE{O#RTs;fBDykYNmKEihU8TOh zm-Z^Z`~2tW(^Jzix0mkm`Z=U#ATo#S(U-G~nYi^t*2t#aDE%UFJ628@1~K@h34?R| z8n_e`uyHN8mGB}L*m|c7T1@WBOa%UBv5kWpOX@~qXN(Vx?m9UnmLcurI{2DLfq5IK zpP04Sij8F`*OLUA#7=Y#zSZi$WVH@~gz|mEv&j`6M~ z&KWwSfu2gGBj+kJ_G!1A*jsO@B9qy|0bUesrXC+!-3p_W&I0f_S8aELq?r<_xbA8* zt594~YA+{s;v(+!I48fT?(q>LPb}FJeVG9^A0%80xIb|y#R~Dr zp#GE}7Yl2hyHo)0oN4vlB`T|5AvoYE?${+z!}G+uZFt6QNSTUx>>#s=BDsJW{0T$F zYhqy*ZCp*OJ7Qh9S0_38^(Cqe#BhygRP{4SL;EUbXX}W#U4opYVX@}Xy+=oTE#WL4jN`DG6(i=E9zk$ z4M*oPE{#-qOb5`$k(KidS^AHpMmu-h6$<2tNfVoj3Z^5{2aWk}pq5wY>cz|Y#Eoqb z=0MMgX(NUZep+t=^AAI zmcB12T|qeP#ijm6mmxLo7rOD*zr{=QAN2s|f*?UNL(Z@iJNT%*B^NLnE&@geuy9a> z)tQeXXLu~;NDY-tG=o{KS-Y#i&5C`-kkp$8)XLgsBr6VEZ8Ig5M5|hEOfwfcLKq@O z*g7#!s`i-rX4#fJ4W0evR}AnOS%o-9;zs#YSMDkBjX%?!CrBAuk=1?rv zQp;J5#b=00&{#6{%}(e`JPs%p#lQoYAuHUMKVgiOBC+qGW$4BQ`P$0BsG0u<@)y(?AT8|qD=8&d+pdmXJaUDqK4HyA5m0*1c!;cl^iZzAyyxLe& z2znzh^dM{oM(J&r>1qUzev~9cVY^pyQ+3-Yo5%^L;g~Y~p*H%D&^T{RaXuc~{Adst z0VPcGJArARf@T}8lrj{_MK&Qe!DIX@N6a0!{%fM=fQ2Ji* z8%&5M1oBrHRr1Loulsto*4$L`Y69p!DC7_Woj&qh$hHy zu@LLv<%uMoMJe#cL|1ut*=}fS>%7#>G{nh2=-^?VVdN{H7pQ5g$Ass#@~%~+NIkq( zw$`K~#m6Rb`9q$THaC#xm2PC0dazcZk2xBOu6N-lCCC|2-791bf*Q7}ZDR*=)iHyP z^_;3BkJ6NtY)|fSP9mU@AqyprW!sno{#&ypwTL`T&tt&SyZqRTdIj&+td`EzI(8YG zGiQ4Rx_CNq_f=ptJghzYFnhpGqHFzba#QDJ=q zv}gxVW&o9~UIAxAqinKJp^ASBxY~>~o8jWo>|&xc?;W-ZlSGt)Ex=+#ZDJt6S9-ut z1=t`pCCH=M-r@9nT)opM0yyAsGM+?nQ!!SUgh6c5xq8z;ktJSp)OhM5G}$yLd5Mk` zdVoF?>(~^j@kfKk2`E+ej4CjQZi}xs&KuCo49Nd%i3HS8RZSb#F25hlgEv@q5BIHF zI+>`LG(9S!qEA=$^Ali|XDdN#j}=>l!UNMjzQZ@dq)e6#;)t}Amps>^n$?a29$Vjx zM$11rnO)$x@7{XKIw??5JNa_LBX6BYgx`xt>U-NO@!r0&$6jfeocug?L(@~~rM}|X zu>{Sgi2^&;jT;juptohG_qwS&-l@btIiYdooRUc^ZLV?@yPnt$6c}LSua<_4o6#WQ zZ^WRm0xvv+jTFlFGcENYoKPJ^1VRVFMwr%^m42nB9W$Wr2xIf%zD{S@qZmJS40bBQ zOWVUfdBo;JV!3G-SL~Gs;_hhg;casoS98r^3^>0mtN~T=ufYL=J;BIF4z;l~fJV;1 zI|EY28h91u0()U7Pcc3s1k06dPDS!R09w`Bnsnsn5m`gZ6;I3lCQatGq?Fw?mn^n%kK`|5mv# zhB26ap^Y&UF|?2G24B5Le6G&cY_`WFW`&6F@hJRaKw%X`oFT0M4!e6L9l)|v4OE!4 zA7DV1+SgNNgdh((lGzRBY)yC8l66jaoI9d` zUu;p_uWWT=|K?h??Yy?M2#O4z)w2BVfmhx{?oJ-=iV;ILIJ10zL3z+%LS9&CgnlY@ z+FoF=ex<-#DEZ+7@I4!W3FyTW^W|$vL6iZ)c~T(aw^$lB1&KH?Kf~3>_0$9LP1slNH!96Z7~H{4nUw$|wB+ZBH9d*Uh;d>k0n=Lc{8 zy5Ngmx%!Z#hqUt1mTp&<=71-|QJ(eMuj_lwZmNZ0R$F?^aL&J?XD@0w$Lrr=urn#M z!F4zhxeNewz63O_E9hIcec6}vqGFuESF8Fe(HjMU)VfrOAoEpXJ!wa{KWTPXJ7Y=` z4Emz^rX;Nr^UFZt^~0YYh}|$1^5R6crf!+XC0ee5sL81EecmiX9}i!slN|9rposzf zKFAC%nov`q_g9yD2oNr$hi|>h-{&8S7|y0Tpu$9H3fMHpcXRyEMUINC^ax9j~UR4r3;E3MK7S=%#Lmsp@iP%p|PeO3WWC6d`Gj+`g` zB?BiWJK5|&XP{vKzif#cgLfttQnn z)6()gpv8CL6zU%!#Dw@&JL$8}B|r>0g8nL@i#8+u<<_Ks=Q?!-Y5gN>M-JS^iKHK( zVOug_QUm}WEwF%LE4MlJ)XK0c?7nEf+oE~u^dRQgd-oSTwT(N3+R|T0 z_UFntZ(GBpkls=Joh!cjMMd|EcU0T8KQtR>#cNsTXdTQk(Y2Q6-dkJImExS_Yr6wf za8}3v8LayD`uoC78V#Ub1Et^4E_oGzb~Ta!+EuwhBIY8H@koAOwFywQ@AQo8ul^@U z?$7Yt-(RnICUocdX0p-oBeFob9EgN|Ka;y2LZlEp%FdXFj0kY{&oTJaxnBn7?BKv2S1`l|BdHmaY;zssl z=f;WsV$BADx9yHc4F9fEbjq|r+m7F(h(YRm<1H3;o#WSJmM<{cgQNGYeIhztavoro z>&@fjeEarA7+7|@xPRh@CFK`C8ayBGwWH^6q9)EiL`{E)oBs5SMFo={WsR%wcT) zdI;;_^nZ3v-;0IfX3824Tt4b>evTu0idT1nFG6j0(7ZH=ZemK%3TKAFERP!1E_CHd z4NFH=r$#E_=Xb%q-{hi-oG++EByrCSheyUtO2RGK_VP5PHT3ll?j zI2t}Cfc7Kp{7comBm6L>Cfg$Kz$|3!XwUuQKAhT`ZlBRBj;VVu)JKkBe2?Qk{%ww1 zP->pdwVuOzQXc+Vs}~ewza`3*UZ2}OXyt_s)QQ>sD;8?QR;7#NXu_xU06yrjK>p_g zF-BJVik33PN|XFhpdpL+Dv=op=)g`C5OcX~yc=$TIsK*PbrA{t1Ns&vX3SzkfB0Oqze%nPh1I8JgK#FNY(ap*Pff z6a^23wDB`CN6|6__in=&_2|1#aZ~n;6_c6S0T*hq@Zo(yiMqpE%qQ64lL$#0o=vM+ zLF&wH-Vbx&^JORuHKx#7pdVX30zUs3+BGvEwf3%nSW_bWId)oG-8Mp${qgYC@;eUO zBUvE}bM6owIdG@rlwY2?=vVx;GmsdpOi3-KXxq&*C2~nt7QOvmozu zvSy_j@Z;%th=rVh8q{{p#HjV806DPhh`#<;+UpGX2dr`nyY1&8*_IE>N^( zi`N1CIpE?bM)XViP&B>apEmJ7Z|Hx#Mwr4(b~Y`Mw9ZnSU{Xo1W$6=t1ol{r%V!sK zAAiW|$JFt#2@w`j!^@wvLJc4BuVeG)Y-D6np%1CAtfGyg6sK1f!0FzwG_TeQA}GiA zCr6Otu(II{X|KS&^~wcpR~8U!Cf&1kD4%_?Lx1DF{Zyl}3+MAIQIQ)|%C7u$VzRof z!E9Hwg+H}@!N$;)_{68g*=6~Wj9nG(TE3e%ZkJZ+`C{jDVcCw;?&Q6;)*r!D9sdLJ z{I{Oxa`v_MdjMNJAr9h9g^WIgs7y*ceSd9FhV6#l_x;TXIl_rIG`-VT#2z@XjkT7 z`z@+qO-%veXUfzI z&?q@tN1V-y4>(QH*fJSR9RZt4N7J7|uRre8zkIGAI|4cMg4R1KLYs?|QF`?r&=?1I zIb^;!?Lb6e1gP6Jk0?b9wT~B|pInSNh)le&$ICkQRg%Nr>4KLX8!eRUldZaiHi$M_ zqFHZ`@@3fmC~O7U+js3gb@O$m@s;`XEyOp*MD5G3<+dGOkdE2s4H2?#l**#|7Cr4y z*RIH%z~IMYh|_Ac*@Xb32xRc(PX#)uCr@!q9^Kp$gV~&OeBgLX?WblJ=@41-g~x{!MG-~ z)~Z5_jw%JO?C^$%mkKZ4((6h{`CTb%!IMqY#nbE|WYbKdrD?xmI(*m=vj#8OYN^|2 zsQPF|R9gT?GV9W4MS&{%vi8>E?&_+n&X8`4r%`Wnl(#=y?5S&r-en%Nup}mf;ZTo_^ll8{>nuQ2{~GzPtal#L!a376bzP1ZwAB5q%R+0`_!* zK2bp!1-k8G$XGd`M4~i1@2o872oYEk-=H_w8*xSwED>EPwZ_ZO0fo=&9e%XM*QoBz zys9K~xdP~IY^>l*<=|7w)TZ>}YKIGx&fPN$7QxKu{>vQ+G;Z)pKW;E>JthJGmL%_< z`KJhlL&ota8*a?rU6L(z{_%`t6nev#ya28_1~IW5uC^Nt%lLZCW*VnsSC3tW>dBJV z@}EumuIJdcN^N3xG?h(gSC6;u-fi1qWp}gGdOkqvT3@;HjQ}!r#~q%Dx8>fHUwUnH zOv)Vn?Ll_}9PjXytnsgNvJC$mAlq%a;SrLOgLGFHppc~3QF5cNG&=$YtTT1X& zjjTno1Cqu-zmcao>ip|nbW?%@Xy?cvXN@s+Q*}oj?-Mo+=2nd&C4*V;A+X^6Mv*PA z-@?`40jyc}I6ka3kGZuk9VGBr7+36-4>sf~^t2xbq=>)bW9{G&c22-gFd_^zHXe~D zDDrBV;0?5N@p_=h-5`GB`(xJ$Uiu}=-Ef{Y#Al4^s|Nc@!3q(1_C+A0Wnz_32cWT^ zc!=ci64#O^to)+>n?Y~0Zt1xCS(laewmC6HL3FHLQf#S<0h9GBHSyU?W(Pu`{S zgSq=_^ibT;@b~A4$6Dj=DfgP*|J=<_Q+pj&k)5aPru~Ae-5bVt+jArI*mK8Y-aB<_ zkiAm6OJ8_4Lirhfao+;?n?6UYU8RaU=O)GbM781Neuw*k3M-rP$YXkehy3}0C`)W0 z+yjTQ(?MGxPWlv4Lr;01o&?l| zdtCs(hP1h2wt$^Zr|EPF)yoD5IG8;8qWc}5)J%~Av|^hhR|DMZVgee$)R``uEH-+e za<4Y6ohwQ996aB0?o`GXBZ{A=s_?+paZch_&Y|u+av-1L-CVr9RJ1}I^ zK{^q5+_yozBi-$Ol6KC2xH|kP@%gWkB44*W`04QmP#Q!$3u|}+maqh|0a9jCV zX?Rv=YP}C{$hzM*`1eQ$oJJ;?_Z!QrS05a*Rd|0VdK>g zlSEYr!NdV^1b--0R8RnSHe(g4Q;~;mCT_}Z~avd{yvWo&^j<|r01nQefC&7^n(l1cN7&$_PBsVOo*m2DZ`|$HaEQWt; z^x9z*!${`#!Q5rWHt`O^ei*oj4=VDn_XvI1$klkNb1c^*R`16ilno~Y;Z09y)gKsT z$27Z#`b=CaOseanj8cBvzghWl_W}tqd@R+uwe48%)YMEfGWbz-Z-g%1|1hrN znzzE~vG(Wm-S%_A`B@E5h!^Nt69fk}?PAnK;ku7E{MPvuWW<~{d0|&|?CfdK+4x~0 z6q+1+J+9k1m|4hx0gFRcZ1>`5mxf^2-*RiIjK+C!ymtUkd=aAa16lCXW;Jads*Z7G z0dpJ889_g=5p6;I%|yKy3iv8!KQU^WiT3H#6b84 zi4pKswrHOtL{H~Z5O8{4KcLtVKEF2i);5>^E^Sxe;R;TTqyXZd{I} zU76NgiL1X&=0J?^reZVu^>>TR_J*q(+q^@`*#lhr4Djqn#|aMr1}Hm!D;prnCxo#XK%yfv%1g`Sq4@`Ri_DPSU8v)13#qxLN9YaUljv%w zHCOYE;aiuV>^JNMpGyR2I(D_u(-AWC87n8Y#IJ1hl?G(y_iWKc4ke!8#I`upgjJYk zoa#)24iK7FlxYiy0+Pxr%$H;7^F-<6HwHbqzB(@njLJh^OFhCaer^pjO@} zZVx*ST19W2q(GIH{pI*UG<=*=o!NvQO!pP+FSw^UVEH2f5FO)(tS7#6?G)w|xPW(=1ztz z)5>uA+05z!Ygci@efq)gecN}Aje}k~3bTqr^RaKliM(y1-x)k*`g(wDD%yPS;7>^3 z|D8oY9GpH1F%1lu#qu`K&|uTrihe-i=zv>f1c42(1qWNBYtRn>SrXJLmQ!8Sgc|LsBI18I4&h{8{=0b8E$68d!J^Y1Q#v&cc9!?-C>C;S8)7#Pn0IpS3M zfOI2Lo`C!IU2#Mee5Y7mpQ*nAR1?%kXJqmFJiF>uK`;Bm^~P-7kxieGZ`HOnuxhZ= zf($O3q|-|2%3>ZjNT8FwUr8VRMwXV{TmbaDP^2JPOG+C=F5$799r+Xa=KU(F)Ov3VeMVj~m!)HGRimU>KP;~?$|UDq4Gd2uR!)zKJ+XD@O40sf7v`E}xs+5E$OuXkRj z(@a??xrh@y99UIlhL?x!^%aDsKzNcJW90X{kEag-%`a+J*VN!i?W zcW(RjBToa*R~?G`kEp&x*r2kfEPvvJccArsw+~~cp7ZJp-ga&$E;Ni8OYMF^w_|np z2X_?#%eMczy74`THF$FHUpQfYo10ehEB+P83XFrkXNCDsf}=l+kN$W~^nrmjAY&R# z0e_b!1a-^O8l>3nIBCEp z36y#p{N~RmX;rWmp!@&6v+Bx^j3MBaXf-3ci5Y1BD&c9&u_Cl#9fFZ!&@HtevWJ$5qadQ(g+o|{$7hFl0owSycSThA8geW=dl37`+v!+|690sc9)_( zZ!21jzGKqkXpl5#*CCE#<1YQ5pIq}W^Bz|3M)?bVdJh*$n;eN(@7Xoq5!N^xHMRKuA;C@thg2AwsG-*m$TagDyL^+Ca=&4J> zU%?n73rsxp|E+h)iuFY;nc_PEACyQ-+F-Q$tLc7~a9>F8dZ~5)DW?B_2lz&SBIH@h z(l$i~-whq0FFG?4uP~UYgEsJ#KPkFG*e5V2tb)d_fNvrVcreA=K+fNYi?7?+aCeea zt>0v!>)B;guKR3IA)z=wXc)KnMpi!1RlM%K&eF%K$qHkkEGy{*eLxLE>Avc zx4pN#oDf(RkQgYH7ey95#kNB^Cx+ zDnev3>d+`UopgqhM1cSjIe446wYFtu$b3ZDV3=EDn_PtM$uq9^mw-j#J$tF~7rUdZ zj|E+)nVQ}B{Dd>nlq1z07hF=eEahWcUXXAqp zq=T!f1OuNn1}|goFhohCtBareN&=`|RV#mroZZjpJ5SRZ75 z=J=UWSwc9N*iHfiU;M`fGy;zGVCj98I9D1Y$H62Eu^iRiyHpxSHd$^Hu6jc^8E5=J z*8qvEZ?^xvAy}V_16|DV*W1LKEM=h`Vin%b+o1qL>bN`nfHx+T=|9pPo+{PJzbQ(; zZu_R*RDiAH4viu$5=HZ zgD#*0pd|vvjJ~EpwJzO4g9^NETdkT2j9@oJ2ZO|xv>D~w=FU^i?4>+3o(|@f+VS*A zE9n-26qSgXEx_gOLIGrBi>`j3IW@q+3?iS2*JtuAGx-!2%AU7-hHqTm0~UBvqCs%h z7cw_}1Ag}?TYx{mL9?+|*@~J*qtSQZy;>f53$f7=fc|xkHPIn zVBFpIP%5d>k+|b{Fi{$6YwT1*CNkEcR3TjRqmdeUUv+pLo0MQ_5@^Jb03duqDI{p} z-L&t0;NY6n6Z!AG-`Wp7r$E-)V&piO?-iur^vfO@(E%+hc=w0efbz__Q+ZezlgT9s zx9=mE;}nCi)$d29b&aRDlws|mzDU@|;!!!z5lFu|Cz;UeU~SYooFsV^AAI70$x9hu zmJC)V*B;>|r_Fu8e*cMPrS(Lw)t>ozPAAX5dYGXvZC07yI~i8C5h0nu=Izau)g7#f zuCbu**sOf{9^eEkok4|cL>64SQQ{O)x%C#x8fVKDU88x)S?|NwJL>LhuIteq>i`yy z{lJA)R}8e3uyj5F4N)2~NytiaoBklPMNNhd_ZJ-Zh8J5cRcau$R5p%msnZMQhaWA) zERL~WFJk5jaZ@f%fv^WOWu4hFVStbI4aI}7G?tVZgX+hV3E>G6|>`xTVt%yg}} zyy%oRm&y|FBQ;uDZVeh%>jfDs4e-shUE{|1Tq*Mm3LkpBa9{!Z-j-QV~x0~(Lt#cxQE3wA&S6y^X> zBDR2C1YTfQGKTZm>2XNedLVUZq(F4g-u1dzb_R*ZHD>iyv1itkn#?&2wE;XCD<0u( z$jB)mo&0Q^k=0kqXFM2>+=IoeDq68@{C`-|!2ndoSS&p%&=L0<1gfotS&>xYE0Qwx z@Gi%kQHOKyi3)JlQUBZacpL66sPbWV#ks82c%k{|nR)w~x*ol72T6Bc{LJlNNe*Q| z!!htfe;Zwc7tfehfouu(74V@(HRay1>)gf5YchAna~uM=8;dz_%Ra`0gfI4N>p=x@ z$vt_G>au3dqvkW{mj}0mkMAycv6H4%9`V#}q7#>sw$)cBO|4MDt%b8^y!S?ljg03_ z?VkHZ9!Y$=Jck$V;n|_Jj|*wREh0Coqumi9`o7)s@52uDREq+B?h6-Kc-izBX1B-K z*!PAvSPz?bpq*I}(xyAB>8zRZoe2}KXZr#}zLbAV!|%Z792+SycX76J3T(+|IT*4$ z9E|cDg0i~qg3MLv&o#zBzXqj=|EDF=e+EYW{u-G{)BwibGlC;PeCZ02#Z{Tlk|r$I zl3sM-4}mC|(w=}^OiuhR zU3_!j>=y&zqVfSf-Oa(tJs64!l1*(8wksea>-a|Rb*Lg?@2_=U(-Bqs6& z^4`b)mRbH?T2nol9}9!;lOACsK}dNCSe=hR0L^In2p{0-axlUj;4+hjC{P-yi3y#q z;UK4Hrm)khNP(Z=+vAWxU*Kggej`8+ph1K2nd+9wo}-dn0J2>UA-=*^Vx~srfX!k& zy>_%6lgOxgbzXRwXH;I$$G~aKOiM!dJC9;Fc(!d~3AHzTOlm2_`ix&SP81$07(8|e zcst@B^1C7w`BKYa-@mpRBra*_>Q{;GLZVMAdKN_%B|RW5XWmAhB>ok%^OY26gM_t0 z+`-`gB;E+jo$I0Liyy<8z^c`6Nqrtg6I(rr6#d3QFR0!6<`VGhpNIdSU;qD8;a_tt z|6e;5zO~xZ5c5Q%)&t;{SO%T-+3m~eixM*@B9wT>J1Rk zM3BSUe3h`fy%Y(mZqH|te4R$HGWec~N&N0=fk#eJzxiYdKpr))5;g~JmUGOSnVT%c zWi%)KL;9Op#?t1GBm8f@YUQIAEGF;3~Sq zSjZy+tAU6YSeU~9K$yIlB>TFXWo(A-1DUdV-Tx2r<{rPPIz2Uo-{)V7*2DWYF zHexs98_k-61~h8`IRTn=ZRy`?0N@6Er`Ok;|Bfpp`Edj|^gk7|(0n%(_~XkyLfh-o zFC%BeeK&o>zF>2{{@#L7kN9qIFivg+I)z!A&rw)m^7$FTiYC&8#h&{~I%({G)FS9BM5UG{ z#BStD%bmh){e(Ru>rTTPxVS55DN9v+GSiIF#7I%o;=N`Vr`3n5#qw6RD$h)>20W}L z3Q!yQBi9jhpooRqWT9~+5648y+=XYj!Rv?!IKT-CNUwJS6{fK14mqE?p6aI}j3+c) z!>&3}3THig3ujF-<=%S-5|RBz7Q2}(M>~LbF-$pe%82PfB33WwR>G>P%7(8(X~q8^e-WcH_eR_B@NOWSO?ax*B=(at3LF~MJ|r{u}; zwn0`=aUYYb?Mz+gtE24z$^hqUI!)d96EEZLgra^gCYRcBRaeIsd+Ov!E#!B{C@3s7 z6aawP4y9d;S9F4}YEC^7_>Sjp=s!zW!HPT0z&*M|+`OM6IL_pe+oElloeBF#ByrU< zDTDE3&`VKqlDHF!5m6J+!P1NYTJv&1JOP7DK^@3DBUXVJ&8nEjcVnq&b_ocr2ndcU zvUxduYC+&Kp?t?z2>^Seh$Q0bE}=G*G}Z!$CWiV0xHh5;OyUiXa>L#e&OU@Ps?e7g zFk8kwb29^=fEGa6qif)arVHq}N<8!~aQ|{H{WY~ZRX@OG@b$4PI_G3vQlM}@ED%la z@=ZNbcw^k&l?eDCbg)$#BjwyD@HO$SV2hA+rUu&Mvd+lUs@3 zsAKiRw@winxApexPe{uw9Qj}Eoq1G~*S`L7q>6~hBv4320ht{@Fvg@}0RaJJ6cAF2 z$RtK42@;Z8Kx8tlGE}CNA%rl9%rZs@LzN@QETBLV2c}4(5?;yR-Q08TZ}qhJyX`uw z=k~7aA3)Y7i^Y1g-*@l*{XWmhrY=VUde3>)>8Z@=jX`)Z3Gwh@ zQWO=!8?5bMJyTt3o#_N{N_hjD@5YiD}p-!(KrBDrYM*^o)4` z&ejnq(F)HCAZ#FDFpy<6W;CBpQw}>kxdWSM0f>95QZbWqpkzHf$2eFLRpgJ9=S(KQ zMwoG0PbO6yXl+Yz$4)c+PX?d4;TSZeX(8@vPtv>cLx*E-;%V$DfRe^~*FU=ANQwKo zs`%cf^hTxr27G6Z8l_<%*(v7I>2fb1aCXU{7vGCuYQy{TO?NzPa4K#+e;YIWLCmwL zyaNs35a$4~OOqEyWP#KdSB?ymL_f0sEo+2r%xM`mX|mz#Ljjg`9MXMK0&*{>kaVX! z9^|VH!4+ZojgS3U4_z_lM;e2hmkTk39k56L+oNG4|F3$K-eiQ z@BzrzrM4pn7!IKOUn{Hth{b(^wcOrB2I!yQq*!RFXQCcADYgoWs4|-o{w-2Bz*DzA zYTbP|G!bD_;2zLGXv>szgGqyb7?(agp;^x@ZIH;d#ol&HQa759YRpLF1rdiU&wQS5 zpKm4WW7|SV?`*g;Q@a23tLv!-^G~nPQ*ZrL46n#?GQQ#RJd;<^efGzp&cR&YI?wFQ zuAbV}uPkk}gIgcW{0MF%SK;Bjro#-ocD7ds{s1%zGVUvU?*beO>_(uTTISIk%&{(a zD4bO$Ki&zGtQj@rH(R?j3@jcu?0#g?id2(9f3`@Ffp(n%sb3V|40&3CZwBGsppHqK zWg!K`(l4DVu{GMI*u|tcYg-xl4xTD8EzVYYOmUWpv8{5UsavItyLH;8S~>(rkDa`g zn0l!E@};0G_oQ3De5(ItpW46bB(J*6{@XJ(QThUFunCyt-Ck+^F{Fe(23O?@EI{UCO)@`Knwk{}xNwAFQK^Z6Zw*@=qfLuRrre#_7= zPhbDd>ospCS6gh$DX8D}FoRu0n!T6Z)Jh8b)US5g=CwwvGcCtMGcD&QUi~rI z>8Y_lRn&@x9`UtY1%ccS;&r1BVmC;t)lzZk&Yp^Qp+x=>DC7(j9>Q^9zMw@fj+aaO z!Z@j}P%k4rQKSa#KR0;sRM?DYqrd_(Gftk@HEcf6MPx>yY^v)Lryt3fHVlL|f>u8T=PuYhq7tyGv)-ZN++>NI%L+yG_6_P*RT~DW2FH3-o34 zY*b>?Q6@>Iy96RSzP}|>dArhM{vL>!pky@YF(>B#cBm+HrokcC#Iy|FGUVu#S7KG5 zWBD+YVqctX`S?tKG6GRB-AB=K$hXZtWTp3v8e;x9b;c6z=TKeLS$cL)(Vn7*o?{_p zyKl8SInKF+Y4_!uV245PaQ!fcOuTv#uWZdfB^qf+kH+ouo02dX9XQs+oosso_SmCv zgILc)oTYZDYfG?ArJSl}*mdE0ia>Jtm`jf!4 zZ5C#8__pAZu^K0(u{t)HbT>jYP7`D-t4a^(U&I~x31?i%SuBhtPfsMTB7N>#Wo+cD z0O#c6!%qH@r%RoR>mNFOUbO`^6rx?3m6^g-B+J>HzjwR-n*;D4aq76J6J|J7dGhw) zkSu_moMUkJTkfHce?5-XDh{&B!sn5lO?Gr@@6g6(c_VcF96CYX%}W}90op{gsEPXE zy&VRd1W^#36W&JJj*#ItT0xEBobh(gwRPO#Dk{#okKm13^I)o1Y80BB8X-36Q3UW| zJWSLRqE9Q&t%PbAL|OlnvmkrK=cmN?bW8U?0oHtsgW%Y=~r{ zMpXfyc+29#w+#>!RtR}nKdw&naOncQHZQ&@?g%IB8ST3!orBGsr76%OCdQ$pYD$DC zr$G!(e`&%5ibo|jVxaKedFc;g=EwLu2}~oLA_#%hC$2VFRUl0M+-NhNjnGp%?W?&E zc}4>!m(VfAIh_+w>MXtvt$000V%>G8y+8V=YP*olO)`e&oZ{PzK7ac9eafJV;mus_ z>goP+cS#@IK~0%0M|LnP990muYO+-O5@$!>lN39!!Y9BumatfotYNvFZ#t|xoNYG6 zHtxJ)%#NE13_~b}@QvMP4LAheGj3rrSD7W%8hE(fQ%#tOvt|a$+~?sB_vLd9ViwDk zUGGBVEh8b*B3&q%xghE82iLegH%6Q{&5_}ro0LN;VEG+NOE+|paGVkJp3%DzXFG&5 zq6ka|a83;Lx7~a_XnBI}!qKF=qf}fixYkq29Z!a63=J9-_Y;=D)F&|(y>tU%vDuI7HUo45z1OQH;Y%L<)rnHu{BziU#MqEwwJ+wIn@KxuGb&yDvvzIJ z>Sj`%{Sk{Lj=^P~r4+a7S!e2@2S>aQ1@_vL&C}@$_Q6H04b^@f-Dz10jkcTjCY(yJ z_+!h+UgRIp_)Y^;HYj|pHpN$+_un2Q{C2T-6Bf|C(4*@Z>2ziE=YoSP2ki5caV-ZQ zBX#k;A-!**HmRd?wQ^z_8Lx?O=G$xcWX2wQqtY#=A3O))7|>W!}r`GbxJZ_ zt&buqYTSM)%IlmQzXWuA(KFOI`xGXf}3O$|*H;TCm)-H7*NgnI4+ z@|cZLT0C%b1~k-Gl+V_>iC@F%F<={^V^$+g-Yk+bwy_;l0T`r>ScTRr8)+<wR8ENVaXC-|->uubLu34+^{1-hB%*i5)semO} zmp@-GEI5=mH!&1hLDdT2bf(M>lxST}hNtMXTny$@E+2r)624zvH1j#%xE& zA*;XtSV^9!z3Fq-EEvC?+Z8Ja+1QA>W^|y4&~|`Xz74C{e(>#+SvTk0d@PBs@W`up z=E}9(C8JOL54IDlX0O;hPs^jXBR?OkM$2LGbB>(h#(e*gXWlAm%eJz!t?#nocayE0 z)Oab{4q5&V8BIQ$%uij^JGk6~^3S#cedJQ@KB~48)dr)KQrs3gYYG6-rYCROCm#QQ zwZViv|4VhqpU&;s3(2U(?@)oW%e-%YS4!FlRI8`D*{aR|gDjKQ}}M_89KvTWg^0NAEB;jf;JM3ykhq2qd? z&&*#P6OC0@iiYd%HfPY;(qlb+i;Du#ooU^O7sHQFii>vRCs0z9A%Ox%iiu1O;v*&? zzLhYyWi7;KzAj;U)0%}pu^uljNIr!ypj$2*XgHpjXt3=}ce$N$vM$a`l9x%ye>PLg zJ78D#LCgZhi4}ni&v(HzV4T`1)rk@PXatt4zq^jw6!<_N(D!iV&=`YKq%D6vNLXd; zAC{(_ggTn=^YZ^RPaflDeh@2^v=FQ^2y7E0>4HEGv0Vx#*a<>Mh_UGHUqDB=${j6R zMg)haCKJL{Wp8zD;(&7H(7X4g7jUO@w#T(kY)SXH*XN0;9Xm})sMd%q$_*+yRz(6$ zyBGuB5-?Mxu9&Gl!yh2LYb{!BumoOB9U%BxJ;a^D z#K5H47l2_C&;qNbE;n*Qrd}pU~|T(c)DXVPYgAI_)vL>a*RWRbnWH|TnsP08QRAr#=_Pvu7tp+3qEfV@USXw9`aIX{(If4*k#o7ZVWlH-?w0bt@>{52l zQLKL$x>G5Pfhy;p2()`(AdPQD)esT@*GOrptC?T}Q40m8!>@IX2yw7#8ht?qPmi7o zZ$+=SL+^pyI09d{4d2p)Td{`X4O@?f3a808Op$^9? zI(Ktn8EJ$nANDS;csr^JMHFd@dSJ5nU08=HG&?$oX?GR*neYz6mA_lyC?lmLjVlX;Q*K}umYHCc}SrZrc?-pGm~XJh%92)!nlm%z&l^SgYE6iK|xnH-Y$S# zrZC@u>V(0V68$LD8o@orlNzd7ki?F?1v+?cWCvkAA`r-R4sBqaC(=d>S z{T@xlcav)BlI|b^I7DY*W|R9*&^kIwiZE3?p@6>L;L{~_wM8b8*-om3b%A(MOXw(u z6XIGogw%nEZQ(@DJLuL4?pHKr{5n7Q#$*;hKyT}kHCOZ7SM^+t++O_8q^ikI+GxQ2 z$xY=gIym60TO$JMNC^Vwy=eE*`~X!cXamQt6SViYA|m()1y+z=F6eYFwGp25vQVAi zJ3aX)zyYVwBlUbvL&^c1!}mRR*Vl5Tx@f9687PXS92MR^p(PCZ{TEjk@#0#R_R%`c z*w!hoOls;0r!D#+h}mGO$(}bO?cY#*;Qofb#U`$g=>s{c`%|64KCant$izwX^m(jN z_hxIveJ00<>N{iw;SBc$=cwM$Aba|3u$DoXZBC^Qh0jCj4I@C^H7?OLcJ6K+{ZS+n z^BrO*2yQf0)&mJN5_sk5maPzl8R^H2S8KZ2-Tu8hPHRYiOP$R49BEUHjcSApU)yBo z^6M2-?(dv2#cK6lpFOKn3T0`q{cH_cN;hM`Zuy0grd8_m8HY;+vyPX-cIQ-Px|t0Y zP2Cw!*0i@x(bSkca@^rktkn;W4Eq9ac&M-GseGw&U(ohoNC=xhh)us(K`5BQk|u?F z{ZXroef^Kx^k-=H0$7W6RtjX>1m}SrDf$#JRR4DLr1;;<7QbDyVXLg;Vi!ceHRjdu zEwN}IRfW6)!nv9(()>8HcRii!#fyY5fB+)CmcR~*WM*4w2!BHE=U*I{0~ zmG@v{-f+0f{t2uy+P!3t{spybJ&{ErF#Y0aDh6JEi!TjiyaYNe7^G1d5ADzb?|GpKoUh5m)h*ngH`qOmd zAZx#KwI?4D9=XYcG=2TN-oD|I8%6KPjM<`xEBbGrI773g{;#@Euka_e|ksA(%*x*tT$OQj%7Kss*G0 z5MIPdy4Un%wO|#|Bq4h^3!2i2v6# zh-*B}@@DY6;#S}e{ycgtS##gKpy0VcLgeY zMBF+0%%~|1EhT{0K9-XR-0c#qr7`mzC7>(n-QtThku$BQOMllW|BMu(ki1Cct4jnw zqzqQ1CtJ@w07-_aHM}1v{jZAq%w&63Yzr$-iB-QoNhW?3b+?Lq;$xDDJ1f|vO;A-Q zZKF}3Oe<2gk&C|0;Fh;8NRL5R+CGSx4j9xNhHVg>0}Sq(pGy~THYL+=+3=ugx2@!$ ziy1d6&PujFCRf^OWT;~j&elQQLFN9Qiix}c=w4XzuH$`15Kq zRUfo(3`Y5F%M0Hj*9x|C&LWougC9*+XDW11OVhBH^v=*6Gqz#i8JaF79}GC z?}_^R1wKrJgfVks0me}wP#7ORbtL%hh1bJ#peD94@RWKaT{8-}sLoDJi}pZWjup*s zkzaUX#Thkm@$VL@f1dQ_T+Rf4U_^C8Gk@n%Sr}%x27UeeDDrMUeOeWcy4|QMzQA@l zu%*Sn7jt<0Mabqm_yNfW+Chos>P|Ly{OGe!uH{?J)SYs4d^zZbe<-K&-odWrzono2 z1^9S>S@ObKfE?!53;};8U=Eu^Dr4uHv{snI$z_Y`H;;vdhjG^dDamf=9oINC z7&@L!_>y@46n#=tVXo^a<$?K?v6-bo0LcY&di7`VYUBSRuZCz|uGSYylcsa$n6@=x z8-HrqK8TdYZSQ|)eOo<*{D^sES0}n!ax&rTs+gbckC;xL7(u`^$lC2hqvqk8#NB!8 zPdiM&S3s5}f@ar89u{L$^;E0;)3;4*^~mOEhYpJKW#^zv!FegA^|P&$x6M!TcU zztHXfMyy$p{R%*4TkI zI65J{o$}?Nz(AGE#3aCEn<9CE60U=xN8Ft%Dyz7!k_6V2CsDMMoZ;A@kPz=z53BaK2S)f}hPuKnflHzdR= z5IX)Iv{n+ z@RF2wBphT-8}66;ey!u?nVGQ23pH~i1pSH9&V4t_?Jvp>dYi{MnGpiCOtEo$?5rbA zv^pJ27arNy^!L92fd3~SJL0W2uJd!XheLY^?h14(@0neZaZEM1b~((3+w(8?#oRi1Z@>^G-bMYYvXPDnC}`~3maT;G$h+kpP({0w>?&MZG?{bmZyxYq2En5e0W?VPc{W{vYJ!;YH<>3pfeIXE1;``VM_yH715!QyKZ zV)D(1bhn@K2Ki!FWF}^$kcdI%r0=6DT468e+FHqxwXDKlQWQ*^WT!_7(hq|Q7rf^w zF7Bhq9Dt;{uu`=8*w z@~6)d6NtnKXDD>C*Y>uN6h-nl6R439g*siwm5jS4(gYq6B=WIt7~fj&m`%-y?mL3q z%$3^gz*2X=vD%We7%Kfj`rT3gE3u^^r3&f$9xzbg)LQ$3K0bt6hQr0dD@M zskqt)@n2x4KPRi;(>4Ee%~!hu|Hp6tn$>|CtD0Jx#~E?0li6zRdd3P_1S ziZ%qqfPg4Q0ttjtRHPSBLXuK?*;^%SO?S6-zH#sPzT=NN-x=fHKR1m0S=p?y*IaYW z`OIfNOYvGUh1lrs;^u-_wR#oeC-@Jcm_RroR{b|W-zNEQPO)m0q64A1ezo0d1Ep14 z5UVv;DQT`!bRkd(#HzLbF*oA>`K(&4v}Wx(<@GA6YVZRs8xgBlDJiX9qqKJInliks|Rb4%O14Hv|7TYbY zY;5=29k6$B`qA0N^(QxXA74NJfWQ+$;lD(jj*N$tBt@M{I;~eSN6{qcJ=?)%KqoV{@1$3 z5$Z~-;LTIgL|_r}sdfiaLiSV+UcJ7)-GJl@Jr+{4*_!X5uqoOa>Fz>7RW&=AIZm>H zs9@xA7HbHzL+T0zOuaqmI><5tnB7SMdU~PON5_~xxQ2$oB@5PS>;VNLtpIwVK>YMY z#-sqvva8syb~Ump%3n>CP7GyXi4?6s+|`s20-obrR~AKeavolrWFJouFm)i2b3gkO zeu6139b##OiSSC0Q|IKaC$it0`%>CQ?)(8|#o?w}sU%8V-CVTDXab2OQaNNS(4HcA zeJ?Rn8Zd>*yzpj5LvWVlVwI+g8Pvo^dU*E)6n}}dRXy=*aPEsnpPSbr?4Dlj1^4BI z8Mt4_iRSI{arM_y&gcoCr*S&{m_heUQ>{oq3L`)-t1P8#t<}xc1CK_#2D0;~^_}f3 z-CTCkJQWD8yY#dIQAv`IvY{YyCrV~CMETES!(a3yE(%0vumTaAYb2(~YH1z#CISbU zN-@D`k#uBK3>Gr;8)ip^5QMmEbZDm}oH*Jwsq)Hp0^m2D{VicBN3J>~wN8p)NDtAR zKs@))>UPr~S|O^i*TlflPDnY!Rv@l+NRMQT?~YR7SJIGo;kC)zXYndzD=7-nkT^k~ zrbeNSG+%w~Lw-SI%kvzI4Z(g-@Rv@qsWXtG?GD&CZ@<&#U=wyECL4jo~<%SbPm8@A{7 zrygPF0&BC<_O_^&&c1ijOJ}4rvacs+DlIEz&O z1Jr-BWr(@hRGv*b?sZctU#pF7c>=!{wLoZ#A~pnI#^*Zq$aL`o}d;w z0k#_yEIC9TL}@D!zhG5jN_Wc`%Zq9}z8={|ih)KeN!A0u^vhAv_$E|li;C1hSa0U@ zaO7??GqtUdM;q5V369*h<6y5T5KZjvKFvA9T@{RrOPy3`2dx`59?nr9R6Y~N_~IR{ zVBeyi2)jW(irEkLbmH`-mq*F!QF23oy>Joib%vBhJJFrw0}xH(Fk@;lDz_kh;+a|k z&r4SWC?4t>zp4Ay9m0jX9eC^m(Soig6Sb>SxKFdmYmpBlO!oOn)()mEGyv<=rKp3p~lyDhRj};~VyS*q-5! z&s{W6{qXKcRn%$y7|4b(RKy4^W(-{Tl|5_s&&^wa*P%?6(^{reFgD~jMW|eD7M}0tF&^3QH6oUJudN6k4K*T2c;fK`~namxZcF|KgZg)d> z`B@!RJJRCdXJw)9nNSt9`wrb;=vq;B++{0+>Rm0)I!o@U>f1bSpNiN2oe>5!H?&}y z{PRaQi_`zPMYZJ|3gCw}m5+wn%Zj9jM15l^Tm@pSbf@Gb`59Xi8-u<&X$CCyNNCwb zZ-SCIcw?zOfV$4w44=_a+8VO%3CMGC8JY1lv~Efk&Mmb97lJ-y>dG#70%`T;FR9^T z!eXRwDf7l0?7^*__*C}BWpv6V_M#R@2nKewg6UkjF+j+244=ZPL0Exu7c;x9PKq7G zY$Z~7*bRC;re=i#87=Me6Q>^XI*^~<`~>YiYO4&~V$=jjFU1XprkNpC_Z6r-4Jh5F zEmG-!uRxr75r2D^gSSuJ+O;V??_PiPE8AB4G%V6ed)_Kv=VXEV$>rH+<<}be%dB2{ z)re5_?_QrARMUTWg!G{uX>zUjqk3;7Db7|o05J6X}OddNeBUjy;QMI#AJQzGS9 zEASyxfc%ZWh81>ihP(~b8O_A3pVezarS_qO6li;2&(Xdt2kKSK2J$o0RbWplnr!(3 z@aYJ(0~LtHLk#Jj#~_lLzCeQ=eO#`A>uT5P$426^_7PnLU1S7%)Nv03O5+BBNjZzG zczV>Wq9kryB)8~8l@PD~^IX4}nDweowfWpb!?9ais%*V#52)(TjYS;u`^jCi&XX#> zrDsq$kU!fqum48(phmj5CO`Ft5&G58Z0W{_Rg;4X>w_b-W(pBv_Lx z&qFM0hSQWxQo4ufst2;p7mm0|~Z+7~MIH5xAj(3HeQ~h9~ND67i{&rWLLc^0#a~E{*Dd zPQ6cn+ zZYX^Fk8PMZg@!B(c}N|i)r8k5B?7A)h1HaAmttf$=xR1t(2RiB=EaaCi0244(W{Bp>d0 ze||!s;wNx;9u%)vAZ8{j zzBkD1#irwd<5YdA@c=spZ*)THE^EZb^`)cK7Zixo)HJ!tARC61W7a3&b8bUS5 z)Z=8+sO_Q|bY(#-WJL@(oauFtUR-w#1z@a}u6#j1#fbb=!8`z96)(_bxEB zjn}FvP(P&ZVxi@Iyx#M`r31$dpU3aJTjxXH&bfZV>LR`6T|&$|zo_@kR(`#8-d%kT znx$r1X&j%due?2iTe_PV&aRrv4=vKgiGHqb4h6F6RW6BUwnbs!iIe3`>b7TWFg@Re z;@=yr`*c}^mFkRkQxG3WN0}i~%{YqStJJf(pXCG^!MV4)BvMe=iB1)d!U#Zth+rBM zDINRyhAbV)R;X1#;4(KspF$wfWjawufjC3WWUs>*%$sf-XnB-K7?0(A-Os2XI(3%T zSIQ?8h?abmo_se^%^BJW1Pg~ucgk9JDiD$ICRR<$Dq66sp(J-8q;bZ* zGp|tM;+#&5xu1QrD)YT?$6DXo1FuR=4-`8)e5!ISy694GKTs94FZ3n5xj+vcKU{%B z=63aI>0kmDbR5}QroZNi!N5qJ%qQDrg)p$T2Jgske3FDJ5Q1pQ8p>ya*Y^ek-lKYu zkTtct@R6($qYa~_eS)28-TV#MNc?!K(6s}VGblX_6$(*niFdkaO~@>g4jes&Yc92B zR>|^~kz?HBqb&PcXk_|CBf#wBU#B#;tfVb3sU8LT#5u3X%8+=;7pTr%Xj34h+E@|$ zsx%B_b_5|8zLdlGJ{2JM_3(8tJ7x^07Y(XlqhnN{V1P2^y3it`WCWo*mb7Qt_hr>= z5ZOJ>%pxCrLgx}xq<*hR=5*-R{87+_EyCsURhy5(XqSj|o~Bw?d9vu9xvGym_Z_4M zu|!AmKR$n~6`)4#el&c}clPIq^lpFN%R0Kcsg_!>URHtOhWxoDt3)%0gyOBWIMa_W z-FCUEU%0iQMBTB(Gf;B!v>7Uu^K+Q8r6|52JeBKG_3IzW%o8UbF3B2^vQx zI@;16qkGmno~S1B4m%K4;Q%zhjg4v~KR306az*GY_JbGGx#Vrc!fvt=5V>d_2Rs(g zew-2GHBG{o@hz zv^?&Ejc7Vg%*cWJZ zo%O~Z0K3kQbPbdl8^0-Vrt$<0fst;!${5E`HB66BmrHp}KF~nNHf#pzfSx&_= z;q|y=B*iVB&R9&#U=~av-Z?Nk>XlFr|RwGon&yG#JL^vt0AU%0rGSKTbtO_-L5Of!X;8i zBjm^EtbR?h14arZKaG*BMw?L^AttvCor6I^268j`^HMWtC0rC;q(J-#DObW3TILjg zJn0C4%wYu}uPzW+dn$sS0!dw^sO)acdZ-EL6O3kjCcW8~cXroPXSQ4COLTvy{Uz(B zvr&tQ^>Caom(SWfIU)J-&z)(fcsK#G8Tqmmy=I^H(QicV&bc7vvD+v?o%=yuc) z%ZAXRaRhG-wl3ZPd#94JZJ258+o2Ov%v^u`Iw?wG^F}_xH@2aghDd*CZyusV@iWG! zIaD<$Ws2JIn6^&p_5kEW7tvCeamJ*dfR${_UJ{zhk?XS>?*qE^pi|dr3NpyqdZ+@Y zX??sRqu%?LZvDk0C03tj!sEZ3MeA9;d3jw~Ipz7@H=bIWcpJu*tRi~Q&AMwfjjQaB zXw|z7r7+TSQ3Mb7;mtl;>74NG$LXFYo4Q9CS9`+1(mo|)A9{MhiIId!BOODGGY!2<4l3=xCzb0j?w@v1PT0GQxmjZf>{D;U)>=c7-Y7-`kBXh+E z0F!C%k{U!2*Fh=OP>PSN4*i+EDTb|%4M$ynCDnm?>*qqX8f148B_4X+^3C$WSJI%xGx-ZNi;7bkSU{%V22tDCto2?8HI@8aFQbEmcxpA2!f&~NjLw>e#0PQ&PF z82d%6=NH{g&Y$Jw&suV|GU}a_(+W<8T(YtFjQi)oO^rwwmqMShQ+fPVWDK!F2(ts} zC<9Wm5H*%^7`hFr31He_we$qUEen#m$jVr1Q^*X)6!uz?1qYSet_CLMx~8?{;#~(4 zC~8s^_%$TvSRQoY$j}m|$LtI83T3KNfzXs|N=-m|rp-l46lJ2E%cHg2V**HV5Qy)A z1E7%E$;=M@A+H0!{$~)|vuGh);Vg}*i8p|DJhnzOem&WYs3lUqYV+h&pIBv3>Krdj z#_+kNy9O6YX4QS*)sr)xC6@x*z+#;p=8@_7!eQcYodU7`Wc#x~{9R}7I(fs-Pp)rc z)d*_a0&52AEqyBM><9DB((i_t zlvwcvCXTN*Kq(z~J-H5P2T0=to{=hncA|7DS*H`^i)h^?u7a~S?h><5}2OS2@#F@|@a4-b;ah#kEd~%kRlehA0kp|IE(RYt? z4({+b+XUp-xO?UL;U`A9RY9Ag1q}CU!^deBnhOoXmOceUzXD}Ls>Oj?t**(>mIIto zhF=IrJO1H;aNtw^txVP-ch9PWk{F#BS7d03!(4*stHwVMkUUxwZSj%hB*gRsP+Yz# zX#=!Rh|(qw3bBh^A$B8i95sH>7nn|!DgkQZ)3Ul|bjrtzx{H#%(XALW@WbsgXe0#P zDK};{_1mDe#z@$~7N)5*2&k?Sg?LlcrC(xUQt2!t0ohLAuPFe23j3QQQnaK&3X)xI z!K==-Z-eOIWjT!0yOzdQ#B^C@B0kN+uOG7+VvDT@NG8JA+|zxXO;L6jM_CD5PyvH; znG<*Nz$37*6F2TEG%XVZ6PM5$F4emN^#!BNC(kZ6aU-D3mZocFx~i?p=7yN!X? z&dF!fv2#iP{IKgn;c``1&?FJB9W+Z*!ox++hIUO7j)IiGqG`g=xRpDuOeL9AklbbW zvcD2*NtI=x*BT3bbo6~3Td8x`dCWwP*e;^S_V@-jt(bSUp|!vM<<6baquTlFU4 zlcFRZg>u2mqJmZ~TUV+Kuwm9NZPJD?ey>kp(Y4b;W&d>ywP#|rF+ zQmwM|PueslT6yY3sQ6U*=U6$KoTwRm9^=DsTIJ|*=>lDQF=oI!M|6aBZrI#2o}m}y z!%%j=Q~ho+#;d@pPS2BO1MDgY6jh{^ST&|IzSpT3{*#Cj_k;YdWZji6jJhm^9s4#C z?&#n_wT^&78jwfk1|{VQ`%=jm5Y0uJ&f+77DRI_D3~U4G0-QuNqbO&ylm`=W3rmZK z3_p4Ge^^LVyI04RZ-X);CBKqffwiz_u{X^t5NgY~u?hjdi;9%m4kzH#&qcu;S~Qd{ z!mf+Gl%Cr1R;^!aGRp|S!vDsi&xZ7MR(9mf@_-F`(6DBAO`>qztFKF{5C z$G=x0!}0Pzx3%i#$F03ko4?ce`EE04c~N`SN4XJ3pFA;#Qh^`x1M z;0SrNqPi?RT#PlH!H$g=442l$%NViYnB1CWIBKTK;n?~4Jo~<$d^3_qkpFHQ>0Mye zf3D86B=Dhswa8nuIK1c{wc=K@UtTtzOmn zrv_c1d+Tf;DscEW!@bhlyVye6z$F3Z%KVG-yi?uJF?6f+TkeQ(kVWf4Dya4olvf5d z32esGO27+KtsLaod=F<-i0%&2UGaz90A$dp)D=kQ-ZH$GD$2F<1$bpsB}rXhM;Kuu zlMnysX(2O!b7GxFuNpuX;|a-z0kUsd=EG&M?<}E>@<-E4kl_Sa}B#NdkxvC zEc@iD&$RDY3iX|_1c%{Ji}~yIuG!*7<}%$rIdX#Yy55?k!tB;hnRE(W|z627{a%sJ@w9wtQ@tp4viCg1kPB`|6$8 zH=1Yb7$8BApO)IdunnCOG|e?ROi~fC$CbQfwTU&&s7$`D)Lb}$97p*;smN|O`3?vT z_pGHC%Smn!LHL+r+EFAfhzFKn2H?S~UXSXi2W@0(d_2APuOOOq6I!k!sU;$Rf(YnN ztY#oF(q#m*HwJhiSfa9NC59dpy14WT)EAjB>jC>nYLx571iv=L_7IBOK8%rs{NHhw}{~HZRn6 zv|T60$p^YZ0Jb6ZX2wz7_?%L0U|j>;okM3i?tzKb-&U4@Rt|e(0zU26OQUdSsB_Yk z`s3*5C6%Dq3sL)%Og9bNYB+IWZzIm$)?W)|TbbRD4%LBxAP&6FvMQ>x} zn+W>z^s74+kzQ)wj;wQ{-vc$aa8yAft(son~JIfeQGY%D76EfmumxK zbn1?mZDqRT2IVszaw^N0NLys->tF@xnQYq|$%aa#Ekr8_(>cU?*n2aF}uhw@%ZyjxkH;RCBc ztZLVj_lK%wcTjYiL&AOf@3Ib;6I-2z9W6x^6X`B+`kLbjL2pH31+lIJt4-D=7IxA$ z$xWfsKMxIOfXFM-V1evZvXS?QjnSR4W{+6^!6j0*d?R~;FTWljhW)Q=^EbuI;JS+M z4c67ZP4u*#s5kVB$fz=`AM&m1Lj~BD#Ka^WuiNqR$r+xXS#&Qd=-!^ELMzXT8avPP zbslYr7WyuUKfH-NFv#`kJhHbq&eBES!KUHg9xcYURtcMY%k+0S`M?!Z44G%xn!-X& z1+!Bf-dwUsVLDQXqeV$P{Pj!NZ21p8Ai;OAg`MNz+C$9w-c==Bd1p`gbT z7ItF`Dn&(dC}h4N`dsXd+5G^!b7ru!KkE4F9>K&fexo}RekZxFYYI(*3s(H%k^!o(EF1uL7U%u`7i0l#ufngdRgyr zL*6quP2LO+053dcvTqRya+N}fKGBsYSB9<#meNZ1G>pg%=h_WG<=>ibK{APRs1yqa zE|NJA$Bukq(S6B|ldV8x>*3YvNg)@2xV|eSH(?8K5!B0R9=<-$Gc0{v=WO~%30u0E z(#n<@GZ#|fBH9VOqd-(^xPEWY&;DiQw0C8dcU6$@c3+0Q{mUwKs|UI{)7#!T1V&V; zok0@(L;Kscz|u_7PAo5UBUs2K=!UQ}rRE@( z^HqKWJm>~$w3poN6s@Y64T^YC-I{_8?;Bg{z^{_VNo*iWXWJW^a{E?xmk|{;Q@RZ* z1buo;&B4+#FzABh>SdEPi8}0u zw*-&+{tFSF*39S&qBql;yDk$5K1C;&@GRZcda$siYcTcVC%>H2 zbw&Qw_ZD5MREPZDGW@tQR=mfAr{u-HIuK5WA@COHAgZ&%VtYefgC88nS$wTmP@VIR`OLa5B?GYQ4R z$N}A5ZwwbPI%MtnqSCq=(m{}x7CD@#`v~e0m%s)JOE>0H!$l7YaQ zmfa6cbhSISd?WuzXTX=);Im*A^7iOaykP=*!gZ=AOM05N@qO0Paj4`E`H-c=Te=%! z+>MqiwL$4XUza~dsd1nMS@*pl{=G4tFXNe2@gF6an41ZU5{3lMeJ6bBfM04%i-mWK z!;O5ap?tdc-n=sd1u@OBPMYp#b!K~Rl|)2(-wbrPm=I#w{0{Cl+e8U0JvZ#DNUv}y zusot2UGuSY7raCQ`A_+Q;M9l6$MP(qiOKv+b4Pbw3H;KXM zg1jd{q%fT;bL!?JTWG4%J;0%REdV>@){3B-Q4SQG)W$RQ3(||AfumL#)WgNDBd{Z%Sf2#g95Hx7x)&(ugbvnVueJn| z_6an$4R+~1xU|2HIWc!>CH?cx0MGZ7@8rGjnT$U^G+pQA=~WWtQgGt%Lx=nds|%@? zAICqJS=mIW65ga#x$&&WxP`a0w{tY7TjOd3mHCBuKT=#s31Ib&!03PdvkV z0qgO@k>xyaTAXqpL{n|v26yl^bK@=-P&SGbkeFBt!r^e;~&BJvb9F% z`>$J79doZTI(*8?^FFmXzj9@|Wav@V3&VnWmy<8S`m9t3Vi99*hiWNB(VXr}4iB_HgGkE@4@)QDuOXqsxhTqTfLq_KZzw9TKJ zTOfQiK@i2V*C-%l?dzb6!d$biP}_&F3^Un6sFPMhM$L@#Qug1OLZ=6qn(8@}mekO+ zFOIa1oTPs*mVYLFVCpAg%qI`<7l#KWQ?zu$UvIqEBxys*6;3da&BjYSo zOS*^LZue+##{$Wk3B`z98i9b%=3ySWZ*&Wrum{@ zim(|rG9w|o1C1i>g9^h1{7tic>ZTSzCB_=BPAvGms5>1pV5?TI=2FD%g~d4UBqqVJ zDAkr+>#1R8ngFsD@RcB3XS)uNo(l_i>;(5J;PNrebaOkb!qdPCBRN!6i0cYPfQ@7W z;;7HCV4CUZsfT&a0{1ytwtWO#ZAMk8qPiULtlAp18PTuO} zQvZ3dHkvFX4^ThE>~JtoHUIAR^R@hw-IqNHcm1b59=y48*1OK|1I~ZGbKus7VTG#78oGN=ohr=ZwT^%SmyYl;F9?Q!84 zh=rLNRibid5WhRusgtcnvK1*1n`XWeG7>e^1f?kg6SU{(&X@INL9+p$PM$nEhti^i zqsAtL)6%W`AT}q|qIraM6jb8!wLh>Trcl{5efcJm^8n@tB3|$pN+p4*MYI;;IaCy6 zEmY?Aj$!n<7QZdmu#|*&jS~=!({}4|1@YEIz@sCq%s-KW^&zCV|@H%jI&Cml1r>8^jbOq&;O+lBG$~m{VyK`T2?^Qmy$_-3EKDg~+)14IPhD440oTk%) zHHn?H0&rP7NUoq(kEsSkW5T5zN?*R8v=uyi8{F4Xx`B`$gz6$7U?_&`!mWj~R{)iX zF>ZhoMMwiFdPs^A;xZ`6Q>}nq7p&r()OpZ4aEkhm6I+?&nS1ERlIT;XOKXXlj%EcH zEkOUgUSNY?$oom<^>1jyH6Jze|0v3i_sr(n>JAVux->@|uKH!>*@5C8L(o@vPks@_ zG&dDuGhs!N`vc&D?*FkSbhRF3VIGvUA}7h z!FcR~{Li4C%z8&ZJ1$dab|qUF%ha3yYLSkyCnW>4-{f0kTd`V>PT-Yo&@j-;Q6RK! zDCt;}1)IK%(jBlP31mo-T`DQ53_5KRG=Bv6aHk4N=&7VT{TJNJ$D_()|6eo0_yf;; z?p&zDY2`2+US~DbV`AVQ$Z);St$oL@&5!1r83f#&wlySG2dKDYb$aTG7q2ucC7-CsG{im>{`6mF<4z|SGY3Jw`{#R+g4(T2D*o1I4`K{)kU zLn|V+%dHl|rn0AQDG-hLlmxuyOcC-o`F5Am?Z8qee?5Qx5`ED_5&&iM+6ZabNH*%N z6bEfCBf7#$wRXFhb_c-pHqgW?Tq#PwTJMMyqLI#Jv!nZnG5tQA4+$}!Y5#>_R$}R% zQem~Xz#y#5rPS2-PBj2fBl{Xm_gb7-u@eUNb^)y=PD&OIU8%#d9m%g)>$x{S znpYpwe>LuiZR74-M`u5s54A0`oQ?HfyJ8xyh1;2H=jEL*rf+*^e;E_~bn?8|x5V(| zKoVihE1%)>c*WArbAL+IJMxw%)DHBx5f9&j>c(caVe0>YrUgk?$g4;?kk%9>wFnlb z>Lo61ijr>z(Ydx7``m^EP^QqHyo*@T?QpN<+&Cs%(3jS}>OO!^ZVFQ!JaMJ!T5yiP`45i5G_!??n^}0v49&L~B^_*UiodwRi$` zf)k++9uItgn|A3QDaRfF^wbY${oj#R0fn8w+ZaOv7rpAoSL07U+^G(oGu;eEEY?3@ z!dXj)$PRqa%x?X<|9*w1KIxG0PW_L^xxEGs#~&B&Xj1Prx+B^;ZDILh^!Ww#)8>z! zoxImX$KA}a9K5oB&c8mRw51W{=SOeF4mIc>Ytr~ocLdX`bcOS3#mtlvv1oO{zr;On zdwEvlT5Yd?{i81_Rboqd3iC==Qz&DT5DXau&BU9T%-FxsV|DVQc2aF4`OB3~%GXX* zqXr`Rva|Mai$1vNl8c3VE^%{T#qCFA-?^nW+KljW*8V^C{eFY!@0TrN zf4fq5m&Afw7 ztJH$6%`%v>?wwe)b{}=LrBK9b$W3oUCxV0L+X%NW63&`G{OI^6{~aXXDt82R#4HD#`kCQ8+ zKwU%p1}$TGpzRltrnp`Q93uZ9tEv2UMWFytPgEf8BtvPJC~y0+p6JryS6&7GPy%RN zpnhp(W<<^_5Ozl#e8kyb;QJys6^M^6y$9(#8xBlUB&+eIHeV;RzMQh8#Mqys2%@D* z@T7G~P#R@rR+;@SK=eRX^Vbg)&g;KT;6Dwji}-TS;?qSX;%hXy(mUA_cJBFzeQ_1= z?)5ZfDPq3w-XYX6FZ`BnkRa6KQghfFFs7tPu!p;o@FP?&pc=8$cCqvTS`S8T_y@2j z4JL|cPW=h7nM>_fQlI8W4Wm0TKg``cdZ_z)<_6k@%5hd3z2F=`yH}g{Cy!qpw{v8th%>NhYJvIjx&})h0)~MfprhP5rZ+vOrBQws8bhwe? z_Vxj@9AD>}eLM1@MR7#8`<^3Oj{|ja_4X!6#_hO&cuV;lxyxbHBTdgTW z1>!9N-euGm`_9jQyIRs%9ACJfsws#71bbe>KXcHShh53_&ZKy~4A|YV?<=KBp|no~ z_QpQE0B!xIs$ps6M zu&@P{#6@RJ?j5i_XtV+igF7QX+49##7kRw60aW$ej;wuiQth$XnQhD_E7-$gUcNZ^ zE3P8;bfO^ssCHdYLD1eZKQD%7>;3cI2~ndS4z{sA@d@*t)%1i9MILZoJT|Agz5F-T z?aZ6-y0h8ZBxMmb4X%4)6Q@iL%C(THQXIIyg+UZ?Ot*m7`=G)?g4vqxXVyUlKi@g;X8m|3ncz%LWb&xvnT;?spmyx}+avqrQYzgx46~a& zgi|2)(K_~w%A+E?;AqC)YK{F57b@K(l(sB7nZSv=VZOdiNa}m_%=*(Jd53(+g9_Ed z;Z%VbR)x}+Va_A3&JA=Dmxs|H&u_u13=URuX^psIg4^8wP9Aa3s^gG9>f1~JUpkb$ z>`XGGZKA}$jo{l$Q~I+o_hTeP`AoC6^!K?V?tfcfEC27mC~(WaMuk8~&cw{ZEQNN50CyskoAx1Haj1wY~o zt%Lcr7mrC!hp-=JUCEZ8_zT~rS|YsvgfHb~?{6O?+kb`{P|`QaZqB4X8~)zEHU$FF z1D~h7gui2YYT!}ScqWe`i2D{C&f+)rktqE`NOw{n?tIYVUF?@FBjNUOh2b>WlfuO1 z9-3P}-iYJ|F7@=Kgc>(ODI$CZf6X#;-E6x96kJYx(BlSafoj~Z^+G@oodjZ9tcjE@g9VKn@X`zVVmk98nqG{>2B8QS(u*yJW1YZytW zV{f}mX^Cztxf}4n4jb8)rB>r8IUy{3`Y6pn`1XEO#f=k6o{M!h!zCpTk{-Ocmovi^ z7F-;nTj?|`M;|G0^Qm75PMCLSq}$B+Gu7<97`nyzgSl_K;|ZQHn*7fIZFIEdqu#~1E=?h zU~xPwx4RB`g{qukDanZn#Qc@ev-|VsUZ&9feXWjnN4);iFZGMaab1|JiH?fP@qBap zupu)q_s?$%eykM1E!2ZThsG+J|NF{XSo9pwaloxI|ALkMhtT(fIr+oryOIEpI={cf zp2vMIP(N0LOHPqTi~1HaD~UbALiiFwIbWO)uK+_Hr!_}ru=GHqDf+_f7 z07TqLlXhS!?KAb-C1-ku^pMcQtj8e>n(w6P^mS3z&lmP?Zs<=4(G?^Zou&8CG+Dt@ z@Fl$m=jTzVUqD*sS&|=2MqhXWP&x=%rkiAUNGAj#76Sft`EJtY^k7i$3Pyj9y z8O#%%j6=ul{&X9M#nL(`$d(sF|!apx{;m1D( z%V=_S@}%kJ23gqx`!v>c7S&8yxC|ssS!A-z1++0c!AIh>5Z$%(x^>EsNO6VcL8J)V zfy(@fsR!n{L1}CT=?Ih#8u9jjg!ml1I!OtW`v)X)1K!`D6VDRnw!F3Xx-J#HN|Jt( z#ggCdbv>Ih`$qoo9_f&tXG(>`&7!)3cLt$WcO$&7n`s%hX2gH#CY`JssHxi#YN7nQ z|FbB+;yIkMr}o@aVU+8f#S`3K?z0xFfA`Mv3XFRW_PpY}OqdU2^w@U%73hf38K_Io zKa{5Pmv6j&UxXnV6|9v}Y7)_sToOpxL2K@l>L`nlTx=FB*NIHQtR=s}Xh40{M7v|M zYlFhpjJt3n`}84HC#vPwbdWB33VDFpLJ9}6L8j2OTPV5XevSRCqjcz_WU4in{R>-( z{M>G2JW`z21k&)}D!Af~BUwQ-SanM=Cb0I>jG3_Uv;6tMNm{O{*09`2`pYZ!X;|Mg z-Pxv*zK{Zr`a-b`A~^&r*pMm0rF>;}-65z%V@&%UL(1PqZS02iWhzGn>~vVFt@i}v z-4>$e+TNabh2ehY>=){%qR9uLu4fXY4#??{P16OJT140g?*|sU>le2VlzG-W1WsB_ zwQsFRt?G62N<%5(uGK}nCfP*o*ybwh8K%B;KcfeV%`W>DYdRqARoY~SB!nQlmo^oQVf?{-6FsWx5Q0+$FHB6Nl+ zLe{VaS^`f|APdxDy5vXsFhzqVNbiUZfDe3xd zUpB!MM4AUMD1O9(Iz>zqSKziZpc>y3Q3(x%_$;@|Ri?pKaSohL4}*DAbRO+`kpj_! z*RWV1NHpa`WCJ#sbfsMr!Uh7^9Bh<5*)EWD1V~Ch4LMIC(|>JMAdq2?prndPV(2LE zK|30(zIoFlwuUGQe)FmK>$@{g4xpx)AF;G2gkUrRKH;IX!Yz+yMyga!Z3TuFGpbb2 zl~>t&b81Ay3Iq9b5UH8zb-ZtHjuiv1iPs0DcBxgt2BEjM*Z`%)g{@Ub^0A2ywsro* z-^Xpi4NU?fcYaTqF~%_TS(@ve{#;`WN+SiAQFkirTG~F1V9no2DiVKn@(`*K+5SYt zlm$|nXrH^uHv^`X7k_?Cf#n6SFY`k|{ySKBjTE2nfyg>vu_yZ{DMI|$A3e_DdC%Dk z4m8oNcMCAZQt|3PAmld~Sq|S15Z{HLZ(3dUX+g;r8Wcrz+drmhkcl!aUG zB#fo1(Yx4J7QqilWs?Y!D|(@Wtt*8ghKBa7dco5$P=DZ#z*V}H+f6@QbjX*uPrk`4 zW-iH4#+B7!{~D!4qa{C3^x4ay#H{w9mSb|7*Bkk@QC%zJ;qC52)ia}=!Y8-3+=P{& z$v%2Vb(T+_HhHF|b*1|% z0d7JNd%o{=_-^UsgmQ-OTrytAvw#wbjfC@%8Yvn~7dt>YfRbpG%AP8?1as_bU!&np zNF-KW{)(atA7$JI7)qa}{?@)4q+U;8YQWHbr5qw~_dC!R3K-HL$Qh{f9(IfdS9@5y z53_I;GY~OXzDHO_${3F%@#i@|k6DvZX6JUzlozAa%aKA#jy%AV! zX9%K5hlGoIynwID*Aw1Sz8bZJ!l!DP2BKt_CLeefCu8Z;ABQ=W$+abZ0h&4)9V74R zgM98(q&`1zSuX%lDV*i11S9j_>pR307!os_uswG@&5Tm%u4|;@2Ws65f+)UKRxP`U zQpecg;|%x;*J&SWZ^KwhVN-6H$YgnEvS@1)_LqY*gGJ zYf7N$$p5@F+C>{DbmR4GsJWB}u8Z@ME&qeKH;rm)+qOn=Tc9FFrIIo#Qj1uC6k@Uk z0RbTbQVZG0Mg&AeL?VP_TL4mT1w^SLQU-)5r6MFkD7GR*Y6(h6q9T>72!tgmeA9i; zdGFkNytjR?weP*}MY2i1s*&}<(eCT)_v z+)9zeQM)-qy_Hb1B~eD%K)#HwYH$0rxuymVFJZkl@@S6W6Tl3-Cmt2=fb}P^YWN-S zlEK_4kJf>NFb3%WAw`)A*JiWPZ8K*@IVcmMaX(ef91R+%KB?5aqmWcU=2 zcPYQ#51(glqn|2Cnk>Xf#dmz{>xPVq=KY@FJlsmWrwvPs?zwbeq)_hG9>G`N<6jjh zGqrWA9#L`UA2R)>E!R9TnML{8D<{9`{zm0dgt7>J8pLWNr6~|=wdPoexkPA;P5?W> z_1Iu9%v?MRfj--F1+!Wh49III0nWS$wNJPfl<}>gu2!OCSRs0&Mn66P6pbt=S}eJU zwoYCJLIyYTdKkZh8Ro<5;=dO)iKRd>UzxgfidN^A9mQtFqakM?zajLDYm4ephl7!; zP^;ewcfhI~;wXka*@f9mX{RLS7|h=0`SYXTXz@;%!s$lG<%D%0WW|4pwfm?qDM91g zsWk)5o*W0sPNw7{@0YJdtVNZ;h3^t3RWp$vHs?#eSwdH%OD;#ybE+PEs2I*a{_LsQ zpD7FDiamu6F}kPDmA`5IaKF^v*16D5=EdX?wSJR*Npf1yP<*~gUzu&+%@U=P>2>bS z6*dXA=2^pdaeq<%=__ai$@NC%Y|*_5vdC?_hmGVO$%ViP8uJE!9uQsxtMLb0L{AJE z8KKL0aIuqf4*BJ|h(4~$!^qftv&$8GrU<7whb zRX44=r7cOj;>ebVN!k*W8?<02QX29X+H98i4Q(Zx&{MQBGHwJV%pE((>zZ(HY@;w` zze{|4FF5pF;1(R;DHBNp8o zoZ^p86iI$FYR8|1d!U#Jo4AoKqzY;e-Uv3HC@N>3<8~tD@R4j{LVf5tz@ZNB#cM^wqwkapyZp z4t43h=UnnW6gqArYbko|OU}%>{wc#L=|W%9r3*}}LyIStJUTHS&@x`(6p85X5(eKT zTra6f^RRLFtL&=Poz!(a;{;*g#JpUPo7Zw2peZ{9I`S0a@wSE2cX{uFa(Zu2f)tE% zd@04#@->X>pg0|!on~mT`F#)BMzu4pq%}%zX(=r^@zV7XOFW>PEj(bT5Zd|$;els&K*x=HoR7X#j zJWcjXL#`%ifiAEjwjLuG!Y-V~**xk-Q3-0R@{vF~>G4PkVF&Io-HbuUO27vE>rmsI zDR0IR4&#Q&2^AoPbn$k=8yb?T2Os{m@8Qs{!7q#HNywTs5~RQPvVKfE04Ls8&NNab zAs-6UhC7l--G$c|Jr$}`#4Iz`4Y58Gj}|qUqdAnfQFM|tN-Ef_u?=~XCNobR?fTxJhSF^dX(jH(+i-jisUkYPNH_QD3th`# ztV@i~g=Kn#RrQ!hcgbJb4pY8z@F?WpSp|vk%DgCcLb5l97H5P}#qYsxf(30k3wV3T z`qt%ZRk&_8++QD3%Qe_ICE2dDe#qR4-C91Sbalk=TGUkqem*IGV{kFFw4X#FA%A-M%r5`bv?e50hvZh8V|_G$}gEVe!?`WPknt`8*DvyvjUYaS5fN8y4_OSU8YQ%E%^IWP8H8|^xNkf zMmb|;8lkCIRgTS>Q~mq_GWx?!ZG%u#yS`M7IpvefY18{hz9J{TR++e8`!+fCLPX3z zc`KI1NPkT{>J^@XD3t_<0J{P2Z^V4s%kL7|E=_l$qszWFVWC*WZCV&Om~DT?^`GG) zuA|Gk!s4?Q!IS!?j@^Ksy^oXnF5%>(OAQw_ccKGm$}zx2F~Rp4T2-uswgtk9AKT1Yo{HA`-%z67uBHvZljg8OEDqaQp!CKZ%dW!A zvY5WAJnQtbkQMntzFv2%HDiuxT@@Nt_Fj~6vaX)mAh2pKu=-fv^4eQ7-WVIdM1wVn zv(KwS%&4`1u{1ZHA*v#?rir6onzx~^bn5{WD@uQaPq^(5{#BNCW?)YdBy#XFB|5r zFnURFB z&}t8`Ruq0CLK&b^@am_ZK{>)J6Ur!0xY80)TRYec1e`Q)LxtnWUhoQgk8o|{3Fr=9 z2hNWPj5W@h$i)etnMVdrR2jyW>U}nUZ=v5nj^M|Pp@)*bQf?9U4&#kE^ViG{-Q!OM z@K$rGpRkcz_q^HDZ(rmISkf=Ke{JixI9mTyZ3pBSr|wvIzsmnvgL-K9zWWwHiqEq- zNBQLTE$XXj`2Dk|$d=6C_T5e&eyn4LJApo!+sPg>dEQF+5~zHoHGK8EM6Z};RbKHS;cFL=a$!G263+(E7WcjY z@m~`OD%qrbG&I8)jS^pLS{ASRfmuuvZG>hEe4p*UMhA{01K8 zAC#|%+1HKYxVK0ERe;KLEju05u3L`~B!tGi3)i^VjRuKzb7Ax*YStq!bM@9Mw@-H$ z2VaS^f>grY*8EBi-=$-R@_^+0Ej^P@{z?-rdLcGuZzjOwYLD(@>q1X^U7 z84iS6WSIOgEw+uDc95oMEaYwK2X8QeeM*IlH)Ml-#cVZMmP#d7M^hcjDVXAZU9oTEAt@+izdEe_z<*nudi`i9hqWqy9 z`t4LCPqR$5c;ZWa6Yj#PgBG%63zeE?|B%B>U4Em3v1$0Tv(Arkjqa;%#u>%6n`M;T zqzgP+ok`~8@%)xz|0t=c*SC4g|EuGH`p0O9GO2FtvpHiIztwzgU=$)(hHj7*5jLUyDgAZ4?XC>}YPc9Tru!Q4*;UrXR{xG~ z66^MWb=)TN)B6^KPTt7Kh*P>)qM&)_Quxg?c{wRAp+3b~vw!}WwH7~SEp@A?oc7@< z9>nl8Y?*D{(k7&N5L7mv8_NF?t&CtcnQECh3#{I7*DE`yJ?o5XjElv@g!#j z)INKowvJjwRh(vyy^PXmsT$;s?T!zOAHOQM(NcY{>)dP!0aS2*oX|?Pf7t%g(Qd!% z*Upcc53_~3ztxA<-ECp~i4N%iAccKV3Sm%)_lLKBm(T>URO6fsFQ#=={Pw#k5^C@^$wu2kDjq9E6I1(^`Kg@}>{z4r~ z;4)skxI{3-YpF&Htsop9M4hf@l`lc+dVGwOirrvCAgIHKXTD1uCAB>zzd9A@SY_Jk zT9Vw!IWs9|c0n=TNhL$Z?((;XB^oz@1?2#dK*GtHU9J-Qbil1yyp(Ma9jQoLCum7|TT`(-1Vj=VP?=0(mH*9kXd1`1$ly z-{%~T-NrOXG!x$>0+2@<4(purd*~sga7pn*$Qi4Imxt-q!c#n(xyCX)4h{uDr~uy2 zB_>?Kt|jaco`FzVkHpL?YMStJM7ejW%*0;u16T`aZ6T<wE0|T-i%!qCe(!ET!2WtSQk9l?tJ;MHGaf-GJK)EK&m6RDR*#2bPD-*r9w$v{cmhung93FW45 zC-h}|h0R5UL)~5Ddxp*Z$ha8mMmRRGESM;ZQiN?z0=v9F@P?({G|6*ns)O|=^-@Zd zRxERjZJbIq#F5yPL|PbY8yzYVZ;TWCutSqi;80SD_46G>>2aXbHyc0)R??Vi%PxJw zATC2@iljo7w~63{CEhh_OciT*!Tb?6k-zsxZnK=ZCget)luciV* zh{nNI%hfbt=L#|IoQ>cZfl;Ig&p;O=3J6*_EdWd1V?C~ZgwoC56kr})Xu0gM;_>$6 zO+UNqahtgD5lS9Ljyb7DaV6K-E6-GQb=7(cJo7$X_FLap$3E#0CR7oS(9xa8UJhZ@E(A>#fG&5s`nQX zIfV5~Bty(8qJmY5 z@DhZ*#^R)36O$HIA3eU4rhtflP-IaJHr|q+zxN2j*-GO5#Fp9wKP*jc&uZL9y5y9A1i&%J%Bpscc zgScgWRd855!jcys!V0Auz~+2z8X&~y#XG0P+lS3panVfsjwZSElzD(Dt_4cKP9?Qk zZYcWHp%qMf$UXCb&}th6s&E$^De#9a+ufTI=p-reFm@dkfjoSGF2;3$;f=aL`(_v-NkY~YG}DD2v1T<-Fmdn2JkRCDgFxO$ z%T-ZGfuT;9l=*=ww_s0Sb#2!W_q=I)L=u~z!p^C$w96x#-D`h})qAaThTLSN<4#U3 zld_cAaB`8|zTM!F-~Mft*~W2Q&aaQ$q1e3bt=}}0d@x6LNT>JWN)vz>7f$PY8TtFT zmf5Uwvdb;;HKBY=rxUl*LNRfy$Ba2AFq^JC5nTSq@(R4Uv#K~se-*^IXNv9CR}b76omFH@hMP|5BNODRx+mgl5+0{%&!ak4NlyjW<+ zJCs=5#hFugT1MYuQs({;uZ2@5NH=rPLfL8t-vzLpej5!U)-u{jNDsgjZnotOu(Pi% zGDe+ML)u4>vgQg8fD&d>C_4h;X|ub)jv0cIgQLPZ^Qp9T=B8|-95x80&Fe~DV*HU4 z(D;YBzi2(&2%_C=Bv0xXb~6r`&7{u`aMKZ*RS!a5K7hLbc|;2DP_*|M+aZ|VPE{Dr zwjZuPJSI2PY|J^LcVc8w_1LclhOuD|kB2UQtD1i_H<{j;%+C?!9#s?-q9jxNDIMvn zHj|c-e7S+diyd_2##EQPMs4PcN;jw4wz7jNDyG^@lH_1QUCokXmYL$E*OjmG&3a3$ zblWBs3CeHHOj4w>6gksv+fz>Iy(x2}DyUlIu{VrF1_s~zixWOR-ePsnE|)%-s-jos znEiDg(0+-HxgPif@V9^o#+Wm5j1FQ2WO>B$g|9r%w*@(8$kcC~OPCP3ed%_A%GxWD zTi^FUdacNy*~E5Mq6{d?G)mIL z;@k@M49_+nt`=Isg`6q`=8af8c;y3fl{vNy4i4Qmg?`{c3u29y`-7nMqVJ_SFoIj( zRVI9`HdKh5J1RJs5(wPzC?l_ZR4O_#a7s8f??=0E2PPP*ni%6)AgrS0iq8jSjqXK*3 z3DJ`!MglMcoybMjB9bFptTEewfp{L^OH#&wPf!nU8*$q-QdW3Sa99{HES3sE%T$@G z%HI#+1x^fNx1vA|oM)X)p29*IbS^?Vs6g&Hl6+A-NUYs418C&y6_?=WkTCMQ#IuC4 z94e{ac(x58%nN(*n*L`gF=4H1IOyioC zf=zq4+HRZ;XUJ!C>_`TDYa2DpqX~^v%G9aXUtbOKGW}D!p~WYs$`VQ(<8|YdaC`PV zy|JrTTynF_uEfN0t*)tVw^l+~ZJ< zt$G@H2Edy0Cz}QGw@X5dqvKekd-V6tR}&avTDJp3!z1?o<#&7J3-UVYt2K2Sar6MB zAb!~7dM4*mRt{nIO4JOhV`An_yFV|3K3w7}C7IpPn|j>!dUnI>+~iDUJ6k*b&Sl%O zTAR|5pPFI)H(H0G0?^t8NDYuX3H`Jm02B!g04T%10jNfxC7Q4=4Ly_}Qls0N5;nquQ|>FQ-}_7xzEsO{Ui)H=c{i4ILA26*)85QSBs^ zp2|;`gIs$1%oQJnOlf0Z;kaA|PX@=Rzme~`ZI z6S-^jRi4HiL~csc-HVX3I+gUvA;xxKGEReMR&zbsxz=Y%)=euBZ~udm7Uj!JNHGVd zHZE%H7)P8Rj_oNcH`q&rIw5&~PGoIwx+ZB{eRq zdD-2iV~z81N^IJ_PM1u-^{*oGz@KG0cFsZ8`;#1AIfw4P6WVac{m|#qqT=#9)-$^= z={8?dm$b22b-OP!Ds!;#9W2ig?pFU(D3c>K9)_a723wf>Npww+yz4CtOE+wH{$*zLdh zQJ(LdqU(~E5#^M(yWctayf$Sg=wfkHxLWjJ7H?aD2dzJ#8(hNu3Dy<{8>ujjUQf`# z9pt#C$Czm&&P{|dxA!N%M>F>_Kka;HXfpksKZmO_wq zc;@dJ4r}GUf`Tz}ECzTVBjxkaofPH*9}6E{N2!LNx2>FD$r8|bZI~!e=7dRLnNx(r z(3gA={XC0HzC54EcjPl1c~@?q4;VBzCPsw>J{lW6ecDP{q)-^rq?KgofNZBK4I5In z;v(9;+(^|hv0X{NFsSl#&X>eWre%4MS7&;~)WT_x;ApopzwotRNadcGBPDai(7Q2* zJqL$ml*QcN~%ty|=O}d*)_WnQAJi zS1NRJdNimJWMo}?s-mvSvFK!eNnxdxTw(<-o1UXt$bPTo#aowH985JB{BjwyVJfGz z(ywe$tUUNP1xvD+yln&jl2)@(aa7ZDdo&NlD zMkwFOp+T@aBXsso=;zSBABrrjq0n7ahxVua!Dp_W>_Rf>pagX=h*Ra#!9>P=q3QvT zZXf8&SbGlZ4*a>z206#XMVl9~C-VPvf?5mpBjQ4Tw(CUD?+R+j?X3(5akxP<Ztmb;EmqgSryydikeWh|7CY5J6X&&sv4^|7_>SiE!d zqhsiioYdovc{y;Pq7~CAXs_7T_(NWiEGr|kNN(IY>3z}TYDo?zX^{rvkK@o%s=DAp z|3VjQBVI?kVC>4*NQ@fZ35vQ_cLb|&oQHsImS|gpR`?%(VWVrKMw_ETR#Re6BieHj zlEJ>J169Jv7{0VT8j07TJt55<@cLG;zaRLeA3g;~1$^qfbC4K>|FstC%;%qZc$iTi zd&fOZXWYt>f2HQi73#>s*M05J9v#}*pJj6Dlx|Z*MSsZ#f$1f?qC4TIxO%1yIUgOT zsy44AX_sD*1p>K$eaYRg`po=649C(}dK&*GhSU1$y)kD0Aci-%53|nI-~F2y{xP|? zAqNn{sfzx$T|4t-S1lL__m9kSfqy-KclOS!0xQc&Kp*Df)*A0`l{WgP4DtUa$AqIQ{%uHFj8RhU82wIyF@qO9Sa9W zVj%ldJT=P1`{4PGgVPF1d1wXVIn}+xz`-@1jW;b6M#C8oVbuCQ?yY>(NShZSF|_!V zZ1KwJLlL_(b|>qt%$*4BRt|kt6+7pjy?Rz$a)WOdUb1u=U7KoecDroW@2?7@-#--v z=;=lHGXEFHP|n8b|E~vwwfvlOD3|?S`8Xs_4dowEw;0%C7^*waTfm)dx^O>4E-ST> zxwoWXnz(Ct{lkUovpH9<%;$LSJ{wVHB_a27EdaHJ@+a*qFVj?&JOtRIV+i8)SC!dnjtLu1$U{q;5Y2M=}wN(XOZuWXIEt9)yo zu)}lOVfSbXb82}%f@Qx|EfssW2$-x7@!S{_#P(PjwgUaVduk#l}!edO~D)5VYRwZA;!bdO&Dnc&+}qQ#tOE@^Qbj1=4O^!0YpTNvv1UZWdkp z{pW%aM@H;zPM~Rn&)qI*3{p4mZPH*xUzuZ?W@X5Rq&CMY_dQ3HD)cr@J6Et#?w(qX z8y#M;$gWV7POWiB)a zqmberR_)D|uxrikVG}*hGo9%A<@R}LmQRQ?Y}}@1e09$rL(JRU&XcHYwQR0~?&#iX zBfXGkM(d5%_mWhb4~@9Tb_q2}!1PVo{fFsWV#^QHw~_^~fgI;DH?yWlouL~;CW9p= zgJmWyT$58N0g8HdGD&yp?gYO1{eHb}R9s(0-shp4+>MXp z9BuomHngHV9S@{cseNP@zv1wz$tpqIw?c0uJw3tpQ5V^ueGtBovn!Zz*hkvju&Ep= zInt$9p1zfmmfiXQZ|k!KCxN$HP4{Pq67~x(@vxm3X#%Us^=8iUT*5{9-&y zm;Q^=Pk|lKz_9ZW<%eOXOw13%PWw;I&I5qv(fJ&a>XkjG1xh1p=D_hVWR%e7)tlKQ zPvLzX;3x4y8#}Aqk2&n^I_7|MhRYB_nNahH*b>d;lBpbvsb#O(2Jmk9&@Wqqg2H64 zjwH9ADIbmud2=(^ne2>x5xh2WWkq%o|{#8^!t{;_xok_Jc z*V06+PHeN5f?1RRNj~QaffN>|!4>6S~(Y%xzexNA~bKCrzGiJai>GV&;?o!(5T$ z*Z%$!^K(W_3^9A zY^38UDX$N1jyBwh9d&t*YgK|viA7Z~RL=7VuA5;$xtFvwbEZ}a)@BcD?QcI5p(_hT z&Nv>JBFh)w8P>?~UlgkLk_-cEYVq9as=r?H~|(3+ejazhMmG!W}(@gI4l z7h%%x;i40u-%IUDXr7KtXkw+;W94uI?ByFvi0f+GAQCux8ONavRL_K7VL5zLKLuk! zztw~NLgU@OJHQa6;%=}hw+ztdh?@z0#8ILwF$9rFlQU$Ea@m+U0W{LalH$Nt(yUv; zqudq*=Ll=IK8Evh4v<7InV^Gdsek~L-BEB5>Pix;3%v$}iWH`}2NVE<1Yi#I)f4{0 z!nrI(+6vZ?`0v+@PL`903bCV3Rc5ACW8+GUf@Bh%8<5gXo*4H|FEO?D$a^SvSF^Uw zuA;h^fRzWUjcqrS3Po7Ch}rYbH!0Zq!ZwEM|6TQ@rKablIpl3Ju12w$8i2x^j`)a@y4vCRY7s|`` zrGb)?JS}Ariv;7b${YiQ(TQ6q24XEx@UMp!yx{wxMa0l^R1>%inI_hJ2dmqR7-6>q zZV@_dkI?oA1rY?OxdYa`z*$o^BA%cls-xtl@?-ptg)WzyypfkH!4e4}7603G@nQj^uIX`OP!83H4IYiwd zdI$Ug2LATk3jX1_WlRO0TU7AH|NUa{zPzXAnl{(V7|sQ@aozjso)}HrRr{HIbn0PS z14&FKG*sDTOy1+=5&Sf`9(s#EcJWO`#j9ctB`NJ<-Z`hMonVR%msw<##bcQ!kM`=b zCoPO*$O&`|!p!7KMSn+^R1ziO?%tDW$hU+@0;50=CY1ri%yKb(9X#nPsyPq%@wpw? zM#p+yGM%+8jB02p&=5Nj z3u8VH>wJmV4H+j+RE{gcBh^Af*u6ryrcbOrE<6g|eIl@&@!I~*2E-?keS)HksYb&>(<0oZX^)LywYc^fCZGF4SyHw?oFcO4TMaGU7w>sD zgM{o5@a~4n2;LXIsy(-)vxMjSX@!`oluElb(s>AcP5A(Tq+kENTdO_ft@-Ih&bpO7|5jrssYs}9sL~ys){blYG4jFSBXiyGO zw)J7lY>pvHJ^KY3a&Y*?;gY_lgS}Jifg=vpcUtG?y#|ksxZIbM(mkbqYpAcyk8EPV z>d&&14eGyqrXptViCrf@7AYv2ow};sbjj&ctXy!{jK@1G-OH0IZpQm6$b%)@wGz5c z0X=Yx^2p7P)<)A#Wk)+t6~!0E)0=7m?T4q;nJUvx`lZ>YP`HyhwpW#XRbGP=l~o1fkO9@`2ufh8(YIVuL6 z?jAkg`aYVAkv%ZebMYQDKU^7tt-;P>DyOMi2ERnoHcSJrqYR$^$w702N8{(1WeIzi zh?~dXgL^R#c-9wrn1Tq29*&D3mc9&)LZwzt=bWyoPZhn}2KM!z#Hfq8sdh5uMQ-_K z_gyM&%ho0rX89Fa+(mBHwzUh-EwPQU3eJ2y6rptLLnXH`xy{cw(zd*HuiD6VXrx$z(1Wh)ybta7`Q0KCEd;pgw;dP*9f2Mbwt`MH%rJU4Fy%$pVP4=mNa^OQ)@5*s zlDOJ7&=-S5H&9eH?#ihzh@;@DiK-!Pv5j=hO_HKmQrt(70%{fDna3Tfr-A0lAoomP z6Wn+J|9gWd-3SY7u|Vb3Us|S3FP7X|)LJU;ti^jg7d?11{{`f}18mWgGrR>4Mv14l zm~rLRZz4d`{P&pi(?ArW=DBChKG{!fhY7dM%~h{Inq8$Dn9yD65ypE|&CQ>Di^r(w z>ogr?zh)io){6d?$6KtvlzPHZT}JofC352HkT-o=)}{q&+s|X_E}l%&lT)zSaNmzt z|6rQE@VZv_bx^0_mpj%~JXdY~CCjp^%BmTT79BcwkqMz6M^VQ`f*TpxZ2C58W?hE$|PUBC!(R|u}-Y9)5F22jYz(-HKVdUIbVDSO&N$6Sa<$1g( zH1rX!sNE}Xzs8q(GA3foTW&7Lsce&xZse0JZJYI3ihU)?uT4n%JxpHpUvFcVv`4&P zliRY4Y;@z%l5#!wn_%* zG-c}aohn%ly~^k?So0qLE7W_x(39mowcr6rEJwJ31)oec((JMEBzfUhp4v)>+n#+- z2WOjg!b_RQiBZx+?+*0bbLt?fqLsw@#8&4YGQG7aq9P>Uzkjaz2u~S1NZ3S6Cv3v$ zb*gE=3<%jiUrJ!GB=7V~`(m~N!}!3MsxH)Zv1$WPGL1oJt@RNe%7baf~y&Q(9d7VEU!?mWbp_4wd2tC+tD|dU&2gN&->! z8bEjPXmAR-9%--!CcaQpzfSy7u5{wPPowyATWmP;_hp^C$$%0=MCC@6Vj%Iy_uIyt zjEt?B=4%go9;>@0WtaJ=tE>s@NF-~^Kbh0{F4n&p`|I=%M6h}SO1iooL#;5s74 zCrwGbmiTfjYznx^6!yIMp_vuol{**vg7R$_S`s~*B|P$7V$kMz^?7S(kuP$_^CGroUy0Y~}!SEa2dv68b_NF^yv^%4RTKzDsz?a6$NkwV{s$Z^*X(ZeY33hrFwoUT_NX7K{s$Z!th9M}7l4DW`0kDhF*Atub%ny(%ox}4 z>YzKpw0Bob49}h0nEb#yX!z5?BK)r~i-+hcP`z^dSE+D=1fgxIZPY5|stW}nXZO6h zi>kCkZ@S!&?8pqQZn~QH*66&ZT#Q0OgVJ@r^vfps66Cu^gR4!%wIAnEK9NB3e82xc z!NC6qu{dlh@fX^MTS67^EZrfH1Usqjq6O&jC=>3&+sGRvzMU8dH>cH$-4ChbqA?3V z3ZO!4{=iz|f@wK$--&NC8zwH|-}*5Xz#MEu&jyZBu2>(rH+U?+29DRvKnJJO!7&M;tlJSv8u6*reVRGmk<4)w7V)=gCJ(s+| z!Ke{X9OaE)_p{?V%L3T;v36hf3!Yx6{*!XN7L7F7DKT!{GXnJ;2J+u5~f zDOjbxG$-FfpzT#Wn0qI4sATt8P(yCm$%je0X@5QhQpSJ2ev11VEzSMhA@2c#at`b; z|81cgl+%A^bNIL1|6is5f4>)oz;b{eU^6i(xpd0|zdS2ov|A z?xl+xO@w{(L|-U&_! z;jq@?efo!q=_EyJSGiUzA|<*YjtqRR03oi^8HW_8w|il(g)ORL#oGorKEEI~1I>T1 zJCV7Z)0yudFzNf=YIVej0L@?ijMq{wEzEYPv_L5I7#I7OstWo?gA|W=_3O{xUu4Wu zz;5*%_%Ga{je;5MJkPYIE>f=3e!o{A!$`s^o7+UN4Uo7fYbqr9VonCr41DNls(6%m zU~my6Ryf+Q{^jRH6*z`I5>4UZm(BVUm;JxS#4IlRC1^Ms`YRdFX}k z5L61fe{P;Ovre!4E)mM~#R)i#NuQeEUl?~Ja~Vmf{k-01#b<}cL6W&%+z1H#N15%X zwfGmh+tcO(t>(!#Z1?)vhOrBG`^V$AyBfvQb#Iq#Op23pmdyl&#L=z-!$I$)GDV-G zR!_f{oPG0yasHof?Ejse(jTZ6u%=djF!-6+TmTXV6Q!Po1pf3crAKV1BgE4)Mx&o&s-@jk1kEbk_I0WUOF05D--zPC?>+Sp>jO4J|0ADGCeno8^G=Bqq4x7>x7Kb+(ZaP#}HtmL8 zVAJ=7`k2rw22$oDE2Beap1ui(jfy0O74wTvbA?MW43 z#2Ihh1WR*C>+oCQDX_q+lR=l=L~=7opVt_Unp*)fjc_}t1f;4-*~{==*oI$RnNKs< zuWHDxD$SK^sm_nM@};RNE-SSYIA%U)v@DMEo3A!}t_yp%fVcR1{E>1Go8iJVic1Md zOto_KNKpxoz(`-28b~g3t_v(?%dNd|mhptTNvPOQkP1TS4qRpd7vfHL)B#=$Jm5Vn zJSUbnD{d-;8sqS)axKlin<2`LMQ_kf*$N{3dHYz74O59b=dPgOQaAlXAdR zhZo99)E90L$PQmSFJqId))KX{=y{V2~m zE=FUhl!VI9<%OuuW?yN1>>c*g7OUYOKc1!`?1?_h)W&!G14}nN%#fo(lFNq+3F;Z? zdYO6D!;IYg?tBc(<&$$=hRsMFaQcP%X^ONdB)WcHEKhoD^IgJv>1Q3no!$~KVg_vs zZ6XJCSVTb?!(6@_JSW&A?rEB&8>|rzf=07lyudcB5^C)`0=Of!X8$Nk3E&-3Qi!sb z({DvL0)v_u$dd0r(rj8eLy+cm%^hK<%X!UEwbPD-wV{-u#@Qiu7$O8+hn#Mld&V_L z^xX`rvR{g~2(6lcA{aPa3!_EZC`GMyRWzNtg?FK(1Q*Dm0Exy3dpRY{uu8ep43K~o zmqHjDa2Xyq?3xGbj#zX#3|`Q$*BJP6cPKOfY)jI5yj=0^1pyF0vV#O`h>Kx>CH?Og zT}lf#Dq5?y#+Wx$d+IJu8Cw(_NJH$8Kdcyk)9)%<`|Ljc+o1k9ySm4VGd&i0Q`WNb z^}1HW9j--=`5IohZ@{j~thQt+PYo$`lYEP8qLtpx4zQe&(>tS};rY^1%F^Ir$wty$ zV2olTIP)0^Id>yQD_ukn#md1b1;`*7uLlj-!Jq*Q2XSMOnEqX&F1zh1Eif0YJVUH| zM+6xw9l(003A+X(r2{#e3Uq6q!}Akp=D@`AYzDi>`vrIgo0qURQHnh4+*p4Ke&zuI zlu1!0_`ST&RM4)vZV<4(4m7}i0&V;m(NlBeLs+jBg?KK?D&k@0j6#aVOmywt=P{sh zy;z2q9tV05N3joGt2js6iju>7Q$f#hEU3tB{>Uq+w_AZ!%xVbIAeM=HG}OP z>*6+8e|#}=(4e|Hpf@SFdNc0cn+}@|W+pj{yzSAhkDpaVD-!gimQHs`4DOrX)5#6- zTiDZ$NXXK1_AvPkLXN(TeoG3Klhv?1SZ0UIGw1cU4$v70Pv`c4%$@0Fi5&e4j)uVNz;y%;w^FCfNx zO8dMFF1szKo_bAi41YA%OYO9{kJX57m%_$JFS6>=lL?!!bf`;++Ce?72(z^Qj#aYI6xOk5*< zwJ(HvvNG_qmGIN$;ntVwV<%HF;~J-O*78=qg7>?s_*eec+aIkan>e;?I&>h;l)Z0p zU;R11efRACOf%S!bLQgP^FA6q8jg?rUMdc@y0^7mNR^z`JJpGi+vK2aon@rcws$|- zWy=g#*I_s%yza3~Nj4iuXci5a>UNs~nf8eDgXK(?|*LBMo^ z?*Y5|iHEFu$yp+YaSORk<0-78dL2hKh@&AuZ*c>}sBqr^YCCM~2$LRKRZpua4C57u zkA&ufLJSA_!zQi>6k9DPu-7niPNnaHNt>z0LK8TKr_hGnRv$K+%O?FuP$= z79JPfsW(so3DhEbw2XsD5gUdm8PI7GWH`T4s6+#PI!buy5z2XU-$+JEVEa78eSxKs z{uhI7NPN{sIiNza&X2S~m*kCAw|k8L*ED}DX!prP3R}^S*!Nf+6NoXQT zVgjHmmvS)&p3#h8Ftkc5d`sOWAafP^svDyucC|d;PX7aoAcO7q(g5Tn9Q`eeuq-~h zZWjmM!jPP%lI0qba9gnhm)|y{hSbOM3EQfq#CZF9-sOW|N6^EYaTTtudXT!`HLliN z>*dgt`vH#73=`Kt`U(x&WhZJOOLJ8;jOBHggucpO0`Rv#dt?`{bg;COc*MEHq443$ z)I4!RUOlj)Ni$wjBR`7X98yDg@+Io)xzrWn##u&Rq=|!wjSv5_|Xk{iKS~qE52j37Go)DRKb$S{kU`ASK_eLoL?$!l@dWxJ zAP*r1LFXs$GJd6lkM}O|>fW+4uZB{-M*E-WDw`wDe=IXs!6ZF6WTg%TQ<5LfEL zSvu;??z9`*$Gtd~&&I9wA`YQmKgESe%LqcDW6Z-xI(a_A`&cD(E&K*t$_Tj~Lb(l? zi+doLGt^kP62_nyz z;4ygLG{_@132;5;`-5}#b0%u8n8l3Q`8T+`#zxj3>1MUqvb=J*pmSbe{yrgl-p94W6-aB3*7#hY8T>qcXrbFowS z$>OvJcZ(b%3W+AI)~)&K>+iWdj`<3pZ6p383lHURPE9Kfx!KI1WTqzLz!GKvwuQ0} zQv164jIX zT6i7TN0n0rW7tb=u(^ZALUadi{*6=2?Unj+Mzz;=9_WT z&Y*nPwix+S15tx?t3dcfv<3ubbkd1lLk9g&3zCxvY_PFk4H)59V_OK-$Y%IPF#UJq zd}zr6hPc56fnG)&z2}I{fFug%;L+43`r8B&sqS!jP!@`pk$GvYToPD<+SqA)zhOe zVUD>t8p(QlQ)D(t-Bh)~d_Ts9VE2R@)vTTWtRHjiVgzX;8u@%+V99QP7#RbLi}+Zl zH%1bls?GV4dA!Q*kbCOU%D%`X522HFwEA1xABQuf0>NQEPSok8+hqusg&eJfB^U$~ zCo{R^e;p{UAf&MkxEdGoeRRU#2FmXDRmFr`3;=*w>s$N&su&OZr`6P6qeBvRleGET z*L8{h85@0WQ_TRBXQl;Lg}Z5f2rW0}f8CH8M`K81kX#%q^STjLrAaKOwEV-saS<>CNoWU587 z(W&S1p>_Z%y*1BF@>f#7pYpGXG`0~t&p1D=# z6(Fm%(`(34>WfH$xr&CX>bQ$7DA|rnwIg-ej%@_c2p`W5Ki*MVX8{<0sAl*0Yvk)s z5VIqhHfhts}$t8nH~a?Cw{9p4=u>DDu<ns}8qk&EfQwiIsFLH+ z;3b7Wjc=fcbG@jjLeF5{VhzuI`~AINKh4=C5o3E|@b|;EFT?+TbOZyvyT{Uk+XMw* zK?YhV-%uC8CKBkr#G~o}B_A*Xkio#l5I4+~IE%B9d@GDo_xv1vkq7Z%c+5H=j;mum!}0<)V_XG%>r z#IKu^V-~7m5n?NBDFmFO;aPMBRY4o1C)v$5F$jX^IEz2YEkb# zQQt*|vLSNlIkp8h$XM$q%nhZef&5EKas1-Fa{{XnE*&>?^=$){ljr>mdWPe!h6gYp ziwJ_m;Ap^7d8O|-gkwsg)(dlS{z`CODs+Qu0W?iMt@36-8W{=W)Eh7<>>BhMJ6fF# z7b)7<{$LcNMZ@{wlFap>5snXQu5pS)4PtwR7_c&9u_|av%y*vXLZlp|;zI78C&Es1 zj6}B&P<_kK%fTM=@}m6p63cP^a7ZheN?uD)o+r_*;URGlXyC0)s}??BQ}zTfq~ylp zt`1LT;N(NVJTQWD5>f~?-{Ofe!wn4yWQ);ffm{6mYTlM`UG4(Z)w+S@W-KO(>jmXX5W`-4~;Osx;u&Yx?7`t7tjs`w;URZlHz?-Fh03^?X}Ry+HKH# zwHl8U>Boj^nZb4*j=GUpmzUYkN;Ce z6llQd3cR3f7+cfF`1#ygVBC_8uCfWbsc0;@ie8s;*v4t!?Eg0=fcQ%}$N!DKr##s$Ve+WO)ct&w1uL{13cnXpZxiM}Sl~RNghnsstGX48Zl! z#$aEKMHzW&eX!`KR*;jzG%5!SLynk`B8WbAPh_U()r9i}vjEup!`eG#!P=iznJe!W zUN?sa;uPV&bF!GNkPKKh^3XTTx!4>jAsI#4iwWZ_wsb;!oIBaJT=nq;cH}rUmSVz1 zG~2QbT0X6k$Akm>_C!W&CS^O9A=s1UmB(THjl;OgaOB(-?B*cj-(ifHNptJ5Spwyx zap~tk>4VQqm@VLIVVjW(6p2aESDeB)PA34LEhEdX6DnbebsIU07LTs|RL^DHJPWz; zPXRICJg$Ui4T3yldp}TFsRoP>ocm0%MJ$+DKut}pD7{>{Q>^3qFQ;GZHO(q~XnCi( zr{!%#xTd%Fp0|?aM6F9k=gLi9AoO|8+P1O>5AN~tJa%?>@xeM{zDMD-X=qJEXJ)$)(?r zkRX!n!KfDnnclC6AN@JVxcc%5W8()sqY|j9cD>t@r_LP{FgZm_;4(6JNO&MZ7=XAz zZb#1Ih8ek>y1;`?eEpMYxvJcZG}Upn$awn>!~WjDnTHn-hx7JvIuq*TxyG!wab}u% zfg)uNBY`3%dS&Wz<3XTH_s|sGFWa9*pdZnW_V7So%@1o$)Iaa}y6TR>PqS_FM<^1) zbl^}_gNa-Q!tf8{rak$`X`|^8xCEFRK&@Oj9J)2+7Zc0j5ZcdoLq@7UoCpr7DGiw( zehp$%-x3&yYpi*37UFZXaLKOl%4V1XWorjl)Y+sxZrgd~HpYq*LD)gW>}2>$u-Xan z)@1~R24;q_OK#*;#L=EkdI&cHGr4%VAL}eQt$@2hJqI>eQ|a$1vKUM^uz@cfZ|Q6X z2=&PtLS-vJo()B}ZO7_D+NFYnTs`(FWA-5?G686JY!-NNikb-9fOCvsc{bS$gFWEt z=KJ^SU=Vz>8NED=DU`s}dq`2oHO2r+rQ0|I^2I@?37iTr1-XX-b02XDkqiT}fiuA= zG=R3WaBQ%|Bo_5= zEA3B8*=fc#sq>RPLiC`Enj|drqv8%c8eFo!+Um` zn@cpowszn^QwP|~yu;94zEco#<(1QWex~E%OD_c79z>jw9VPwppg5LW4oau($1Rfs_1BZ zy2N5Sjo9v<=5w|DQ7`XtNpd!(+Pqy_GQ2e5ZPME!`}|!-n#@W`C&0U#8pz!#8|Xcr zK-|!pck@7`lHB#Cwj2}pa8kSL7NnG!88sLf;Kg7Y3DQQW4FSq1IX<_dnpx(NTNz$Wgrh;8i(3Q*byYRguG%F&Z%Uft_Y5Cjhk`O5y)-dj4{>) zrv^C+m6#GR`iwJp?L>62TQ6mos1LO8J=a%`IYXM9IiU57JI8}uiK3TyzHwlULnk+Z z75bR(Brp};Fy9GPVVunkdh0xxb4lRl#uo6Sps3bc5VrI9BPvIyElxMW>vA}Ttl}V( zZlj;}c6Mut>tOqqSxv_J{OJ+P^R2zh2`PwhZW4#_sY;cb5(9 zyPB-|@G%IVrzI;DoqL-D#cz?!Vot0RbGQkU-r37nUoCl2->tng15|mY@wwjlgI?2F z1?zOJj~L?wZtPO*=AURX(RlhEIsV$)jwS8*ys9nK`r&WkSL5#52%jjf_pu%_gUMXdO(TFG<)~RewQxXhbvw z!}p1%CmoQm;XIb1``Qf@7-A@a8B5q2>ZATLvsGVU3*Dkhe(Nh^sN!71se^C+uJ5Hs z%VoMVEiO*bJ5+u>gWr2KZC|?5aT^nXSIqZ$rXjV456{nrTho3P))(xwKbBobW1=DHqq%)!(%MfYi;X4bgZk{x9`IXgh8&l z$55HB%AE%{m0s1*oK79{JH8B{bv+0M$s5qfHjx}nAUp24#)gZCt#d5!3dq^bc~|4V zDHn*L+UH7qbIB*h-?Yy08$N)4~99)En{pFDGS1(Z01~?NQTUXH&eF&1iuSb9PG}q#Q8bM%1{Y@ zvbxLWj5V<>&`4AgRqPoP=k;IgO#(P-Bqho9S#Q*I__y>7=?&v9kt|N10`ZiQLq)`c zezy{1HPa-*?u!T~$>jBvQw6GmTwc z_1o5w$yKl#0$XSAqMXdj7u)t(Y&E>ouCh0*wd`HPH!8C>knys9b*dxu7QmyofVj2~ zC=1br#WM*8E$yo_-t3q>Vx)fUIg1+>d-v46NAp@P$*Kbn_0L((oq)LoR= zsA*y)o7ChzVUjtCY$c9jbFDvnbxe66 zZuJ68T7ZON$_54J`UD0_uSZpTDO*OSMt41}fo{hzC(HB-XgX$!dn&{7+x#ysa)*g^ zEr;Jwv!#5-{98IVgIzy`Vk%f)0YO+@G)%N%nf8Q}0y1)-xvm~Cx~U4vD@M!kQ26KW zFu^XdmTK6lh0g0)?0E8c45CpXsu?8}WX*zYhFlv*clYh0K7|ltY^%n@j3(gKu@$R1 z4Uh%`>9G-Kk=3%Vvy9%h;BOGB+ko%JSBN+l++%e-vb7rc7$39n*j+#8j90+q6G5{%dAF)Qh&n7?5R`pp5ae16C4wda3$?X|_l5skSRZgsT2 z5GIwuwTH(~cFM0EP8cYjm@_Q!R8uJ3vY-{A6Su_EYiZw4rOStU{P04{ko)w2jDCr{ z*ZXGYpUz*J!0eH5Rao#5=Gv}FC^*=|!*5J%9UvyeQiv9dJ&6J!OLp~XAc1V2$AVvR zfo-UZ;qsY`2B=Pvdm+Zd6EuX^iUyHYaw(ypeWPt{CTT7)rSK|l888H|pf%g6*ikt% z0^1lpPiTgvw;lTvinT*01bZm(a?C>8mB@fP_(>W(q!0X+91N^4kH9N3SMCz&2H?a+ zd!UPaCXO8!%~{h-*ht0=;#<6S;m6fzNp-u%J7h!~$C=U_Jw;uMwWx#z>D7}|Ny=et zm+~g)$Na()lBi$7_4@@oX{Jlu1ao2`Zcm=+h2*fvT{c0wl-)bdIiI6s?=;frsC}Ap z=G?yYf{YJVGPb)rE{uMiNW4;#c-nsYp;Nlwh-S2;98K$`%-uNi6NdZyy$?n!_U1WC zu{lp9LyotJC3ikT-@6)l{>j_8C7@D60%|@vvQ^|hvr{Z7nWl?!^wtFCur@o|`B67p z&+Hpkj8|uqNTCa8_sg@HPX^2^NI|C98@W@r4~xDUYz1Ov{`!-W2qW;twkDr%L zP&S5$Kw@oFtS%7~g6 zK!I_ZmtxA`+sKFXcHkOJ-symBXHE>Ww>yukTv>|t<0Bx&GG{5dzd=Jx>A_AOm4j&H z;}dCA8O#>$HIcXk6Mj_ze*cVjsg`rDE8S5TymDP6h!UuBrFmj4+9SF%V1VK%rOrceN$fS8VC&w9 zXE7)qyGmFlu;Wy>^NtG1WQNQnXNogYB-p0n$WbD-F{F_*OBd5_wT~B*?e@%ga1K`p zc2{#I=)%Qw<_CSoWUzf=Kzvr1D>u8yalsAUfe$5!LbFX|Y`F+f2Y!wvicMTGG;ccyy;n2_4|^QU+pa;-ATWY5?uCpr{~x+sqm zn$Mnb-sFophVq?#Pgm~81(?t>tD2%Wx#tvZa#$isGm%vVZe>*c4kwL1hmycBS&Vq2 zjgFe6{p!B-b4$8*-_7TCU_2Rm^V+8skck2v;*2sNBPX#u*SOLI@|TJNMf;3Kf zjPT;f=_TjF`ussC^F-Ctti>aB{f3A5O8)lM{a=%_7H#UP`auoQo&*nH#KCs1Xe`m8S~+rm-Yct^fg2X_}3=Z@+%Jq1he zm(1feR0AtM(uT14T~)X7t5Gcusx<(!pWEpy{Gl9#AGj3GZ%!FIz*tuRUE?Z_qn@K6 zO@I=jBThmd_eC%EO>RL>ns4UdTJ?sKMB=x{k!u41-0VR57-+N2)Pj6Pv}Xj}b|PRw zopugm!9U;;wEfz_zI)zB@_p>XN+k^oG@R`d(aDh~6z=WcdMbI+$*I6&opYm}(kyoy zQ(Qk+&SOf+ut2**rA(QW0)Czx%NwjGZ|*iOwI$Wb`4)Gu z5K@6y)kHe@C{7MU3~Sq+J#>j+pEYsz772$;r9O_SY4(7pFeKO%o#0VJu2u7K>exM` znAi<6XgZ8;%w)DTOW99R_6v?iTML56f~nUTa*+s0s5p@5yS=^;eU0Uxf^k$XQfh}t zp3k_dS%r)NtzK!pkZVmW_cUKu*=Cc#Bj?i(>do2%#Kr}gh+ke$+1KyQ$=OpN|I$9i zeL>?xhob}LWeAOA(?!-gsN=+RF?ui>+~l?=`jlna)*_c}58seA97@;bxuk1Fp1Vf} z)6TN4yCeYb@kdUS2vh#wpy#aq2NKPjdiQFjlP|Y&YrBG4#W9CqQYfE zu{g{gVJ6%U_5EeBq&jtuHZKy`4|+6?!fP}5ZCC}!j)MomvnhK`E3I=ro zf^}ETZS}M(vek*LQRpDg_PANAl|K6$TYf=W5;ABINnCwTYZ#T`&|=x-jS*9G>^g(o zz{`?yy^|v4?mD%6yGxrggM*cRu62#W90VGUQ#~ijc_8paglr#dDV(}^pev%vc~5Vu zU6H9%aYtcq_D(oQ(^~k@2{+MijPB)&e=VE}w;fH*zI+qmX8OaAt%Z9EM(d!&TX8lY zs77wB`o$9(g^3yuZv8ge-}zr2!Ixh7FAioL@QtM4p^)kkoq~GFeGh}B;+<9OWo5;+ z@-;Oco+MP_%>s*SWbO59uO@{}*mUImbG!gQ=I@CqD-s-o|I+Yec^G|c+v>lfID%nc zAo3$ndO{F@(vt!X2t5t=FR=eXq3k!Bnk+=)Xp4^H8#?)FIBDF%mL6@M!wPK3@UzAV z`JYyqz;eRc_^<4MN2vi)crYFI9Ts4={y=erI(fzbvd2FPh+W|B8;FM1ApKmbs0lEF zD6O-QN&2|;+nD{ZrSvmk^>-~E`6Jhaa!8m+B$BWj(C=R@i{{x<>BAy%`H;xq@NMD4 zXND2{OQN1`1S)LpL$2N0?n7349ki`f&;2y*bPL-I-uzkEM-_9!WqnSNCSAkLM2mXJ z`pN$CN5Ybs8c$y8+nh@Kj;QfccdDhZ*UqrFvMVetPvfP2SQ@y`xA*0#zAM;X)@ui> z$q-I4VgPxJYeHO8-q=M^z$imeW5_tzCNn*$j+%HZOkl*xxH5)Z3tb$2&wK0e?Aj4v zAu})3JJPeOwhx8Udv~^XR;MR=_}SeO=b{`pSnY$v9*49E%~uZh-l}W90xFnk*{=)s z45!@PL-5lG6R)Mkaf3JF&;UDD^R7le9lwY_X36Lut=2xk^x4FC!V z2hbBb@Ne;=lxfyV)I3iZvuyykbOw)%CI56jblCZ46`F6Bk0&`~ILjfu+TI~hn*gvC zHUhs-tMV}-8WnQKHo%06eJdOT3t6^gKH>RgD|{qET5yCL)lx4e+KA-xk3vN58e0H_ zP!`zrz(gB63c*h)H<-uY08|w`sV>l$@7KgaY@Na?Cca_mtU(M!Y7g5fAG(ohA3x-K z%NVy3G}e_?kuz4!;vvs-sxSOX6Roa4%x2ArH=CuG1sg?(vmLIy^a(!oX0a5Gj#_#>Gu(`p;e zp|L(9;??=pu0dA?hKrA0)(T&+S ze%yQ)8g-PrhSC1Og7pk135;q>q90BUEM_eE-zZb%bf%cu6`TR;sROlb38>xu3c>YS z(WM^pY|2?-5fP;L`k2*^A6M5@R8&IN{J*)=-RKrd^+aNovX=1f?yIBpQQ717ukJ|q zN!)SU=cbX;xMho+vkC#lNV{Cz}k?i$WCZ{)Z zZ#_+;vFzTZ)Wkb>t=5KIiX_-U(Q>wrIm;MxfoHczD-LEB$vYhL&U_Pc(j6%}p0@ zUa4#SLZvmpzS#g0FW3jJV!%Ld6zcu7>a+@P^fUTxCElF}!RxnBw*3A7ruyMZ#Mb`- zjB5a^029LFV5~bkhXamkO8`tzMf@zP&>KfoxhTMr`jqOjoavI@WQcmEt+ zmWEa$%|4wG;+Iv!Ld<1Ss@r422pQWJ@k2%=(=Tf{6Eo66UGtA*3PS@iyr{{3b8cSLv{_e(O=D|)pk5|;wB>^Z&-jRq7wW-S1l z+`pB;i=qM*Qy~gRclni+`fVuf^^!q}T-;kOTnng3z*3+$OI_ zK)Ha0p~-=55uW^;!LZdeh$O@{5%_w9N+eK8Xwnj%1MeUFZxR&#`2qxgz5u@90&Fv9 z2*D7wMj5e|{o`d&^6x$MPgV{Qu!~#xcWt08asno3Z>>za~aV~MkS`Pa~#E9mp^m^ zK$iC3a-X`a*9O0S*%DtkEXH}Z!BD7fT~X0%*ltoi42JU=)h>@)LQvbR`HL&(HPuhg z(V^;(uq~~TK|O9!6(tS?gO(2$>`&HHh{5m4(Vld^=inQhU*{m6w~vP1hwKu~e zeLD~_qQ@jXe}$@+Mst!?KtjF03R4$a@$+o z;ljP_a}5XWL0#>4`ltNYcSF0abt0_Q9+(4MdICn&0Gs~~ULhw^0Te*dSy00K>DbH+ z9f*M7|2KR-|BWC0zvfGm5~+dk<;BuP*@uzuHH0rOmhP$%M<%JwR)|3KP{3m8EsIoS ztF*vY>CE44=i4GSHm#c&&0Jqu_D#{5GghhtC#P%ETspTRJ@-;8oH@v47cjMFW3E6u zh7R%shqt1hp$w^vMFO{1!x_1depu(!MN z!+0~}aocPH%J}=Eu!@>l#)dj*m~TF1d{yrXL()gi-HXiaWWKpw7Fe^(O!q+y+@%MF zis-O^l? zlmxit{$wkS^jg_FXqkMWvAlV$)MWkZ0yf}tlKQ7~u$6iR`Ti(&6K+Tw0u@y8&D+R| z^glOc?{29(tp4%2;KNP$=mpdgHw!=)e=g>$tk7w7ZN)vNF5&4aqV@@rsFLwqfv-<4 z5SR!+fmIk|EQR|ibl*u3lI@oFD;__!IvsqLGRO@aQu&__50_tE3W@#?W7eF?Q|5g zeE_y}29d=AM!D)-0;ml3g3P^q0|&Qa^88VqMFqdJ2?wf&4jiZ+Buf`69wZEdd>Y3a ze=(L_sdol8kqFjPt@N`mtLp!uRfS+DG4*a<#;1rjLG5GIhEJ;?51>Mh2V2oxJjS{Z z;6I;pa7}>Oi-T;*xLAd9d^E39_H_|2fevSG?EjW;6jwItVm4fwbZ*!xYLP5!ka+Km zN8q6#Vx%9ziDutM$eQS@JSTN-T~Pm|BT;K>Lq>bL(ZIAbzkDO#_%$V+XaLh9t z`{j;9kS*8hc{P>n-;#}bE^Rzp13Hnkt5rCB4(OM}mbL@`7rmiip9aFe1dYBSrOB7r0`gW{(AGT+Q)g>N@+%s-= zYIaDi`~F_9+8mtpcU2dXwbRW)Rg}!W+qV$pQpR~DmvVsCFCxY@l6*jNa;-$ZFUaOY zPXpL}in@NA_yPt-OMdlQzd5RVC8X##uk~iQGCGoeY?aPuuk|0*Uat)$*Ipw2PZ32zlW}K zD6qPA>P`5!{f~Zdp7l~543Zc$-ZSZ*hP&{({>_v?F0<}qWFKhM_{(@1|#49*OuFsIBKm~C%?DU89?lVH)&A7Ce}L|Ids*hg;b9z~f z6w%Jp3CN!o_!yEKBfBN~m|l=&7e2S0~VBDsk2>`2OMx z16e_lKC`(&sScqwjxK4bA%*mi`Xh-N4^6?Bf74m~B1iZS!QeNE!apm*e(rVtsn>gE zLDaU)v#us=Y#sKcJn3u~k8WGBeY>0*uAm_MyD>HHmv63tUg{8DRK~rs9H)9#Jhk6W z5q$sGL#zO8LCw2yzk3VozJ%X@>F{e-I>v~NB&>z3PIr_0YHsotS)?|U+~2Bui9h>W zLRYv{77TA@%HI9`b{0|^NJf!ZSd?@4h()FAzPNL|_wMGNU!K{rMuuy`KZwjoR??Cckuwf?VrFNY zW}MccyOz%G5FoWWs96wqEt*J?$RlYbyOa3Pnc*}EP^~chxFcnoN@f?T@m_S)`-9xj!4r-=hHJHQC2#7$r29Q; zOaL7*B)I5K@iaO#4O{`be&4YAtH&YK1pgU`ClMAlQ1vB%$amyD%K%1(spMlxa~M4|%t)jv)p>q3Y+tiK zTahIO*7shPG{cZP&JvOccrR?>PKCB#yU#(8qg+otL_fb)vfalj|>m@AWK699Om8-dGphu zD)rD6{}RJgKZD?+*Uj*ly+{2W?)e87(l5HC<>hC+fxaU>pgcRx`B0X*=B|~LnU_NO z?m~q!Z`&cCut8&SlQK&MlNZKUTfDRF-3`-^KfD>Fpa0agUQN$P_#<{bnlNS+hw;gS z+F4No9nw~GZyQb7q_55u?CM^GF|$w(>Z(BAzW~Tw1iDime~WGN9&2~ypW8|o=CKuh zt3Kr3nVy*v*C{UZZAJH{rYNZETtE;PbxYSKM zm#AwVm~gm|8d425)<1l@zyG9{9|MzSyM$%=_o)GqY5lMA@7oxF3-jY|^6yFyF^4KX z_*nm4{@ur(zyH*-{QC>-wrz8}7yIABx7Eo+a@RDO`o;Ojpo%)Yxr$?pDLK(U{E~4{ z2djYb;8-=$4^O$)SV>$>0UN~gPovO_N$Z98>hnajVT68rCue=&Lhh-q$-=#dq>{`2hP zKX3H#Uhjq}^7?|bJhqc|SydsH?w7!ga_=|uR=Y=1swXAvfh4#!$H)YiW4G5XMWbt6 zIpnG^)1R+7J?Zt^k`SksL<@?WsGna{I8mL2A0)DkHtHJLqAD!Hg`~4|uYy43?6)=z z^Pg5}JJ$A+QRLzH9|2NJ^!%mHoWHM~C#IL5h09I3Y*VGO{teMX%Jp@a{rvuIrK%sZ z&ZP9(Jn;IEpr3f5B5LwMqF=+mlPP=-yI#k*HMXD4r?>Yub_M-vKJCwTm_B^K^*8hB z5F)zql9KA*&8KU^OOKug=F`Tv>cUl1WR}<``-pSp#PKBiK3v5+xsyGis!#c<#*~nh z!V>?ehk>IfW{U~*rSIe}Bj|lUR)K<5NEvZw(bY6d3(5UPps}oHu=ALjhqPBxxD8RE z>TV(Hp_;?iYv(TnXRfhpuZ5(3$<71HM&9C)K1c49+Gp9^)6xoaj5FHK%9Z!pe=0;H zKQ#c{lmD&kh**GAgkASq4Y>j`@1ZuTj3A5&xPt4u0E}G*7mDs|qo{RbV9djcd`F&w zu&OG=fbZJuwW}VudmiFjo$iYeYPGR5ZwW~bl*-37A9Ty_-vB5<2yHwIMpst#{9QPf zjX?g>sy98$=(J@qxP)r}&psc`07G|G5*WINXsmP$7+L`w(Mqp_U+LhN7yoiuzO0r% z-dJC5qAz>PKegrlMcc_rV5Z0e!_~aeWuIm>tmLOv9|F%L%zAPqp2KC$qWEZNk(qGQ zY!?^yoW978W)f!M@{mMxtzNR3I>55~ikgs*LsLq?BXm*|t@b9q7))P-6)xr$AY*R6 oM^yy57-twOd-j)czZM%w`%gsj-y-^#@BeYu^S|>N;XV!hFY=OlmH+?% diff --git a/Svc/CmdDispatcher/docs/sdd.md b/Svc/CmdDispatcher/docs/sdd.md index eee5adbb3c..8147d5d4ba 100644 --- a/Svc/CmdDispatcher/docs/sdd.md +++ b/Svc/CmdDispatcher/docs/sdd.md @@ -56,13 +56,40 @@ When the command dispatcher receives a command buffer, it decodes the opcode. It The `Svc::CmdDispatcher` component accepts command registration from other components: -![Command Registration](img/CommandRegistration.jpg) +```mermaid +sequenceDiagram + Initialization->>Component: get_ComdReg_InputPort() + activate Initialization + deactivate Initialization + activate Component + deactivate Component + Initialization->>Component: regCommands() + activate Initialization + activate Component + loop for each opcode + Component->>CommandDispatcher: cmdReg() + end + deactivate Initialization + deactivate Component +``` #### 3.3.1 Dispatch Commands The `Svc::CmdDispatcher` component dispatches commands to other components: -![Command Dispatch](img/CommandDispatch.jpg) +```mermaid +sequenceDiagram + Command Buffer Source->>CommandDispatcher: cmdBuff() + activate Command Buffer Source + activate CommandDispatcher + CommandDispatcher->>Component: cmdBuff() + activate Component + Component->>CommandDispatcher: comStat() + deactivate Component + CommandDispatcher->>Command Buffer Source: seqStatus() + deactivate CommandDispatcher + deactivate Command Buffer Source +``` ### 3.4 State From 5edd51baba35ce0aaeb2e2203dd76b7bc1413be4 Mon Sep 17 00:00:00 2001 From: Ani Date: Mon, 25 Jul 2022 16:44:20 -0700 Subject: [PATCH 035/169] Switch away from C-style enum constructs (#1589) --- Os/Queue.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Os/Queue.hpp b/Os/Queue.hpp index f0dbf63ca8..ab98e2436a 100644 --- a/Os/Queue.hpp +++ b/Os/Queue.hpp @@ -24,7 +24,7 @@ namespace Os { class Queue { public: - typedef enum { + enum QueueStatus { QUEUE_OK, //!< message sent/received okay QUEUE_NO_MORE_MSGS, //!< If non-blocking, all the messages have been drained. QUEUE_UNINITIALIZED, //!< Queue wasn't initialized successfully @@ -35,12 +35,12 @@ namespace Os { QUEUE_EMPTY_BUFFER, //!< supplied buffer is empty QUEUE_FULL, //!< queue was full when attempting to send a message QUEUE_UNKNOWN_ERROR //!< Unexpected error; can't match with returns - } QueueStatus; + }; - typedef enum { + enum QueueBlocking { QUEUE_BLOCKING, //!< Queue receive blocks until a message arrives QUEUE_NONBLOCKING //!< Queue receive always returns even if there is no message - } QueueBlocking; + }; Queue(); virtual ~Queue(); From eac659e6ea1672d6b455b3cd5fe63a70232ac16a Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Tue, 26 Jul 2022 01:47:25 +0200 Subject: [PATCH 036/169] ActivateRateGroup seq diagram to mermaid (#1584) --- Svc/ActiveRateGroup/docs/img/RateGroupCall.jpg | Bin 56285 -> 0 bytes Svc/ActiveRateGroup/docs/sdd.md | 17 ++++++++++++++++- 2 files changed, 16 insertions(+), 1 deletion(-) delete mode 100644 Svc/ActiveRateGroup/docs/img/RateGroupCall.jpg diff --git a/Svc/ActiveRateGroup/docs/img/RateGroupCall.jpg b/Svc/ActiveRateGroup/docs/img/RateGroupCall.jpg deleted file mode 100644 index c783f63892d54fc1975fd67b895def640651c9ca..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 56285 zcmeFZ3s4hTw>BI_ML|Gra#J#jh=717h#;n4b$|hc$X!9nAcNcnBMK5FCMx%9UKK=9 zh>934VpKpBA&~@-V^T5huEVT-PB7r0^DkrNkIsI1o0H!w8a zXtv4R!p?rX!wyHMy+6CSy8Ytr;pZO^7U9Lrolh8{^bIHsWe!0$`i?<%OtT5T;3+f&@(WSC_gPqV6`YzgElKpFfUHJbc*}n_+ zA94+0Rw^w*AD)sX2EZVrEGKe8&S)-SWlassfb0f86VYQTh_umLg&KUG`b# z5ZMlEutR}KFN8Z3 zm|y1QOe$C>zW^*aRLIMzf7Vi4aMY<8aXkS`R%c10GkB#v7-(XMfg+(Y$XjR4YZD|cw;{d3Tls?OPI+;RC;BWNfDK@ zUG%*Wf&0f@mhn#wFiq6H*1*|8ME#wuz+8AP+mj=?H$X*~q=vK-bSRs~2`eZTGAyhn z-3!l-_UA|gWPSuCSs+Xk3Y1AHJiSt-UYWU6YlOTQGUE_ZSC0VT$Ssiqqfd^J-vN$x zW)_X;J%k8Zb%Yd${Rd$0cAk7jEqKSw)ZpHtwR1&j60HJlzdZ6rtr|B6n}{{mMtXVN zFx#syyuywjsLD>?TCY+%{&BBfMrB52PU=iLBdt8Q1jCE%M5_X;q#;k76go!2@^5mfgQ~A=qd_EjFuuh0H)y zW8(Lu|6Uz4t+9wlAJRSq^s*Ab6QUfs3QZo?GV2OuP;j;psb8S3_51?|x_52cuTdWp%v&5nNhc_x#mA%E4p*JeKPo83rJN)b0TS(BQj^3u%kEP)3DDR4~c`{|8 z0;5D;4{JaKWJM)7E9_u%2|1zKfPvjL1tx}`gInH}cz_%mC#DbPh}hhc-7;`3Vaek;~X5wsQ>j9mw?bB2~z4im2bJ%1LsK>!;lb($d+W<8oH%8>)el|mB$R@ujjcpIhVWYhWqAJRhkCg-(uHY+;KJ-n2QN_PC zQDDl>(0(+?Hn*XU-eYS4kv4C8ghjl(AkM$I)=B@H#4{$WDj|%%uh^P zNiy=ABO0JC+!Jw@t?j2qaqp8gyK&Yfo)QkIz&!69+{Qtan&r32aY^yQy;2L3hIl6H zGqULuP@6I32F-{a(th7e-af?4o=yZ*WSimHlQ#Lzk@2G?r)FCS8qSu{&|;5-yUn#R zK51+054pI%E<9tcRd)5yd4I6JBCs5872QaD1fyiiw7Axy4s#he222FXH2$8J}$a zb!}C9N9m#)0Wk>>Epv)xf%F0o@F|EIr4zf9VgWOR{1(9=b1(c%8WdZ)3+{5DT~c81 z5YR%)6Fkb`16e@|j0RcXS=IQOP(uUO8+EvVn8Q6mMQz2UY@3W}y94B%u?!&|Hg{`% zf-^cq>Zhhrmct#WcfdX*aEU`yaS@NGMq=^>OYE@*lQ@Si%J%35YC58dyr$|>wD97! z+x!QdPlLaP#5gJQ=*DCl;-aX~t%lc;yWfN7iWb zO%HDd9+w-QTu5_q)s5+CJz^GEXsBZ`kiWigrO>w|IAOA<+Fcmw5=g45Uzb|uZGAe? z-jHUr*>1jI)VvYC@*;MWO)h2I6Zx$?My71tD0L{DCs^fdKvYISO*xos&}WC<`wahF z&+`+cvcR0fP!Z?w&QNe#s-ZEFus9I}e64&iyzdO}TDN$S%uRSg2aK>XGa z_G;KcsK>oJ6)CTvIJYN7ie`)_Sf=2Ot)xgl$n88!d|fgvFW)>@gB|VrHgyer1PtZu zhvh^N_pRj=yZ+R(lb|85Ge}$u6h>TO0wo<%^!?>Ota-%5fXKJRaH z%{R1-l_Hwqni$PvklneSfG9eSxtZ7rogz)VSg}2UIB)PBc~Zszll;6*h-AgSuJ>U zzu`WqOd^4J)es;_q^1*AHzifUCXz&XWdiX6R-I)`IyEUtl@}kw>BBJt-Z0qJPiW|qh^?VppoqMs4Y}>6E{_GUEUQ7XCdka2X6eWrVH@c`;BX-`eU6}Mq`<6t4#Z&d>9s)_ zO^2?WX-H)$k*dXRIZgJW8dYw6M!BEP7q}2mBY6p(!95VM#NxW20W^i=*FyL6M0tiHqUzmSmC;Gx z7CJNU+tco|M{f^E2&xLqQFcZ!>PKo!VWBdoCbo@YJ@6AW$4;#wvNn#$w#y5tQGk{a zQ`-fN!IYy%RC*GrniEbdlNyq6SkRb$bKI%CGeq)_@pNmG6E74JG+LuO04S&+&Qb3;*W-jM&)u6Thzf?iQCZ$D$s`K85) z>MP=Cp8;)e68`?nM=|+}cU%i`N)e(h9}nSpfvRYaeB3Tn6j#5C^|o*knh z%J4&E%|sDFUlt&u4f+Y0Q_wB)4mNa_mRTRC9Ec|62g&h}dc9CX?a*U(85swu^&yvq zpHq0$x}Y}VTdGL8^_fj3P^ZA~vBT=KT=pX(&xU45;}CM$wcZ!OByMA8E@gFesUdXq zdNdk-_5#a*2yB`HgQ4$k?w$iQKT%iVjL3L62V#hb>HRap*R>HfgKAh_wdhsYj`p`N ziEq2w!b;6ngx)@pZ_)d(usKb|F5u9i>L;UjpGKtTt{+?R`c70&n?JYJ3WZml;Ofls z?DEuV7kkga*Y#xG<^EUJvmdrd^)@G(TjXf<7DTF$=gRjK5}yIWa>_PpH;x)BkXZr0 z(vZA~9}LY8v=JJTrWcKB=+QJtJ(7cPym28Y;*K7DD%}?wsw-#I=bf1pe$0@1lEa}$ zjv#dgq`LJ3k=PYXUUTHn-A!9qj&RpqnBfnv4I7=boV_XAhUU&OlB-W6X$s6}`9qSC z@ME=@gsjXX`aFQquXcHs#Qw-A zEANNI){h3OXUil7^2a!*yuCs;hmD=U8nDB$h6j+IGx!UL*#z~$KuVkfL!4OyUlzLM zvLh6jT)IBa=sk?x17W9jL4;P{5dmD?vb~YmTC%-e64Cq=JP5w7+)fvt_2lS{iz*kW zC`ZvSGi@cbQ6UlB;39C_K{%sa=I|H}tB_IPW+nts|rclrFXe@((>W0>w)XIzOsK6|lg|no-WM@ddC|r67d5NvHX$w(xfl$<(Q%-3G7ByL^ zGfoOm4}11Dg@d!L+l#L>FAPY%NDL8>DkDhOOd6}g*F=OB(Z*)-JI=en8Ii+m z{R|;Ht5gTdIOiN+;T|rEW$VCttvK7Rjc*bOYHwqT*UoV1t4XV&`@c0d3>+P>d$ImO z#y&4cq1lx^O@~6`t{(qPNQ>sVR z;;G5Lpm^?w)34*~#G76SzgXzsbKP1HzN1Zk#HXb%-+1eXa^GWX`YJhxCT~2F*O8Md zU}-CR^VT0i`;mooa_RtAr$i3{n0`vPM zRz;Q^DKT2RXVSNa{eaR{HTZUDqS$VMM)*-)=rhWm2dG0qNQbIqodVO>fqK4WOlFJ< zZqJXL3wq!G%&%8Z4sBBU)8=0eQCZEm&;8Hz{{^x1Kb!Oa!Mgp==KRm*{9V)gAD{DY zwax!7hx`X+sq9D(Wv9%k0nWHf!nYwy6qszbDC1l`O_}tSgh#YG)k(EN^YQ?iw<6ppm_14BCaPSmN?6ApzkU9IfiY7tVQ{|I0{aK904yeQ(#h`@k3GOCdX6y zk3l$wE1F4_F_**ie`FvQlXzwLl+Coj2GKgKEZzAECC2nI{6%gk_{;kshZx{Gc>6zc?+A_EwgB z6Xo4vf&$Of@FnFnxeMFN2GC{cNztUD>m~9B0Zs)B*bBe*m3a79yKrip5|0Rjujl>Z z8lM2^pLw$HXTwX;9G0FYK`q$oL?5@m+BL?1!h36fUd-Dw|E%6q6RaEky5txCGGG6R zJ>?evtnoO0V@-rXca3*R@Ch#uU31Qz;DRIl#5`cMRPacz)yhQVogwN>?TIl=YU{ip zSPn!ov8sejwr)bm`w*eo^Ifq72+P5$ABbtx%eQ;)$2H8jkSNfe3@*>eC0i!nCXIag z^3foXs1>7(?{T^Ny8;7x18>?-(=7-Tj0K~mIB z{m)y~`-8E*H6z)X_iT4$!Sab>gvXX_#%7zo2QX0WQS4!z(YNKvA)ANMJqwSGH1-w^`Y`l+ zA;Q!m=|)nIkeJI-i>0qjTnd`yqnV1Do20V;_8W>BIRq@q`5lNlix=qtx@K_gC_4+M z4Smdl%!KUhX<72(*r5PE7iD^bhxb}-zjk|Qd|_7`k8X1@h6?_|hRr@#j_xuMHnEq; zT*8DUMhD;*)m(=R77pn`Rzt_iHKsMF#?_F3Q@Rn(5HfQb(bPjSfN{v zGroqr6-s9ii50P>TFp%t40?tDp{g9UnNJ_6zuCz4U~>iXEipeDS?g5q#O!tL~&JocJ);%tNDp{*M2ef2)EP}whc&(@Ir)SZheYAy`?u8|eaSBWd9<_0G&?Jc!StY(yzq zU5bIs1)52VV}5KL2-*#eWs^Pc0$DTlSl#yDkqy1fxsZIZJ8CmW^OQNI)}S#BJlV34 zbly1$jO7Sw1?b+y#hofu?W3%Otp&XP(lsDfww@Y`!#?buszKJnuXpC;Ie6Fh+56PI z9BP)&4nEpLzefC_14QxT5}+JYp5y8GPa-flpd4re|D+8&FNdN zv)k$TUyIBm82n26^ovBsc>m+TD1~F@G?{tq?I@N} zZTIg@4#H1$O#~RVIwEz!kuZpsv{q$^9Tb>-hO{4!-qk8F^*w$$b<#IY_JsRz%HUIX`^{VKY#7M^GW9w1J011ufg3?#i2cfA9UkzpP*$^v@A1eB`~AeVibM z1@&2h<*(*W`i5`fYx5528hGSu-3cx=EGTiZUKO|0bz(L-aN?wtLXDcAXVqq1anSDQ zpb+ncn{GawEEp0+Sj;(AHEg>I-;yfJEFk3;>QJPxfwQ~@t#0xq1@LJReaR$yRpN3P z0kYtFvmxbNin+|ap?`*~TMa8PKj-+@J%qEM>mswPV+nD3t)Z)m5$q~lntJ`+ai^o_ z)$>xMNAH$IfP6{vLs)!|4D|p08E00aBsx}I5p|s8CuC%q^?kR}{9)UF_W)<)Cnz#|#L~)jt(G)opxh=Y=@T1FL(pvI>k0NFJ!G8*kBD5g$Npd} z$oZb=&mnTL=g0?1OpNo5frOp_!-~o;RZVrxOyEJ;)NI1&q^D-Pbo_3WzgK0zvz+Ew zyQ-Jgz_UUZb6>xz$|n|m{wRIt91b!#4y;x3%S~uEmxwXN0C~egY>FLLoiu@8A`9-Z zdq!Lw`vT%i0^s)|ygu2mM@A50v*O_~-^&58w%9Um7saxJF%o;GA*W8DO&SY?*0#f! zxc*WqvZ4&+3z;owR@Gm+0#1S~uvyE|=7*!b#Lu0yCS9>~+UDmjd*UDC2H`=A)Wlh9c zyA!cqbtf+$eo8+TP&gBjG;sfM$b!q+_J>0;*hd-9*W!1B`1H@RWhfO-P^WBx%ftg0 z(wI5U#ITA_fKF5VJ$Nhxy5GF)X_&|}?wEKVlq%46rk0bcTN;M)1}-@76#}a#Daw5^ z$J3+3{5P@Bo6tC5NrOCFW^@~-{rrZk4DGQ)V+@KqjJDW@^Z_x%A$Du1eGl1Ix(h~T zP=iua4wS3&w88f~CR8oPiT~+e< z?ju#<1$y?=OY^FO^vfQ#1yp8w4!!m}Ns5%{$_txJAtOFr`ztf8Bk{iMm!2kSIeZ@qIw7sMz8mklzpN^#7B@sErzd<;<5KtSAK5O$Ydmq2$ zyc?C?Hv$~HxN_gz(E?LX)%IX)VELxO9`2VTmi)IZRpk0fw<~=|@4Q2^nx_sBa_7J`LoH4^dTR5tT8-2?6_$|d{6SwF3QHPkWpvE1SQ zzpQ7XdA-fM-ZJkeKkTA%Qlq)p+dc9|ohYsWL%Pr0FYj35^78oVKyAj3*B<^=qt$*% zY}4Nxb05r~{kdcSr>x=lhT}27eRJbe_n!=NmkHTcc@8y_nA#A$x>AT=K`NeY4P6Ug zq(aBIZHOaW3uTCCxgVgWFRCgiw)+Ljk1?U zUEUoh#AgfsGMv|n-r}(E zB`J@pz7A%BY_9Q^E*9EnP7`M2&h2vJ5mbXvFPUY5;h|c;21|2wz{rrX@CS z9Tqz9I<=8E$YQF7%oV;aygrQ;@$(W1#*@aj{rBha8YKR{UfJH8q$ZQH>{jUF_S34b-c{ScXAIiyEQPaDyZ5#zBp2*?IyA7A@3B;tn2^>+7OdR5XwQKCPEVX zL1X;RArldhBRedT6GzXEO$n+=ms=^j(6_V^wP5jqej7wZ&^a2LgZ4eH>f9D$TKYhr zl;hnqmqXYizl$?I1ZU5VMz*5S`^-6tHhI1L1_k95IbYyXa->kT#(S(an3_h$iVkc1 z{HTYr4i9Z>8B*q|Id~SeCJiw&>r0YR|Ie$5CdM)bL*O$3MSjH@Kk{3icae@zD@c&t zv`dT~Vu&I$C=Q;Z*RSvLdoECSHUNkHU_7{OFXWQ5*?~+A54c?Jr(E zAF)!Gtghu>(czI{s*(`t?H^QoyiC`--c-LT5j-%}c*ozDrMi{d&keCvS zTkg(@FL)n(A}zq+-pt_Vu>iOX;);W&9ixRrZBmes-bzRVFgPvQR-)nf2~tuk%b^FS z4zneBP<}bIT|+hWQS8VXkeW>p*Qb{VRq?CG7qD4#mUy)h(gpF}N8R>$S|QBZsN3h$ zbbS7?^uPJSuA{U9UtGVR7m7rg+ofnE(f>_e9y>WS|5v5-(l#+(x>EpeazGl`)0TwL zH_Cqy>X@=CMA)oTUNVyh%v}KDCKe>DA2Qbibr>HPo&Q^|MPKx$_9`$NB6)O45*yr4 zloP2#fvjfcKiNmH^Cmbuv|Np{k{42_lgUVT{oFK$oF+vHnHNXVK{6VnjlgI#;sF!M z2$LE6rwv+;_H>YGk0GzW@#qUJ*vDu~^?$oU{GU|F|3>8sjeu%-#SAVrg|He~A9ZTs z>`23?O*(EDbe9%e?GleGI$1>u;WXZV${3#5fAIZ*_Z^Imr0|tV7lQ={-?<;_-k=xw zrSKZg4xdM@*A^p|8t1~%{*2Bzdw z5|4sD|B9Z}ODP36?~etR-rrw%i8VBYw#}631dYYWBIFfUBN1(zbK%G*Vk>}T89rj` zQDZjpWr1uA&l~tNO}6*D?{?d0akgov=V!vlO*hWKv>2Ukxr8~dCUJb-- z1itK)DPh0uVWABTUp)dYqMgLIO#rZj{CyDj*I?JQaENe1f!R8s`>XNW-%mZG%&2{z zL|_-xQVp3&Zlh(6w$tFsaHPWF`(n;KV6S4wZ0wW;2{1fh;(`p-_D@&KhPidD4@iWy zS<9{mPiACFssqSJS!ZJfGoy%4sMlVJ!bJ=%@z zU8TS*n8idu4%0uQeWp1V!Ii&7B3@Dv7CT?tiymA;13)bDOIPGql(R9g|aGM+x~(D{8ub6aDv_1dW9Uhpy}^rcz07m$8kOp9V)Aw_)?9#V}+0zBJsgmd6ESWMvS~`oncbgUBDzCVXg%T-?a>tOkVUfW&eWB53JW$JK zC=0!p9${4fHTC2Bzn+$#N=(wwR@7UN+07qw4wfZHz%w#cbafwR$6s20tgDq*(2fg-7>un=;)Q6?u*;fOKw7FbxU)omke?>tJ#O?a zsUB|(y(rERsC)_@%d(5xt`^mvw2{tuKe>3PW53itZTeMIWBJ#I?Y27ir+U0Qs)s{@ zr4H{6yV@EH3stWE?rL~~;q*Y#sb;#vw{TPM2NKyOc}L^d`-~TfHc8j71b*|_bh~0o zWz+3*e_u>>c^PgUi6NwN&ib{Ds2;|^h2#JbR(fIY7s3^r*`E>Hx z@@S{A^m>%rdJv76Ha0(g+%S+J*!pGUooD=?^A{WATpV{@id!%}xiWBlskT~XTi-{? zfneQ-x~GHenoA5%RN?{>PoHQTJbZZYu(8;MlECCKhqBVC!Y!!2P&?G&3_*kJ#<_7n z1`im@Lm!-O(R162^!at{Rh@_|^Imfk*8Obzz|+~-+^zijl}SWl*uYp8u=f+Qvk-2O z`fR6)>fvR;=QQ$ngSuR;Df5$82(Zv0veH`MV=8L$)XyK3V|M**@lj8h7ztO*2ESKz zi)ri%=7k_pS->c-V>9T(_ zdYxZO-yTXLrl_!;3D>^G>4HO~S;=kcd<7Q6C(PfZuIltwV7{C*84uLsvFo+N5o_#o zTl&IH!gt%-SSdX)ey4s|I8FUH)qcn=EjbKzLh7g$UDs&X#LUrdW7iv1QI5`=m2|lAQVPhJxPG7Tg( z_!zf{CT+l@jz#C|e5ni-2%W;j<=TtsqVRe|f;OOajP>{jb&NBRUN0K_jEdo*OWgk9 zZ|JDd<&b(r{5InGg)z?i5V2k>J~g<3OEZ8aD3NKrzKDZ{VU(ZXki%WGAYbH=`!&y- zCr9kbo(I28vedf2=3F-shS0Zm20VG9cgppxm)rKvEAHD1(WTiHHs;o{EIirzk5hHJl_ZPEG5rrX(=f4`Vp;X$#N zpOD?c%%N)9?L3Q{2?6!ESYx=yt-kN}6T0WqK4&Z8;h;l3({r0Pf4+C@W6#HD57T%4 zQA51=3q>*AjOVs!+X8Ap>1U|#|4@0IXtM0`vpB-f>_D2{ zw$29!17Z?vSG9VVd&E@vhpjMGHs5{Hv5!$*VEP;LcK<+-T>mzEXOP%t`e*d`QFiW46rTC4{KU-A=2QP2J$EQ0zhGOp4IrP7GK}rz75RWjC{r54&i;e7 z4lU0%=h#qX!?o=)NKoc~pUnXi*>&xWT_JNp}(EJyV_ zU`b8LiW6QqRmhy zib$N!?|yHD@;w~!@ozsZ^|9s4tgz>P6(f0Kk-=9n;+_8=FzoyK$Y1!Wp};s`gSrTt z@6qeEBN1!Hb6eU%1M$1X6^8l!9kvX>%WM^x!12G-p}4q2lKZzyIGQ(Ig!<0SY}8+L zGAfwGs|V13(11e#439eT4p|5BsOaZVyc}o$HTBqY+gxe~ikpCRZasY);(iuYm_M6x z4yL(14*CAPzI+!J~pUE1am}jhv^dQ5%EbAc>)3a|~AM%rIKMEsRRy1yngU_Sp zqM$ddE_r2AduQJCA=n|^dDJx7mUb{Gz~^IJAYg0$>)2j%Z>{5UpC_ zbQByu9ZDEv3)dkXPYrE`oM+yj#t!WnemzS~`tVusKHyF zfi@K4Qwuv(z@@~reu7%$qyCTZfiNWJ2sY^x{-Xxm_tp)dO)LV09=6q3W~05X#gkWS z4Rs!R*i0TUEQmh3is5WZdaYf)S9>!R7nx48E-n_m)vF>v8ubgndM076Rbo}!@G$b z_-ZEN3~mT}6}4ppHA*AxOu-piOSNDX$@QDaW_nyWZNwW}a)Bs;CRuynCT?{<5XH0c9x_1{u3j%ofW9od2^XS1{~z+lO&ZbnNGW^zoDYjV zH86ZIc^}IAcfvoL)`A4uR{(ai@6c|;4t!D9IScp&3D+RNAKJlBT>MWmNant;KlNR> zoYB9oxK}8sPL3A7SIIw}XuPJS&7Wc6$2+3C+3Qq+<(sx-omoQ)@4)G>br!(TwPO*k zS~p@gJ4h&g#Swi`zIkWtD}nog9gu#df3^3WC|+Vz&z*_arPdiD_H&yY>SH2LFswYv z;IOl>b(<9!^(Keg)D|b;C~fGvs3DD|BC`Vd8FkbwtU;3>lp@kgm*MZW$4T+zMNRO) zC_O#Y34DECmysn~OD!XBfvbh5@6}bG)!q*pKf`9Cg}HC)n*34fRuU56<)l4>P)i8s zjsv3r!)$&aAO@<`=h>BcZ4QmgI*}V~ap_=wJndDK?+J#-CI2t7)n=-N!tp&@xO?)K z*>8c#n`1pS)MFid{JU)z?&8z)HqnbZ;ZyDlh<2@8f+(N~M1Y*3>8hvF-G+11>1WA2y_3a;p65Ew$lv z5}vU2h~KECmV0b_2C2`f!DU!-GBx;(H(E!c&$dNlLuS7H&i;D&adBfP@pFIMTepc7 z@_!(OH&Z?%*m9rL`18{XADN7i1?mF3#EYGgpE>^=3X#6iLmLItoZYF1tx3~kO$E<#sL%ri^i1D0=mf> zvr=Ugf_mnI<<^uO9~WJ>n>s!&nD3YFm$B)~ozHVx6qtY@$qAHH%Y%IgJ_GIa$8NHJ zUhkAzuxpEuIwB`Ko6fC7R#3+`f2kGBYmNaDi&xY+t%tK0)Rmvk%m=2L&}Vs$vc>?r zHMB6nmzw2n*s&Y4^Iz}lKKcr5xcm5VvDsuj8iW_EI=-uu`m*lkTIegXccD+`ueVo~ zZh(MvvWBoEiHEa;R;LIxmcs;h_JGVw#MFsdpqv-7)jtJ$-79LmTYrDDxW4V~wL8&H zaW}TTpD?^~E0Gu(8K+aEx6Ms!+Xdg;aB~k2+w2nsce-hJ zq9;Dzd?jkbAtBvlcOhMK{0yZ*IHMV5SXf$nYqD`;b*!$W=w8&&;}Uxwy(;=lVF4I= zAZB%t_E2bWhi+S4_ulnSt3|X-sz%e&*eU`%$q!Wr59enI4=3}3-_M|ZgSSa12HZd( zP3@l$KDXYpI+oC+;YhFsDaGe783-;mo0UxhO{TO>@%c0PHR z!R5a})Uo>q%ETM;v|VL-OC3^tmzktCqHnoH?2 z20+I2w&b(YeI&m&L?=f$Fck^Ky29+66N1Ix&%V{_aXV?$wN0nNS+RsI+NCX|KgTa7 z+rx1p;5>RlmxLa|B&5?dWnt2=D0(fcUie~;m;)Fiwy^hb>*_~T&*H@Qcgvz9E26&z ze(TqhfT4qggPpp42tA2NI{0xqE_aN8m<1Mts zBTy1}>Op(_NxS2`*LJsTs+_9z^aIm&_~!PJ8r5yNA`4MW<7}?j>10g|dSV~^!tvM< ztXt`u5W3N?{Bu`p*S+y7eN+ppKHSf(lp5C3`X+^uzNM?_eGz-Ac)pC#+|>>mR~Cs?+!!?n%5m-(e@(2c#|F7+qH@Fi$QeSsE5P$Bz>fDCHw61F-!O3jlq zKv>k|MHOBn;9=WnuuO9C85q$l7eWqMxJA*SYe3yTCa2m4eeztZdn7;{B-=iU*cS48&epj{-g&lyyX!SQ@;-XxF?1mAYfd$6b^qw2hTaVgS0?l~URrW-{Rvh_ ze9fog!=H2RPMqNtF(yJcG&iD^CWatp^_8L_NqJ;h@6AD|)R&BC%u z;rk?^?m)IICPmc1!45VcD_X#yRtEs{>I69fPKgk9E~zj2-p^nr!k?#@pq~>$%@x-} z)HL7>MU~VU3SR`vgy`pb=)l;6aI^?-NV4RHnhj8}@cDkP$d-lswReUl^cvM~a(13> zn#PHQqpH;K@|YKfw_^>hv#M%7UXFNo6SHzu{m$j{`FAe!clQqble|{WU>~IqDfvOi zvOptA25ba11cOT+KSp+T<21>^phjznUyGmMkYMOwi|9Sj!uqNIzRc17{YYU|@DTr= z%WvQG4C7?BmMoHQ zFK>DI>Kk=`R=!9rF0xv)%h_w?z8gkqWbd6=XKyV^-^;Jf>Bg{yokgd%MfRGnF*)K{mWPROjY(l~qP=tRIpr3*7oE?Y1SbErYu05v&DKK+^9_^tGUF3m}_wy%W z8_HRe(cg-0t;MAxWa{PsnEzg;z%bG7h$`0|;-?r27HNEw8Ns?L9%g>6S)J2~?@HFpo*#MULw+Wc$_V}Q;N1Ueh^c}PnaETc{}4N=(3SpSQ=_Y7-lUE4)*S`ZbZ z0wN&9hDeP_he)P61pxu+O~_QH(!{8UM2X21gwW#@5tR}V0g)2vf|v-QEJa1SfRZNC zWekxpB*pW(&bPk3_FArW=6Ck>?R~EEgDW^3jEwS*_kHgBxu5$n7JOm6ao>!J;CyCu z&LX?U+u8V7yfC2jo6J@yNZ`0(kdlO6JbEzI?nuEH?FFY(19;6CBQ-R%}KlN z{`4O|sHKt;+=l^52u8GpvWYbxKulsDy!tDu=-+^lr4Rrihi%)@hZe<@KB?`;cY$Eh z$C^p5xPFuAP1zS}_-p~k)wSQcK*9CW`>XiqC>;Ld!4MnEXw(F4$_H(+e4vjqVJdNO zNl8ag0Fm_h+AY{JDLFwc7Gg@K$^GwvN}23Y&-WL4PABjGa2cMFgzb~vAqt!WciCgp z6UtMm64{X6az#q9ykBF-DS81YBC|Qm36O$VC0PxpEJaWNqYU6*v!s1UP zt)}Hz{e)$wyuEe5Ts=mRFQADPodxtZ5ocJ$Tbl>pL8$@VQRnnNK!iC}C-a;Wwju}b z5*N5*EvUgBj~nY1TDydI{+f+--H?=`~~Z38}XW;4q0(zcQHNFaAM#(E`P zD#wBj_;%H(NANRSoPVd+$g*j1{UcUze>#s&Ef&zxq~%B=Z#ay$j?H^q`USlXq3?$Y zK)6`;WdcN$asDaiWY6FNmY;|#(lg$c{caNbWP1m!H1phRV`Z9F>sk5Gw~58}k-1i= zq>I1g1$boWne4KpDeTizT`0KKRXnqG^O~&(rZzj^QTzJb3gUb|x}~2WdUwU%&zBp$ z{(K^E)b&nb1#xIT%(dwEP<@InXCsBsIV@n)SKy8p!Ll<4MV6#pP*5vvH6R{<73R#7 zNLbef*$&XAQy$dQ>bXdGMqlPj@|D~L#sGI%isI!ABE20i|H*`frXl-qfs}Yv^o*|A z)dHA4J;uka5o3dmF$%zPl2h59$lQta2+tuZ0Jx>r0VH{q7hq@0wMi!h;e`2&8Qa~kL}>9LFzjZjceLWC$GC=q=fSWxytV{$6U zv-i?d0w!?o^p6q!&Bx9f>}fgnXns_&*FV&F@^Rs(-lKw@>6faj>%aDVhvJe<%D5VX z!bP(?rBPofYzFQGXK}?82a$!qRGlLM=+EIgx&tjYlBpWDH#jsJiiyiJg-egvxM!JIT2H0CU}oD=$glev2u47}ed zDBM?0*FRm^{G$HB&DW&fU`Egt$BK;ffn@c9EPyk+0f$~HE<);oIJ6B>0?J!{s>>uZmfM4Zm7J!1UEX!)JpUDuZ?1e7>j-`x2=b(;C2hM{|&6D>~jK5^T5 zz)yU3rU-L4)UPT7wNP8a?8+hTo)qDO(0q_$rFzkR$D zKX@*SQ{1{Hf*ffjbVIrda$js5+A-AF(7dz4;P#H%%IAe4zV?HI<>>{%!fPRrZ?G_C z(Ai z0D){5ltDMH#E#beR$1CwD|DEQtO@$P%?P=M>m2iSSxcvn_CQ>(R9jfU4Q?YFiM6;v z^n~1XXwj`nqeaiF6b%^ClwTARm`pWil@(!YLq{VD$ z+V961MKenwWi6ZY= zGTm7K9FUGpHoKP`6L_IK72+u#((lST7elA<7^_!=ueCfgN}hHcOqz0!}dul_}10@zw&Q za2HeEjsR=1Ypqo?TW`8W0Bc-p1yI9HI?Jc00+TYZtS&dq;%BB%xXE;dMqMbdjl8EG z`T9WY7c1yb8`=68D!MAw^^?9H@Io(Zl!q$`vO9CiL&(Z~rC6)zGLoaIwPs}xfoX{y zN~Rp>lD?tKP{jl2Siv<5B$LaOnSEV1yXb+if+>Sy4YGw;ee(j6#m#$j_M41hL!?(7 z^{Gow*|eb|sAbbqt$7$|Ze+w22kdDq(0*NLP(2s=wY^rDoT;R=ug%@V%y}T6ek?H2 z`?m8^b4ieVLWZ2@y$6qZ<^%F=H=tgg@+P4>(ymKpO(Nj^9TCg(?h{*yPKQtwuwD$(;rcfx9w!SU(Q6o#K$-&bdd$tE<_%s* zmv$oWACe6F=2d1sK<-0@R|q^89x~*BevOW&tf6r4GEKm0c&bc`-T`a^?WWnYu&lA>L4b_-s0wJwHSA9u?VZK=joU7JVejLH2dPQ z46kS1Ee#_B>r>i3+;%!PpMst6Do7ZA5%JR0Pp>v?{S}6rUd!mFTOK)w_gda6K5;u^ zGarAn*!H?d=)g748WQGs4 z&^G}3;IFJ8X-~H}obQhlPWP04d8*|)fISc?+Ky0x8^A0!TmXWmVDxIz(agn-8599N zRk|I%kn>Qyx26KZv^gh^?CxsBSuiH{fdK>|b{m=&_fmn%g@l#DuMRwCaASSH7kBUq-)Lz7QNxvCY*f zmsQg7mJ8gib2d+Jt;>yHcULq!$YK2{AGNr)&j^TiUEA#M9598jSqi{Ly+jLvfs#!X z5pWsFQW>NkG7{z^K2RENh}NolU-dNg9??qBKC@SJRD1w&p_Djct*v{o+W|w-v{$-Z zjFa3pkZMd77bD$M&89-m$}dLqbuENsdNryg7Pi_4OkICts1sK==Pm)a-c#CRtq#d1 z)u0hA&J0>)BJD$0p;~8*cw@0&Sn>3#&L-TDR_n-?u4-IzH?gDbf|n%_0TTw3c{3w_ z6yiY<3Awm{*xn)#p?z@mkEGqKs%sWFv{WwbDe(JU7fpE+{jNWT+=H$nZkO&^&5f6t zh4IfQV&;@f@{P0ZTJgz6SM#wetXAa3*vA%NPpTzAUx0eTwOG$|`B_ulNpsR+*aYf5 zb8EB7=2O}ZhSIKi=;9|?6sDgD!D-v$rufCjk7sY!xmDNv zc-M=vmAqoDq;{uT<@Gu@tQkldyq)LO!ih6wRpijx&>JXCj*VU-6JiNhs|BqB=(hIh zDcDLVM$$z;cZ$x2O63qoRLpRDEo%wZ4|s-|@#>l;j8|ild&cQ&NI&JONU}+~@X2sP zQaCT%U~+C>811^$lGr0%RmDXQviY7@V1>hyCy}#5X8c+4hIC<67g=o*UB$V=G$BrM z_Djmdx-f-*p%@NukVFUxT_(;lBo$;(i>)8@j0N2!rhODN9cY^==*UC-JmDQe)eE<^ zz6>bOn2Ai6bk4{@=9?*9-q5Nd0SgD@P;z0@A zG^vPau{Rd1y7kUe^G)oBBsTv{wnu#Y#;JGTWCDv?*EMrP+tzuXs-r%R#uVAvVm!tQ z{jz@DZM?fWz-Vb=&Khe!$AQ-4#qMRUOuyTZFk~is)a8}!ZpJmdagnxDp=o)@9WP>1 zq@gEmt_Id^XI0aZD5nU+w#}@SBo7e@Nfus3B1K{37E7(^o&utB3%**TLbRQz#TzMu zSVA8dJ%i)Trd)DLe(>(Q12Hr+%YNn6CfzY$4D=gLZ0EE&mwq=737rH~1`A9R0INM8 ztu>OKBT6$q7g41~(l(8a{f&Wq{2H-0@IkiVV-hYsO=AgWqW1$chMeubaNCoD@jFrR z)$a*ys)h82!yICkXOGz8euxITqPM1amY{F!sO!{y_m0(Swcu@^j!TMhCk<1iUG$%1 zC4C$!`>wzOMm>;(SsJD4tyNe#Dr;$&XIbTHpH=3p{bJA1$cwD-W~I>4>utR^3bZ|2 z1%}><51gv+)uiF{Jht!pxXE@UZ~R!k&f|s+4D+tyga-wlb=5~-^ht7bNR5v#x%2Fe zvbSsC@4h*=mr8lT!cn;SZ1fuG8bA<7R{>es^G!&v^Bg08yQCOYAa9-%*^*YMY@s~I zBc!!f^DydbE4a~7q)@~RMmM2X8sn(+jZ78doL>zxxS}jFAHlTeD#13z;RQ_)Rj~a2 zP(~X)Z?bOS%-aJ|mjlD}KU^zoj8eY&2pi*&;L%&K@w#g==}ni37@pHrN_*B@WRrtE zz2W|dm2S$`HI6Fw1d)T>{XmsEt+49rtiMP??j`9S;QT!{-xWIKl*tIWbdy>h(m<}d z7iM|+V|r=uVoeS+zhDxS7!x#e^9m<@FMo*e#fL2Pr#psS42oP+yWsix`7*fC=>-`L z)5HqNLVuW=Xo6l3(4$&7k1&GCQ)1tO{>!3Dy?_u&ncT0_|1C zf8ikK4txdl>+g)usOgt=(zv&1@eVe?2~~4NQuT`>10W+b3jkjNo}zem{0B%zvhiNp ze_*(MlG``I{!f+y1?eq{)RPPr(0_vT=zqF8{Jmb6=crMd^e5I|a8-Lai^{)JpmfwX znHQa}=|6zudl7KL-{JB_-cx(LDne=TB|oCCV;cAl4tE4`^}C7o?fkk_y~d>^>n?8A zbL>;+XSLGJy?Mhr`$qkX2Fp%`HB@H-n}a#W#fOvx4Db$UG|M8z^RC!;>db0&mBWBp0eLFYf8uR8v} zfpz#1EXDoPsj&_|$o~%p<{IUH%OIQTC9fm1S0{8-G?rj0#SiW|KHRFfBy+2S?j=Lrvev&Y8&eTz6o?_Tc_1?(K2M!Gqult$_GYYc%qfh@aGyJ+`ylbN@vs{*6LyfJ$ z$8k2CXC-8^23e?ij11DoZug}P{Z=KCjb&i19tD`~!IYxWG>TMC(Ir?P{zSg;3I2`gq z=~TMwDZoEu{m->no}N!ieUa#2`b|XRCVpA^3J$EkS^a8#1s~Y7?rd1$P{+lyYiYdB zwQoanw+zhN9gpi~AAIxWm91Bw!5v+F)3#5aiNF2<)DkyxW)we6XXjjhQhhu-tM>WM zk>{r7ZEiP?DUNEJY--c4w|Bi@r&$tSeciV%ujC-flU{c+W|PXr zOACnk-rd$3A?S6DevDA5G94(MzRAE-d|C`Cl8cG~PkFW(Elc_hsD5YH5Qq7yA$SEQ zW)lCMdhp}5vtJ!(wnQfYd5I!vA2ilXNgL633_1cU(@47ahzHmWvcQFG?{U7s>q&nk zV@=4ARe-M4(lP42q>G8je`Af5|Z5P*@LLH_79neETS*+@;f|hOcHM7?Z0m*$6nRl z(sy;-{=UwU{PUAuMcOVYCsgJ>+wTdnanyRj&pE8QaZ=09rgkrWxqW`|i{jqavNKR| zht6}ekq77!gUF3K(RHJwfL#7ms3Cbt8DJya=E38C{hRzV9sRF599S6;|s8nx8hXOY^B zANCSPA{_XDFYwKuYR%o%hrO6LNc#Ed^}T*Pber=^q7mNt>WEnnSyk*A3l^nTj4BBS z%{Bw!wi$g5b4!>i{wnrz;CC^sHWP}kql5(USBG1S(Tr9)&`0Idu)rtG#p6RW} zdbK@|6kB+Jeq&Yz^Ztr1t}b(Jbs}xhd23@;2@>lADG!@mj&fu5NBXf4dr}BNSmxmN zq z3u?z#(Ig5C@smbi>hNkW`X4u3HaRFm0*Tpw{QItd-t=EO0G*TqJ;SFq z^p&bsm7dC}9TTnlZ(-Y*p1mVU9-gRtRSYE)@AhxpmQ`qTUQ zGdTHDta>35>W9yyA%gW_X>x*K0JGi#eoha?OBX|824YB1*3 zw6sHbDEH7^JC(}?HDwro!CdXaSA5>pY-!CwZ8vvGyyk29_MsP{h0233R=pc}y*^UO z=1$U$iHM!=!a1NK_f_-Xi6j2q1p*=Xk4szsRooH0^v8v*_^70fDwB-Ka-uTHg$Q=0$-L*S3`Dox;{y>D?2X&{SAZM-jvOjAEzof5JF5AosG|~ z-`=jKLu&EL_Zr2u%vg)s@M^f=G9y2j(dyAv%~C@G*_IS)H713k)TqTv_Fu8UHEWhX zDLS0Y)=-3RCi7qd3k$k>c{In+ARvgYBMy(&WR_LE`dj{MEu=rySiDq{sdDctBzHmDYxJHFYa+rn) zn#*bL(ar<2H#g2rykt4QkO)8vuD3dJ0~K*NEEJe|nxs&DQ49@X5tpYJCh@O0I~^Cccv=SzGer;eBO zyHEDE4Ycqpj(!QT&mlSKqP>hu0?r>*N1v)%)!o|lpt$&0i5uHt&3LJXlFQeU07*Ji zlQ=9am)w}gslOKkJVTZKB-YAuL1slZ#D|#Qb2kCWshdDwxwQe6EL~015P|qm_Z7O$ z*DH}MFZS-nkd4M0t{_odfW0*~^%(pH)#j9lf9V$o@pWnPAw-%Gg$T;NQ?bu-tb~t1 z3I`;6PksSHaqRqWcP=S(NX}f&QFO&8;mXQ<3Ci)5-Q2UxgtAjiXedk`6g!g83;A=13 z+@`C|?vRg3YORLP#py)qYN=*?ELz2E_G<28AIXDOBmy9XhrHs&2SkV81DgnZ6_t9v zGmR-PDX5lT+ODA?iI*x)plfWh%E-N{eVqwnHwv6CEUbf%!PGXw8sc{Meyr^=E^0L~ zjLlhIW6`J^4g5qmfGoq#IrfE1@7v$uS5gA$h(~}S;==Dlyg9=hsMG{CtRoWPr0Y@B zteH+EjFQ^m)rQlZ!9(ejxIsDuc<(A4Z!C>VdNT?yfeg5_Hxu7m ztnr&z1d24#7x$x$w_dvxQS+5UiM|GL%eqf1W{2%-eO_dl+P>b$qW8wfcVDyX^Ec-0 zUw>nC(}Ou6+Py=2va-L-CRZcB$kA63D0AH>n&Zry<90Raxbw=SPwz4J|BJ!@^Q8S?+wcGHz5wy#Mu`=pgigp;&|!u# zJ;tLXoJGO}^k!TlYn}DRDaslWMZG8e}GI+B5?1M@VEB=aGI?_P*8_de)2JrDsm!4BP`J`#QYZNIwZWD{D!p& z>j=#q=wWUP9od6aF%X?uK0RR`zmym+;>(Y)`1+n5UISP&4Qd$&X>Zrigc-D&i1H~@ z>zxpbiai#HPX6>WuJF6V@zB(FYu>$ies720vtbP1w1}HE@$vdE>4$3`A$G6>-xBYu zL#jGz7Y#`}9fLo%93MDRe}lZZ>&lliCu4_-S;VCm>3}l4YAxYVhq!gND&W1hWtC5Km(X9nT~Y>*uc`TI|D+B zu)n@!($I%_S14RiP3`e(-|(Wt+pVNi*Y|~Q*@dGeHf0}1B+jYNiTNTo^?6E(lVZiW zj8l4}zI!rs44d8PRmG03NltDBp828ozn*Y8XrUP?+^gu~NB`~bnV3KGyV4kLHAx{7 z%zkXk+_;OE2@f18u$lmsdObS$Lz4LnSySu>vs$9nHu{`v6CAFD{h3)&TO{uWJkuT4 zZauFw-uD5&teUlcLPNg44C}Tck5K#yjuKw!(+}(|xLB^nzBAU&NVFV?9ZMatJJj>3 zQS(7?rsd&%G5ZQ$1+B7OWmB<3QcyH_lVv_JCs`ZvS#mD+{D;x`Q~o78zivf`#e6K% zJnf}Zw*N?YVTQ{6JLkd%zH7+t|7V5pzlh8J_W%FFGiKnw=y(3TE^$T|ctvDM<>tN{ z(+Hd;ztV;;F`xdYp!eU!tbhAIR0nGVpvIykg_P-s!~@@Cd^)%XBhkxnAI2NEg6732 z0aaRx8*Hwp{Hfg@XTp?EdaN%3+!i)CtOG{03&tCX_E`DdR0-|s^<5d*Q; z_3coE^f{i*k^FK#Nwi%E3X5DszfcBAfOhGRMwa5${>)xS-L1_p;Ut=L8Wbf?sbq;{ z>C(G>)-OSpp<43$-yYAO{nUNIlt-TUz;#z6Q-l1YFJewHb;K8-6#4LnSV))f?@q5C#3&yu=pRvw|}4I`N!XJ24bK|(&PvM-B4M~LrH=#SCo25fYMFB z2T>*0aB1kpN8lA$HToy_9+~lx_;oLa z49dbD1|UZM{bHlj4cXRPpF(|Ap}se-+;@;4%_*H@=emErSF{-myC#R2P~&x%U&-)4 zRqu&0e8%g3`u?cLu2wUB-RtC69;2C6H@D@kcih?2;?XQP`>3FRWBjQ8f+e%x9qRjS zsFIZ}HbQcWgXv4f>KA#8s~jcru5pkdQ4pJC@)-%z%^_rk-s)LuSOg^42kQ(^UeMSA zXT~==@Sh$>t$F_z*zAE+V>McXSmfLl>9}E0^h=%dy5IvYl9iJ9$oJ@0jm^Mulz<8~ zZD3yEV^W58KFOQxca=Le?}+vSQv0B%2M+g!Ys$#!6Hb+Hsjs^xqoM6m@rt|^x#S%C zP39-SHKKSsuZX;W46KrM1(Y(=;x(4n!pcpUgdyeT70LXCgh&Qeih|4%#0Ma+{V*m) ztP~c>pH-Pq9#MHia$7zSPu4~PTU2i}?0pYVl2)HdnO#k1G3x~CDjhlm*xo1Y=qh>( zT8`3$V^|x~Qx@^;&UpM9rp^Sbs=NZOYk|i(Rg7oqq5f+7Ax`qlM|do8{^D-~Ct;fk zrMS4!nUDE=-OhC!n+40>g{aM6wiQ{fFD$U=&9HY#O1@F#o1SV}&AnNfqmzDBYh}?c zr?V;7Z)ALv!SEhljKtbFdZF}ObFfRx5_2xu=V;3P`f#Z6!`O412aaM?zJRluF z@?bpQ;7R%TC4(#;B|cZKC+|&lI3d7@hmpw5TN6rLKq=vu;$xw`rFWcC z&1@nsZcSucvY5SIAMwd#6s1WGyM)hKfylN~R#UjQ$*bUj7EdTtYz=uOlh%v$h=f+A z6(OM^x9FbO8ovUG@b1y8p()g*&8I5(bdyw#9jpZW%g%>-r;Ybrjyx8n=q7eUv_YJ9 z0jT=%ONbZ&p&5_t%xvO-^JInV@+enzNB>Y~D**M{AQ!H3L z-)Hhl*)a@<@|`qW{UCJF|8~mJ(2ak*D$-*t@6hc9FQS`gRB>`%0ZC7Zfjy`!_BDKJ zPdUBI@j;tw`e@3TFBRv~yA7NB?cLArAsnQZY%H*^3eEYYC*@ACME@Sk)WCWPg?) z{Iyqwl)?TwvyrI5yEi?)b_hTQm79QH$y^KMgu{iTWs(@CISAkDT4v+vE6Muc9hhzA z45Il#2~t%ehfiyHkK#F{77`a!zKTry+XQ>Q!}Lb z>WTB3~spa2Fg< zPT65jPh6|qkJ+Cov1Ba^d0}+U<@)K68V@bIhl%}ZDwgC$Vq#y$$~R7CPSqtg?tymE zpG#ESTp}FN#l2pF%o!~$@p@U|5rhD%@q^mXSJ9BOKE@I8FC@yk!OrntIsvMvGRPAU zX{}ctm^CNwBJE!EFZ*DIRtW5x&tffmAIc~UQSDF9BT`%Bid(@YO*NF~3{8xHRWSw~ zDm4QJpnJ8NzfUiqxruFy%CtUdIS6K)x^Tbwanz8JF%PKriXhd1)2yLbTay_8>n&!+ zH2Uxeo4gO?dj~wf$RlhR*Vt0$W1JJ@^rZf*Q>2!?-0L!sF7PO}x1K+A{Ai#FHCt&^ z_0xuw3~f!9HoFIdg<8AXu-(^F$mJEJ?hxC_%F)r5IV;<@)nHIWs>3377I6JgsHrIOuG;RIFC`OO<|u=lgW%E)q`kPR+7gi$Nee-VmU6_) zp!qS{jMxoU@B+=C%|k3@WA&}oCNE_aC72M@L-&k#za=U=OIse*!j0N|QJJ!96=YMN z7dG^fo?iy!HoQ1<^S(RTn}d&y^QY|W4UEs+io3MwVY#q~T3S;O;91}{ZTGHDMd!wY z$Im?&o`o8zS{omFFl-`3*IA3oICu$r`3m zR4XbWcMU=Tb5kQ61w!u_h0vQERcr*0wu<~hbs?6y?p^SODoz-vS5w3~7I^!QGi9=D zD{JZ-`?kUUpVD{I!w7p@huDg)mSe44Iq(O+SRL;i?s8QC3`PRjYaqvz3 zr9#_up3@V){tC8#U*xN$Hb}xvYO`u?&Akb-G7L|;Aii-Mb-jySz`AG(tg+G=^OcvZDP%QZE)*@8Q|OZ(vK4cS`DcZ|vPj0&%1 z6JE(RIb|2fY3^z()2`0<%*ve7|4vR@jeT!WpT8A!*nm};U@Xij+x}?d5tsj)ZT_?S z|BcROQhuc^?m>U=hp@hc+X=MU=PB$TZ2S*0`@ik*UxH}jC>|$1cS9dGh=2Rjy>8>$ zp0cZ|k*WP9C6f)z`iF1FH8w-SxclDiCc+9nMuC{@-rZ=$d$0OJn_v=7aDUWO7I^Vf zpc@arM5;|ZiC<5Q<-QtVqmw|(r3=@QF@ZcIMrwds8o)sq`+)69PGA5`Nx=fs;CM0? zN#{Pr+x9d@2v8N1cl5|w$t}$F$#|&ok}$4taH>K6b$%1_L@L)VQl7F@?3b>TWC4C$ z6>d$HCi2nCNM48sgyAX2F}H}Za8aDeE2|c%0!)ZE$-=KVY4u*A#nL7#T0d^+Xo&Co z8(zLUYl5Qhhnn@L!vUMYi%cf^@s(Q~4+xZJTEiiXumMRA=e-Z&&BkgDP)>4|jE^V) z%fBhQMyS-VXUpR*tYZYc+7*^f(hqE`=+TS3?BE}UTQ#w6(h?tEjbIw>1dI(xU!-qX z5aWI1T+b(?v&kiL<^iEO-fab$^(yx1*_Z}l+U|_&RYI?5U1{=P6B|Ex=sz3@ul_ae z!Tksf$t((!zOI(4&xw{%x~@qM@3d+}H##U%y`YVLu+Rn^ET2e(y6Y45@1&gNx zhWaVcp9w77?%-VyVs|2kKvA#Mh}?vK%L3eP!gvEt*e=8g+sY)Fk~|@8`kTy*qwRFA z^YCfX8&p@rf4V3B7<>MoGlBX?6#o6+OFz%Hus-_(L`WCuWl2QSbW|Fgj7-xx3d z81(*CPz79&#kYVa3dk7$>gzjs8!nJRLlEKZb}23TubquDzNdCx6;N=wvTv~RkSxE5 zN(rU_99`Qk-T-(k+85y91G$!5v|ca%P4c*!LZ!>kFgKCkv8vUnZD3tOK%1g(aK}57skl7%y#Ka%Wc! zV_?q<;@e*zM(m{Ps{}sm7e;+3c2&&qa81h5p+6(USg#$rrnrEq$nuTduL7A=) zTu{t;lBOiZ+FS0NXMM=_)i0uIoOtn}MG(z@ZS|yi033#%J zjSf&;S)&6NwK9vAuog3W^3CNc?mXjn<~C$Z_!*H65;>EbG?s$q9J9k{;c_^)2-HuU zlH^qrR*FM2+2~5=X4;@v+aJVCE`_?SD-zUML^vyiNoD%Qt5?*Vg>8AK=^)K2FVJ^6 zP2M^(8AVop16p;l)=1kqN{#Y7hAd*xBaHpttw`Cn8@v5(Z3(2%LLc(YzO*87)UT}# zGi2JW``)g)Y$snjp;va?O}%Ec+wVa5>ICLpWC;}IhgjVwe&V!{4Z9n|N|D+2_IBkv z@rgV&*7A^>R@l{C!cxD93k`cgT{M<(L8Omezg#>}IYoW_xK}e#Ute%#P0prMPTO)V z%Pr5kmHGD+`*#fP>MNu2v1W?goI~9%|Wx+rqPDwEnc;)$|N4VAK>H+!g1GBmoXl z%Ni#gKv$}>#EJyr8c7~75EBRkU@!K2D;{+wOk_&rj~$c%%dM~wNN^OXD`}i_Kk{nhafVG;-6rRzmzEgt7Y3d|1 z3HU}X0K;n52GUoo<&-emAdsihS2Ho>ca~=C*{jOd8j?b?fj7yc63K!De9u^DfZv`t zjV18DK(%pP(3U#N1KArCD8Q^lGFuvs24LRU{1K#;Kq-!?F47a9m&Mz>ChH#1Piu6m2Cd*$E07ZffC*%ftVq->uPRhm_Cd=<8j7h zcg^)A>b858*+n;VD{>Aij{5f(C6$4=*o6MbIffO8f7>GnYDTGrav&GXTdQ{FrtdTI zvNy;+k%D(vExnq`cHG`NU~LXj+ZYLGMKPgxf~lC*66LEwg}N7qTXHw|G-}Jiv#7eFh2}dfyr*V57uo$D^a+` zcnwMrMqX^v-G~xkR6?W3The*7>C3P~^QEYnC@x)@7{RwqaH@we{Gt|otYu_fLbdKi z;0;#0k!b-dHrUSl9gOUKICXqCG3iZ_2e;y4+n!X5CQGM_LL+S3NB2?n%^{v8Ek5@{ zL@KT&`*XZ?OpfWe+y*J-`N93?;trG1JAm6xlZ{ar_0jDWD7^<|N~jQfy8H>(hXr!3 zE%q7S{RNgLMc}?{<*X-f0Bzqmb+YkfBS%0NZUr;Lxd{+@$cmitBv&Y)h{qWo!OIdK zc5+z>tl#v*goGzh07GOFY>5+V;}pebpv(l5j;H4^Ls9Ll4cG{fJ9EBrtjk($%GwC> ziX|D{M}mW1K~>Ml`jTX0{Ge7FzJ?(N6W`Ch%=KW%U1csOStGA_=pi?oKC%ue3=~di zlHcSiBLJj>9(F17_%*@lVk|V90A_$gr^Q+#tKd7%ZF^C6NHHI`F?4~W`kMBT@rUI1 zE(dwv@{PvZSJmts4?K6O)xFHZz1T~gjd=fhuGBxoY_>oDD)9v|(T5W3^>S`=`yTJc z{%XVC$`Yp>JJY;XXNXvvpNxxJb=)ChV~{XS7v;3ab+pJ&ZH#eh}y|r=y@Jd|9z#L;#GL`6eS;_jVjz>pZiPt|(p-!Nm=w^P1A*obK9e6wWr%%=$`&gA4N_T;?f@GPoTFv3m}`H z$ek<&9D#voV%V2a!a(qJE|B}tkDQ-%CU91=!kpI<87*k_QOUhVeJ*|J1YHRbA-X`) z0NT+&q4K(i5yE|9Pb+f?L`{?KHA|50AhHAc!^L5N1m3Va>?~9}cy1tnjg6|e-TNcC z2Y=^%wZYcil-1>xc3k~DF=xLgOd;-hRd#oZj?J55KNUTvZ5g4DNt+)@Zjnxq40JXP z8M(A{zc#dZZ<%J8X<(+3eJtXo?}zJW&W8ygbGsKCQVN`MmfNRH*c1@L#FS9!(np{a zkcRBC&V#oL1>kB95zYAc8E0sza0v)S+u0f`CCsfb>q>R!I%!+L7TB|ZF+!Yc_g!d4 z{}i@pkSZ8AQ8yT~eGDyto~0Zj*>C26!_%G`_ct^1^!1;IKr>h)kv;hh4st;+1xs7C zvsfXJhXyP`8of4XS{9CI$8QpQi9AC-BOUAskuga}a?@Hf3?(vr_YP6`1+=r#eQlF!{6j&Nf>cfV;z9Xyuk1PB+tpuB1l$)SWaysj zT6`B#%CIJ8Y0apW&|d8J&~=NnKtC!{4ZWe29IqRbv&#L<{FyK5F~!to-rjqeCWnqa zviRj3R^2?J_@IOQ%{C&@{l*EMhfgo^nH3&g#RtCP5Dy-GDG>zLl3eVGa_I;Ta*zYr z1j68ea7@C&h3&<(`Z~|l0x>S-CLkE%70`GTO9sO)!u)#Qq^KvsE_?UHt*cDsaI^vb5SEwYAw6wf!3!t z#i}(YJX0ngD($*NB%K-$dV6~7jqPqK)R&{T&%JNEG3saW(nuVj-ip7Orfc%D!o0ZV zQuUnzn>c%KZ+k!{(NgieG4?F&j%gWq%=FqZ@rGm`riFqM1Na$p86>kUAiri-jZI=H zX$MlGJZ%QQ1`X_zy7DC;Q(k)>wK9w&Z|t0yITTmNj%LL%H$ru71&G%DgAosWkpce8 z{y)YutzT)yN|%Xkk@`Gx7fuNm{!IqiseBcCmd`@87p5hm2$D0hkBb||HA~HqNN(p+ zX(zgBMV-hRiFSmXTO0$M(egE&i5w-dV_7SYj-DFIOpvOO^dNCCo*na1Obi(IhVkf|B@HdQ!#X2d^E5?7iO!w!D}cC>))?bbj0^entG+ zxJ$ibqrCCx&5Dnl0=iAkd9jhi7wesvo{tGC%{O+JZ#>W2Y~V<1Ig;nP-aGMCbL}3c zL8%4jb2=zF_e1st@+gR&K|Pl+L=Y+=EFK=&H~qj#Q5&Ru_r(08+Ojd3doz>2cY9MqUs2Mpz54SOOati~ z%YxENHy9>tV#HBo9@g@ONbr;A+NzfauGYwJ7_&>*eaN`Jly``CsDH=&(EnmpP>w|= z+2@ik%$h*5tArGP_WRBuiI>WACBn%G(J55*x#+pJfah+NRVfeg?u^N5P=C_-6_d%UP+mr3Uq~NeZi~{h5f!*jC*;I}>!h+ivFcuMSsJn&lY!$!!QFzzJ#M?bchnO=bbYuO%G-ok81$oavGd zR^?^JbSD1foS2219?$@>z)r_TZAMsFiO45pKoBIj651fWDw<3 zb8X#_)1(%Cy*gsh02L*%f-y^irJ8SMK)>Af zmfQ_+EiI5Sp={>sRDK7OV7$<4{N%|~>xt2-hFld*q#!)Hfczd^=~PgN6!Dj5Fp|g{ zrQHFWVXdn(Oij|y$-LU9LA+!<)sjQ4(Z};#ksBoAUaU_(XL2#~EjA*OXF&>Cp8BrA zehTo_R;MzDaKW@Is+5`aTz#V^WhM>=3!dnyEFZ(hBw1^~o$Re#6|8?AXya#_X6%e6 zhWa^B5=WK-e}}9NwN(7Rn(Dsk8pevr#K?lqDEX4NBgV@8V+rJCgTySs0vktb$ZWwR z{4~XLz9I%wxV(5zEuIRKOdmHQRMP~~0m0<}8)yxE!>2}XJuI$pT)0ul+Mq{L4iDU1 zWfuFfuOQs1@@)DuEEd00A9gY_ir*#_`kXjQjf2RYL%?QjKIwKqM2t{Tu#3eQsoSZn zoK)hhdM&$3?l|TZSjfC8OPA(F%?hA*2U^T0=Y&qZ?;m}QcS#U-UyqP>j(U~FHTM+1 zAsv9ys`$>zB)R_cEp^ctfZ>!PY0AXJ!klB*^;H+R)HdfO&xC(mbL?w^WmBtn4K3H{ z2-AG^+$#LG^TUBw4hX@+@K=rypKuQcY?j=&mN%tE!(QICFx*4dMOJ-$j@>~Ac0K_< zbqPC@kKVMB--1l`G}+0&?->4hac=ykuF=tv;o;8SFm#>Q^g-TKe@`SZHBb|JzL{4{ zv$(_dmgJE)gk+W|-n~^2=EqTPGEX}qm-_P9(VyI}>E!RK(=~qoX}U*b*ymT+(aUcN z+^qy}8b5Z{IJA$L@VfL^K&tJ|M?`axy-Sf6=C{1*yq&Y56}hz`X!pO;eoZVu0Pmgs zP5^K4`c43w-k`Amd1FRU;pOOq-$^0V3P}uZe1Qcz&fDQ*apEDDA8b3aj8*H=UjZDL ztKlP(GOU*fI0ZB>PAdao#$gkv_|?*FBro{VB&Y?VG*RTqs&7dFpc`#|b0x8;O#|B} z-di|ft=w(BlH`CS!rQ&m?T~2bBij+SO(^|z5=5jY_1%QjUZ7Plr3`8P{5@b&eGZj8 z8({A0-_}=FMhbaA+TW1w@2nUi-Gf}_&8#3SA?}xU9H@oy5JTidE-G9qAP zOr1a(j01=wBozu25TeY3kfKF~2xx^8B_y^CVGwdE0t$sx5h9aOnN$K1!ce7(jA2kh zk|Huh@+yQ^GW6Sc?pfa%@SLuD*04aXqGRI0U|5KE(k(bMT-aHt!;O4h4yn;r2PyU++b394K`U21J?S2D``63!tM__+f9NwT-ITepbwHD==g;#Q<9;hCX5pl?=NNNd%{N(SLo zV!JV)nT`_0&!ejb*eBSjWTgSJHfc35iwkH`?2_NKzz?lR- z0cC@i+5C7{4_k3i?W&?eK0@;p=`6@D?~%L-yb%;1+dP{{*6apWH#|w4yh5=>(Z$w@ zVgbA2AaQiMwViYq@NNYeDJj1z^;h}jTHMfsg;tCKV7i^H@`G_>ybj86!~zHOAd?N@ z5UKqu`X{V&vE@V`$HnP()J9O9xl{yB!XQaf0UE{S@=H;30JyHs+5yFN&`wB$VY@>E zQ3@k?J&!-n{$3UfVCyhN@H9_=TS?4oq4Mz@X%}LuXk|ZZ@0lA@qdGMMmHGNX0>$EN z3oQvdM%_cCbp-8rATMEuM!I;yR6dqQ{+RpO0A=jDV*9|H+LmT|jiM@8fXD)cl{mgl zfP~g4X13U9bTn=5HMMp+!;l$wv$UhH!Iy@t5AkEVEiNro2In(UI$!y?my6#88Ri-v zi4j^mgzrRlp5A!Oxz(!}ugP~w-IW8)7oM*T>o4&y-4r6ONN@crv$15&Mak%+_RH0( zX5scFma1B&990#MU_@+gpHz9*I^s>{H=1dP5C+o>#;Sqq4*HE;9V2d$S4D!^i6VRdr{s{1# zO&r@H&)YJ9J@LfE8JcKetHV-`LLF9$!{xI5F&Y= z4P>_;_Q>`=!)zzM<+rn;w;rI+zE_xAC|1~uNfZ<)$l}_ty4#+a#fYqg9leK2COZjs z91VcMK*}}=<-nahP3l2@iYJI)7ne^5DTxh0BXQO0erp#olAqF86+WCxix;31dDV_- zlra4ONgQxA|Dq?hYu#jibZXNE(oVnuEDl!~L0&~PN^rD*zRs~M*z5TE%eQ-O+_BiO z0j=)7C+4O*!-2I|$M@JO$F!FAb5;Ix<$Q?PPiy`9Xy>E{$2tZYOrIl$wM1CwlskJC zC%5)yT7-L6q*u9p-^^`2vH9ll$XqKgq5J;u;A=m6cHp%9bMblx$WI(W(Is1w-3Yq^ ziyaJIsx7m;H$dJ@ep<9oUj5oy3oVMiIno7+azkeylC|NZ6%lU3Qt~g%(kXh)w+&S! zx9l&0`}C*RYv7}28Spm=1hAlLm`RL2QH?K#N|h{h&svPQ?&;ve1bw`uq?>*6#p*?A z`_aLmh}#6po%woEbfnO}r-0*O9`{3dwhRA&45c>S+o4s`m5xhg-MrDQ(JV_SqckHG zhD1v~>VkEE^su7SoroKwd{5_7FPQTXp&w2C?wDh zV!MiIpwvzg=LrU`2`N-8*sb}f9z&=rg=A-w%(_$W*S|DT*zMXF3}Toj@w*M*c<_Xo zacXBJB}&BvOUvr$LY!ZpaoEh#eCL} zw!nXnS0$U1&Tvg@XD?dWw9^E=eEJHRA6K@QPg^N3=Fhg+5L(@*tU}XiLtPxa*fAPZ z$@$dpm+B04mNOhs*HR~*<*=)tUacVZf~i$k+f7|+aOiyPTtl)HJatwm6yN-So@DJ*LJF#eEHAK5jCG{}m3-@?!mc%-|AYY) zCVkkWb;18+1y~sBlU$6hxOY-tOG^ihbh}s_hy(1IV)tIjna9S0Z|0rN89~bIfn5A| zxf^J;#V%@&8tLsXyOcx_&!hRoIj@qSJ#I-1>O)iO`zH?A)|v+CYNUDb-EJHR-oa7d zFUKQ|=TB$*8E!#((`3dS$>3vvP^MGEOb*h4W>B{k^&x_T*dzeJZJ*7+AmBn_*F|i# ztOy0LF>ON7**1Xmxh+pDgcUPvk7})OjpK*POeu-jmF7?IM|y6>L~Bho zsrE8(>)U>T^AyS!(!de&Gp2Z&1HeU8PR5eF*)BL->O0LwD%6ZbdS)`Eo0A~Y&9G14 z(sU3sYcr_gs61bzU5A>*<#R>rnsj@~8#~2Pj=}0iXtcW07aTd(YjBEC-Q>?)rgegt zpqp^KhlE65I1Yg6AqkG3H^A`_l~2ACE5MCh;{lci=R@tyXbqGgYPcQ=%w>x&m-@Cs3zr4CugM>4LG%YT4>i?v`@@vrlmBYAnJEJ zTbooNha7%&=&e_l5W#A3iZw7!^y|G`=zK2doO5->BP*O`TbH`s_ExFZryPy%AC8$g z_@-+}v=|u~WhoVQTDUb=_&c*{MuwZ$;zgR{Mz-XqC5O%SyO+)Mhqpvzo)hG_^fPQd z5O{ zwkReMdZTL1Tt1gymN`j{CwXhlMJjEhs?V%l1?csPp&)ITcAZ$@)wc;T^U;Y#pKzn*X%|5hYqde);9%%nwxhT{3GnFE=Lqcegl``>RCT0b$1*i!p>;4! zuVK#=216h9SE5&CWl9N?I>?qzwtBdM@&h=sn7H5tt6i6c-G-5sGLL5pgFs4)$~BT- zzd~n`_b%TIF!VSPB%SHg1kTjWV>oNVvkL#* zkfda7_bg=#mWGr9cRr-3umYl?&@Y|=!eRYbR|^*2PRSy9Kxo$iGmOEjCM<67W8q1< zI7_#nalM*GK#%p_3fYmK*n@$g?TaaS-!vJBQ5Waf>nHt(Jf?cl&S^gBY2^;XgBP~$HGQcOpzXDBk^^YAa3UQ9U|VY zUlzVIQQ&&E)c^q*7DKD2DC>y@&5MYOvK`lm0k-`t`$5^EUXVDa0<}mb@dBR?qGA|+ z$co#HRkhXzTPsGp8z64KIV66_1C6L3&ACACG1?%4qN+GRbo2om4PbKlr_f5^M1fIC z)AlKY-QBFSf)N#v@|AXaL!K^`-pI^aHf*$476wN`;I7CtH6;7t@LK@kwXp{LHwrn2 zLMpn4L)$1yB;2#FyXYr%nLNAB9`Z(^87?2=)sh$) zp0AEDfn^kBcw@dtrR~Blyl07(=H$zq-Gk5314ilPcNuzGR(`8>^)uv>-Oq~k9(C+% zb6J(qE->MTrsit*_@-mj#&9Dhl6q)iW?W2d3EBxm6-1;Y33VIQ!KTsIk++es;9MKU z^?*v5H-JJSSbJlZ?fNP$O&B;1Qfbz4qgPBenL_mMNC7we;iIG-=Y)X>K}br@jbX!N zenBH@p_3m~T}Gtw^MKy?v?cb`fW_=bL_5EJrgcF)rFP1nL7kIMPt&W1?N?PAB=o)M z{B`7z8Y@6zr+KFQCs`)kxP&OIhOnIJK+CZ%5ly;=v>k39V-B5YXW!{+ret7D;YmI= zJ(r@U02^S9xTrvYR+=hWTO%)S(u+W;n_c2GKQJBE?@D8xw#d}*uZ#2^@gdgYG{O~| zq(;rCdgP4y7;hD9*MbtipxoV13_#+{Im_HPb14+ADN|6}kgqJ4N&(Ot%FB0-Z z_>i}XE=d7x%P((O@9N%V-Y9n{4Q|!yKj6+eUUG?5ce&Wr!GL2Sd?XBY&@3?~p3iy1 zidO2{&2Y;?sLZ#DeU&Z52fUPpKYo4l*V`8_PuLzw6j|HIdwmnv3V%MJl#3o9T+k?SPp3_hZI?Az=Q) zGbUpcczc{|17VClb4SboJ{r+O^#aOFr__CVk=EX|mgoWa`lwGyr^I<_tix`OY z8MKhek}3=wSDgw`_I+$#eqz_LN9`~-F*pie?*zEK;Ry1{Z_F=VzCLB&{#U5iTM^s@aY7lKU0PZ`$&c*ok- z8s?7n5ax=)1e+bR_IbWbWjZi7%YTYtt54HclJ~u8LL?q}07Wsy83MOFJ|WW3C(-jB zWN>ZlMMUoxiLO_-CiD9Y`(D;&J@w2r%HkKt{_v@)&9`|z411l*L3(>7MlMw|XVZVfa2c#!Lb3BlyAS7F2x~ zhYgCSDx`Qp=Tgzh@gZJk4x2IDcRq+3Tor*aq}qv5tDq2e*x`(x4tg)+Qj%nbC=j?tCK2OZ1t zpWh9FsjX(Ept^OsuD1k2rZS6!KK<>5kz0ntH{|)aGQ#}hcjo*w6rS(7%kK-G7BH)U zK?N@4t%LwDh)Hlr5G3`aJc@$BGhZ{8kZyeqk|^dH!1V;N5G%oBPqO7B84>)_C zruabvQhWw@oYZ|FpS*}tl)rg9fA|01v1Qw07E4x|LfktnWvD{&L`4E{)%{PvZuD-6 zTlfDL$JQ7Y2}GeF+iXT$1eL|f-;%YVh6B- zNrORwfbz($fHLTS0JN8L=N5;SNT$*iOC(dDpM%T+d2~UZzeFC5oRuHriE;Uhk|tY- zA)~Wr`rqSdqbXA_K>?ifYz?>OzuXg-HnQb@KBPHB_yDQ*|Gn0sKc{(^*)p4Eg>QA? z&G4v;c^610f`wI%qCI}{#Aa@heqW>v7caSY$tjZDdHqoWcKAe=(`RpFeGVbY@l*e% zo{{_1+^gED`ST>Ucd!<^$~)?^r@rc*%#f(_m%Mhn#gtUN3u7p?Oqy^D3;H*wZ!e8n z?xrp`wnV_t)KwhbvJ{!BZ9yGj{xICL)Z=FZDakj%s5aFF^QiyT-x!tOHM19JziXY`GN!lED=BlSbQ-iqcKJZPJn1W7 z+2xZ*ue!X1Hov`U3G}dhh<}eH*P%R;DnL0t3}3gPxCMmppR52~#{aUw_`vTqA5u|h zTHf5bX61)e6u{TGoV)X~Yi_yeu{3rLDf+ksr0lQ?R1Z1^I?3FOSV|Heh<2(3gzsVL zlys!dBUVp)=Wo?H^=K=4?X`Uji^^}mxpBujPEEHm_4DBA+Ht%-E3i_Ag*QRKf>A%7 z2w=waWc)f=;5DbXk6!q9RKn3MR_)cLHczUx0t#Xp?|xVM-4)aBl#74bm_P6Df7WI; zWRmchXEXceK=6#BA+?4fB3C3%WYkxC%5NPUdaQqL934@Pck}J7s|OS0>U#johd$6> zkN>ykf8wZqwfrs_2$1nnoJ_prbE(6%*zjVYThz#vnXhU2na$tAC7F$>h2rlS*jGpF znlzxKu+#)*1cjkxXDD)zU7da8Uf<4B!3}Z)IVe9s0UWXh%qWw61;>J-dP8f|KDYs$ zZc5q#EP3KmWRc@x-fR`j2I8J!sWh%-VejOdg!&`mtWpqH^AEaoCKP;KALc(gHSr3+ z5%zEasZf*V)M5%#UJy5iMMVJn)tQ9=rfjQD$pi>tnAHVew!Xg0&c06U^5xbIrR`iJ zF_at%t9L7$4|YpWVm>kIyy5X{?R{@adR+hfyI9P@t$ZtOw|%}>gm3k1TOM_{xVPfa zIhGDY=Ur#Z=1;9QsIR#=5v1;R!)J3+iPAm>2tid{cmCB%{rl&wX@cm7T`4@|EbCwy zJbf5i^|XY4(Dgj$P@nYy;cP1Aqo(RRkoB-udqb!h?*i#4|LVMot1U(K)!xRYl5M~4 zb}el-dtm$0J9~ni$i9o?yfU9o01mO})_A5SPzgh~no&5X;cTH}d!~1bnQk*)-`b;G zhU_yE&oA*8*ocTai2-QIs+EU#`1GO+js_51o)`6{woo|n7U*0iWMu@Ae zY>ci_1O#+nvG1C;@W`>m4F*5|EMIb`pe#*tDZk#b`bV#Au64bajfV_xfRxC?^6#hh z2mgLYkh~NF)85%Zx`ZQUB%9luXjN>7ursyNL&SIvSywE%8ec_FY~s!{lbUw+#v~x@ zy5|OW#_9+7_Sfnb5Y+Y_zFl{(k==Oj`+)(a(A@naQ~uk5?g<<@3&gLsDS-GDlfEQ= zb*-GX%ve+7^$Xa8l+0_uI#6I(AXy=A{2Pc6edtC( zMWO(q8+Not*(-OzrQp)HBYWsxpnW*HM2ND*FKOMSzk9EBr&BSA**aCUrB@ar#rlV3 zPl1l`MB5933zYQj8SC7IAU*0By8T7OfSTWc<+|``!HX>|+})2w%KGj+*Q76lzD~yn zmU*+-ZA_-=x9pH&KQI-&4(Es@P-LiR8{lbG0*Jc`j416uW5n+?>2(%GL zfUW2&7dg;I#ABDV5$(KC%Z!0d_-Nk}*hj5V9I8lS4}&~L>#Y>L`8f*!_gQAthg)+5 z?99tt>jT$c@yF#qeDnWj-W;DTW3&<8SX5(i5YJb(A2>o^`3j=6>T8Q)c!PT-!~LRh z7EoU%x$s4f9+vq{H1N8~N!qtne!v0Q>Hh63c=V+ali zW8pwcJyNC;FOhG+0o_@46J4|?@Emz}Kd?sX@PyMsUjF<8&;mLs`m_2 zUoyJ1eZ51VPq8RL_;!A>c5&mQ&S}j{mo@eE>@FWG7U|_2wlpn9A}v2`NK&G!e@ zf1-#4a_AYm-&Sl5ZKq4(*y1D6@@UGi_xqF3^18TS21}iRJlM&lGcCZ6jKZLIc` z@ALj)AB78mOHU}CF0|7Zn^AT1K#~9bVc}n(r2q07gR?+R))K!SU~JvtGba+FOM_&e z!)Jw*Pll#^&OEZXMUNG*Rj1BtHO~KXL=YY+GGsfw%-Xz_C=9_}NuP^&gC1Vv0vX&F zBZW~JW3Yt^bHfy9OMtzQyrHfqglOSHQ=eKAmoxv;eCX1bLHf3lZUo<%ai`n?D(;j!mq{O8Vh;_{}l!fwjHY4E(km_M~S=Ol02m*w|H{f~N&yWe;|v9EBrYVFsT zG9QD)yXUWy>)-SETvw(nGM10iAQ?QXnu&bPhw~s^53%dqTc^!VrT&9}e^CPIqpP$q zez&$Z!j#a`nzP4u6K)=Rj7`w|e9__z#w3rUKFwA`;(MYj^u42X@oi%TKcCu(-tx@a z4Wmc;Jb%`^;a*beT*En*HZr4T8@plks7qDE$l;@sDu=WovbCaD z>xuhbXI8?G-gCk8r}oB7Twf@3wCePWuRXy8+xyYO&wnqZ`Y*3Dc}m^@8%~45SxT&p z@|#88k$j-LY1xj_-74vRqTb@UOU{>^TxqnBQ^V?&VREsVeetj%+O_wg~(hrOmM3*Do zJ7caSev;^t|5P(eGxNBU)CE^9n^j4lb7Y+I7neH-q$ z+~8k!zkh_DFONt6tLElVm)yJ(?t81mPKmNXrdA5}$Q}{#~Z)JGLZL{3A*DKQSf#<2?Z^)Ne!o2bU|ds{jB1 diff --git a/Svc/ActiveRateGroup/docs/sdd.md b/Svc/ActiveRateGroup/docs/sdd.md index 235c3df0cd..d7e08f5ec4 100644 --- a/Svc/ActiveRateGroup/docs/sdd.md +++ b/Svc/ActiveRateGroup/docs/sdd.md @@ -63,7 +63,22 @@ event, and increase the cycle slip counters. As described in the Functional Description section, the `Svc::ActiveRateGroup` component accepts calls to the CycleIn and invokes the RateGroupMemberOut ports: -![System Tick Port Call](img/RateGroupCall.jpg) +```mermaid +sequenceDiagram + Caller->>ActiveRateGroup: 1. CycleIn + activate Caller + activate ActiveRateGroup + deactivate ActiveRateGroup + loop for each output port + ActiveRateGroup->>Callee: 2. RateGroupMemberOut[N] + activate Callee + activate ActiveRateGroup + deactivate Callee + deactivate ActiveRateGroup + end + deactivate Caller +``` + ### 3.4 State From 66569e8118e5b46314b6b7b1b88e138ceb409630 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Tue, 26 Jul 2022 09:57:23 -0700 Subject: [PATCH 037/169] Update to Svc::Framer design and implementation (#1586) * Revise Framer SDD * Rename FramerComponentImpl to Framer * Reformat Framer implementation code * Revise Framer FPP model * Revise Framer SDD * Remove unused port * Revise Framer SDD * Remove trailing spaces * Fix broken link in SDD * Fix broken link, take 2 * Revise Framer.hpp and SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer model and SDD * Revise Framer SDD * Revise Framer.hpp * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Add sequence diagram to Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer model and SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise comment * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Revise Framer SDD * Add new word to spelling check * Fix error in FPP annotation for Svc.Framer --- .github/actions/spelling/expect.txt | 1 + Svc/Framer/CMakeLists.txt | 2 +- .../{FramerComponentImpl.cpp => Framer.cpp} | 61 ++-- Svc/Framer/Framer.fpp | 31 +- Svc/Framer/Framer.hpp | 100 +++++- Svc/Framer/FramerComponentImpl.hpp | 91 ----- Svc/Framer/docs/img/.fpv-env | 1 + Svc/Framer/docs/img/Framer.png | Bin 0 -> 86526 bytes Svc/Framer/docs/img/class_diagram_framer.png | Bin 21120 -> 0 bytes Svc/Framer/docs/img/framer_example_1.png | Bin 46223 -> 0 bytes Svc/Framer/docs/img/framer_example_2.png | Bin 57819 -> 0 bytes Svc/Framer/docs/img/top/event.json | 48 +++ Svc/Framer/docs/img/top/event.png | Bin 0 -> 33543 bytes Svc/Framer/docs/img/top/event.txt | 6 + Svc/Framer/docs/img/top/file.json | 76 +++++ Svc/Framer/docs/img/top/file.png | Bin 0 -> 65865 bytes Svc/Framer/docs/img/top/file.txt | 13 + Svc/Framer/docs/img/top/framed.json | 109 ++++++ Svc/Framer/docs/img/top/framed.png | Bin 0 -> 81211 bytes Svc/Framer/docs/img/top/framed.txt | 20 ++ Svc/Framer/docs/img/top/hub.json | 63 ++++ Svc/Framer/docs/img/top/hub.png | Bin 0 -> 37919 bytes Svc/Framer/docs/img/top/hub.txt | 13 + Svc/Framer/docs/img/top/tlm.json | 48 +++ Svc/Framer/docs/img/top/tlm.png | Bin 0 -> 31864 bytes Svc/Framer/docs/img/top/tlm.txt | 6 + Svc/Framer/docs/sdd.md | 321 ++++++++++++++++-- Svc/Framer/test/ut/Tester.cpp | 2 - Svc/Framer/test/ut/Tester.hpp | 4 +- 29 files changed, 861 insertions(+), 155 deletions(-) rename Svc/Framer/{FramerComponentImpl.cpp => Framer.cpp} (52%) delete mode 100644 Svc/Framer/FramerComponentImpl.hpp create mode 100644 Svc/Framer/docs/img/.fpv-env create mode 100644 Svc/Framer/docs/img/Framer.png delete mode 100644 Svc/Framer/docs/img/class_diagram_framer.png delete mode 100644 Svc/Framer/docs/img/framer_example_1.png delete mode 100644 Svc/Framer/docs/img/framer_example_2.png create mode 100644 Svc/Framer/docs/img/top/event.json create mode 100644 Svc/Framer/docs/img/top/event.png create mode 100644 Svc/Framer/docs/img/top/event.txt create mode 100644 Svc/Framer/docs/img/top/file.json create mode 100644 Svc/Framer/docs/img/top/file.png create mode 100644 Svc/Framer/docs/img/top/file.txt create mode 100644 Svc/Framer/docs/img/top/framed.json create mode 100644 Svc/Framer/docs/img/top/framed.png create mode 100644 Svc/Framer/docs/img/top/framed.txt create mode 100644 Svc/Framer/docs/img/top/hub.json create mode 100644 Svc/Framer/docs/img/top/hub.png create mode 100644 Svc/Framer/docs/img/top/hub.txt create mode 100644 Svc/Framer/docs/img/top/tlm.json create mode 100644 Svc/Framer/docs/img/top/tlm.png create mode 100644 Svc/Framer/docs/img/top/tlm.txt diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 887ae4524d..ace6521020 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -554,6 +554,7 @@ formatline foundin fpconfighpp FPGA +fpi fpl FPL fpp diff --git a/Svc/Framer/CMakeLists.txt b/Svc/Framer/CMakeLists.txt index fb689c4fb0..c0b2c6c2a7 100644 --- a/Svc/Framer/CMakeLists.txt +++ b/Svc/Framer/CMakeLists.txt @@ -8,7 +8,7 @@ #### set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Framer.fpp" - "${CMAKE_CURRENT_LIST_DIR}/FramerComponentImpl.cpp" + "${CMAKE_CURRENT_LIST_DIR}/Framer.cpp" ) set(MOD_DEPS diff --git a/Svc/Framer/FramerComponentImpl.cpp b/Svc/Framer/Framer.cpp similarity index 52% rename from Svc/Framer/FramerComponentImpl.cpp rename to Svc/Framer/Framer.cpp index 576de36aa0..71e13dfb4c 100644 --- a/Svc/Framer/FramerComponentImpl.cpp +++ b/Svc/Framer/Framer.cpp @@ -1,38 +1,41 @@ // ====================================================================== -// \title FramerComponentImpl.cpp +// \title Framer.cpp // \author mstarch // \brief cpp file for Framer component implementation class // // \copyright -// Copyright 2009-2015, by the California Institute of Technology. +// Copyright 2009-2022, by the California Institute of Technology. // ALL RIGHTS RESERVED. United States Government Sponsorship // acknowledged. // // ====================================================================== -#include +#include #include "Fw/Logger/Logger.hpp" #include "Fw/Types/BasicTypes.hpp" #include "Utils/Hash/Hash.hpp" namespace Svc { - - // ---------------------------------------------------------------------- // Construction, initialization, and destruction // ---------------------------------------------------------------------- -FramerComponentImpl ::FramerComponentImpl(const char* const compName) : FramerComponentBase(compName), FramingProtocolInterface(), -m_protocol(nullptr) {} +Framer ::Framer(const char* const compName) : + FramerComponentBase(compName), + FramingProtocolInterface(), + m_protocol(nullptr) +{ + +} -void FramerComponentImpl ::init(const NATIVE_INT_TYPE instance) { +void Framer ::init(const NATIVE_INT_TYPE instance) { FramerComponentBase::init(instance); } -FramerComponentImpl ::~FramerComponentImpl() {} +Framer ::~Framer() {} -void FramerComponentImpl ::setup(FramingProtocol& protocol) { +void Framer ::setup(FramingProtocol& protocol) { FW_ASSERT(m_protocol == nullptr); m_protocol = &protocol; protocol.setup(*this); @@ -42,28 +45,46 @@ void FramerComponentImpl ::setup(FramingProtocol& protocol) { // Handler implementations for user-defined typed input ports // ---------------------------------------------------------------------- -void FramerComponentImpl ::comIn_handler(const NATIVE_INT_TYPE portNum, Fw::ComBuffer& data, U32 context) { +void Framer ::comIn_handler( + const NATIVE_INT_TYPE portNum, + Fw::ComBuffer& data, + U32 context +) { FW_ASSERT(m_protocol != nullptr); - m_protocol->frame(data.getBuffAddr(), data.getBuffLength(), Fw::ComPacket::FW_PACKET_UNKNOWN); + m_protocol->frame( + data.getBuffAddr(), + data.getBuffLength(), + Fw::ComPacket::FW_PACKET_UNKNOWN + ); } -void FramerComponentImpl ::bufferIn_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { +void Framer ::bufferIn_handler( + const NATIVE_INT_TYPE portNum, + Fw::Buffer& fwBuffer +) { FW_ASSERT(m_protocol != nullptr); - m_protocol->frame(fwBuffer.getData(), fwBuffer.getSize(), Fw::ComPacket::FW_PACKET_FILE); + m_protocol->frame( + fwBuffer.getData(), + fwBuffer.getSize(), + Fw::ComPacket::FW_PACKET_FILE + ); bufferDeallocate_out(0, fwBuffer); } -void FramerComponentImpl ::send(Fw::Buffer& outgoing) { - Drv::SendStatus sendStatus = framedOut_out(0, outgoing); +void Framer ::send(Fw::Buffer& outgoing) { + const Drv::SendStatus sendStatus = framedOut_out(0, outgoing); if (sendStatus.e != Drv::SendStatus::SEND_OK) { - // Note: if there is a data sending problem, an EVR likely wouldn't make it down. Log the issue in hopes that + // Note: if there is a data sending problem, an EVR likely wouldn't + // make it down. Log the issue in hopes that // someone will see it. - Fw::Logger::logMsg("[ERROR] Failed to send framed data: %d\n", sendStatus.e); + Fw::Logger::logMsg( + "[ERROR] Failed to send framed data: %d\n", + sendStatus.e + ); } } -Fw::Buffer FramerComponentImpl ::allocate(const U32 size) { - this->getTime(); +Fw::Buffer Framer ::allocate(const U32 size) { return framedAllocate_out(0, size); } diff --git a/Svc/Framer/Framer.fpp b/Svc/Framer/Framer.fpp index d5576eda33..071d06951f 100644 --- a/Svc/Framer/Framer.fpp +++ b/Svc/Framer/Framer.fpp @@ -1,25 +1,38 @@ module Svc { - @ A component for framing unframed input + @ A component for framing input for transmission to the ground passive component Framer { - @ Mutexed input communication port + # ---------------------------------------------------------------------- + # Receiving packets + # ---------------------------------------------------------------------- + + @ Port for receiving data packets of any type stored in statically-sized + @ Fw::Com buffers guarded input port comIn: Fw.Com - @ Mutexed input Buffer send port + @ Port for receiving file packets stored in dynamically-sized + @ Fw::Buffer objects guarded input port bufferIn: Fw.BufferSend - @ Buffer send output port + # ---------------------------------------------------------------------- + # Allocation and deallocation of buffers + # ---------------------------------------------------------------------- + + @ Port for deallocating buffers received on bufferIn, after + @ copying packet data to the frame buffer output port bufferDeallocate: Fw.BufferSend - @ Framed allocate output port + @ Port for allocating buffers to hold framed data output port framedAllocate: Fw.BufferGet - @ Framed output port - output port framedOut: Drv.ByteStreamSend + # ---------------------------------------------------------------------- + # Sending frame data + # ---------------------------------------------------------------------- - @ Time get port - time get port timeGet + @ Port for sending buffers containing framed data. Ownership of the + @ buffer passes to the receiver. + output port framedOut: Drv.ByteStreamSend } diff --git a/Svc/Framer/Framer.hpp b/Svc/Framer/Framer.hpp index 0b488e53e6..c94f6e7b74 100644 --- a/Svc/Framer/Framer.hpp +++ b/Svc/Framer/Framer.hpp @@ -1,17 +1,107 @@ // ====================================================================== -// Framer.hpp -// Standardization header for Framer +// \title Framer.hpp +// \author mstarch, bocchino +// \brief hpp file for Framer component implementation class +// +// \copyright +// Copyright 2009-2022, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// // ====================================================================== #ifndef Svc_Framer_HPP #define Svc_Framer_HPP -#include "Svc/Framer/FramerComponentImpl.hpp" +#include "Svc/Framer/FramerComponentAc.hpp" +#include "Svc/FramingProtocol/FramingProtocol.hpp" +#include "Svc/FramingProtocol/FramingProtocolInterface.hpp" namespace Svc { +/** + * \brief Generic framing component using FramingProtocol implementation for actual framing + * + * Framing component used to take Com and File packets and frame serialize them using a + * framing protocol specified in a FramingProtocol instance. The instance must be supplied + * using the `setup` method. + * + * Using this component, projects can implement and supply a fresh FramingProtocol implementation + * without changing the reference topology. + */ +class Framer : + public FramerComponentBase, + public FramingProtocolInterface +{ - typedef FramerComponentImpl Framer; + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- -} + //! Construct object Framer + //! + Framer(const char* const compName /*!< The component name*/ + ); + + //! Initialize object Framer + //! + void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ + ); + + //! \brief Setup this component with a supplied framing protocol + //! + void setup(FramingProtocol& protocol /*!< Protocol used in framing */); + + //! Destroy object Framer + //! + ~Framer(); + + PRIVATE: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for comIn + //! + void comIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::ComBuffer& data, /*!< Buffer containing packet data*/ + U32 context /*!< Call context value; meaning chosen by user*/ + ); + + //! Handler implementation for bufferIn + //! + void bufferIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& fwBuffer /*!< The buffer*/ + ); + + // ---------------------------------------------------------------------- + // Implementation of FramingProtocolInterface + // ---------------------------------------------------------------------- + + //! \brief Allocation callback used to request memory for the framer + //! + //! Method used by the FramingProtocol to allocate memory for the framed buffer. Framing + //! typically adds tokens on the beginning and end of the raw data so it must allocate new space + //! to place those and a copy of the data in. + //! + //! \param size: size of allocation + //! \return Fw::Buffer containing allocation to write into + Fw::Buffer allocate(const U32 size); + + //! Send implementation + //! + void send( + Fw::Buffer& outgoing //!< The buffer to send + ); + + // ---------------------------------------------------------------------- + // Member variables + // ---------------------------------------------------------------------- + + //! The FramingProtocol implementation + FramingProtocol* m_protocol; +}; + +} // end namespace Svc #endif diff --git a/Svc/Framer/FramerComponentImpl.hpp b/Svc/Framer/FramerComponentImpl.hpp deleted file mode 100644 index f95cfa699e..0000000000 --- a/Svc/Framer/FramerComponentImpl.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// ====================================================================== -// \title FramerComponentImpl.hpp -// \author mstarch -// \brief hpp file for Framer component implementation class -// -// \copyright -// Copyright 2009-2021, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef Framer_HPP -#define Framer_HPP - -#include "Svc/Framer/FramerComponentAc.hpp" -#include "Svc/FramingProtocol/FramingProtocol.hpp" -#include "Svc/FramingProtocol/FramingProtocolInterface.hpp" - -namespace Svc { -/** - * \brief Generic framing component using FramingProtocol implementation for actual framing - * - * Framing component used to take Com and File packets and frame serialize them using a - * framing protocol specified in a FramingProtocol instance. The instance must be supplied - * using the `setup` method. - * - * Using this component, projects can implement and supply a fresh FramingProtocol implementation - * without changing the reference topology. - */ -class FramerComponentImpl : public FramerComponentBase, public FramingProtocolInterface { - public: - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object Framer - //! - FramerComponentImpl(const char* const compName /*!< The component name*/ - ); - - //! Initialize object Framer - //! - void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ - ); - - //! \brief Setup this component with a supplied framing protocol - //! - void setup(FramingProtocol& protocol /*!< Protocol used in framing */); - - //! Destroy object Framer - //! - ~FramerComponentImpl(); - - //! \brief Allocation callback used to request memory for the framer - //! - //! Method used by the FramingProtocol to allocate memory for the framed buffer. Framing - //! typically adds tokens on the beginning and end of the raw data so it must allocate new space - //! to place those and a copy of the data in. - //! - //! \param size: size of allocation - //! \return Fw::Buffer containing allocation to write into - Fw::Buffer allocate(const U32 size); - - PRIVATE: - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for comIn - //! - void comIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::ComBuffer& data, /*!< Buffer containing packet data*/ - U32 context /*!< Call context value; meaning chosen by user*/ - ); - - //! Handler implementation for bufferIn - //! - void bufferIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer& fwBuffer); - - //! Send helper implementation - //! - void send(Fw::Buffer& outgoing); - - FramingProtocol* m_protocol; -}; - -} // end namespace Svc - -#endif diff --git a/Svc/Framer/docs/img/.fpv-env b/Svc/Framer/docs/img/.fpv-env new file mode 100644 index 0000000000..ff60caacf4 --- /dev/null +++ b/Svc/Framer/docs/img/.fpv-env @@ -0,0 +1 @@ +DATA_FOLDER=top/ diff --git a/Svc/Framer/docs/img/Framer.png b/Svc/Framer/docs/img/Framer.png new file mode 100644 index 0000000000000000000000000000000000000000..518e74ea3cef7833e6918e113a470b8bf01bee5e GIT binary patch literal 86526 zcmeFaXH-<#)&+`)iU9=`P>>)tCXz^wq6jEaKyoN@kff5cfP!R1$&x8@4uxb;0VU@g z6eQHHc~4S=;0W0f92^{iyLWEO z;NTo~!ok5^#Xkr?$>}Q#$HCdhX(%Xo&qz>2(9GEEvFt-lZQYwXW?H&3BDa{ixHxfe zF2B&$(2%)9fBA#vNezt;jdWLzJhqm3{@h1K!?~uisj{xJHl{k}WvHs^r!$0~-r?X~ zBO`Vwsj0+|W14Yo2-hl|Q}wBKw{n?EAuU8Zuvg#r$9*Fs&o1ucczH}zhE7x<-`we@uC$(=u&3*VYY8&M zyeolNi_<>Ge0++1r4lBP-n3gN z>&CnD1V`r7X1%le0>AabP*Gk<@AZ-`zUb!i^`_&@nZz@KPxSlcc&{->|}9fR?K zfBf*?h3viEt)x-^8|8^z7ys*)1r!eZP~G5X$gadyv*hYN|JSm_yvGf;qhIdje`DfBy-!)Te-UMyVB_Ghu}) zeE)odCjy5KzvdZlv6zq><(@Q_6#Q#%1k8vCx2G8{O!0qPQvuSW4V?AqhU4eWEtcfe z{QkQ0-`}%k9WOCjQ)9Tq&|3UI-X!)3n)0Y8>%ZOfB0Ri`IyOqX|G18Se$Zd*^aRJ{ z*1oE&TQmg!a@X%M!pk4~dJO#}_Wu0Hn0o??X#sck|FyP148~Vt@N(7BSdJgQ>aWkf ze423k>Thj-t=6BP`@erOb`oCRZ8J&mUz_;9|L({Eyow{gmi~Wk#;>LS-!X$E(yyrh ze!l+#oF72#FTnZF+Vppn{slO{00*i30>2o}_Yve5!}&f>{zWeTH!DWy-7jAM_hR#( zQS=LN{$~U5`x5;Eoc|1!zgOsAfb$D*e&@5lc>OP4|EtV?A1QzF`tKvK*!H_D(0hdZDGVo&ghVkZzcXLUp z`NGatMxqh_T93A2-K#4S{c1~SRE3k_QZ=cR+o2QlUiC!>|Hy-we!L-vmB!P~@xs2- z0sI!LU%3-xCEL2k;A2NpT2Scl#iMw+e91W&)oeaLo60C05?vp(rV2ghLT*;d9BDmdJN0!U zx_S4acxb@p`a<-0wDT_Ou)_+PtxNI3T=u);hDBq+^<0AW(@mWE^=ZlHTd=sz{9DGw zUjoJ2&>`yKrX_P2)@I(7gbDH+r*gUIIufnE_7L?*C}kjyqL-?nST&e zD@vE~YG+}WEDNu_2p;_W!B~{>t<=VCYXv>)un8du^PGHa4Dl`JiOP(B+_X~-N8jc z-4;D%P3xq+yR+ad)jnvo`ZY0y<@kI%t}DvXZex)5d$`>~;<6#Kv>~!sE~9mDLv%4M zYanmyH-VTfydk()R*T7&M5VIgtV?_gbH~(Xx_w?BopLlRl^mb7UN;^p59z@d9__C3BPUdQ7whxbVmw> z6DgJR_9GG-pB8O;eY>}ZFX`mDnB-KGDB;fO3;1pEesCcSXO#Qe|hD#yJd+vG1UZ*Khw1MsbK?}ToboZ3kFL1n z^~%n2NQF3fEvUk$m&;cdhHqp*3>&%}Ai2XFufRLZJbIsZCMQ9oHPccXQDZGHb>2?sUSYBK_TfQ}KI9Jdu$!xD+az%NlIKElI-mxFAkEW%9!M6Ya?)#Ml z`IXxF#h@$)T9eYH8ns6$l=i;$j3xAgkLwv4H!GUBXIT3)hd94}dD$)_#vrE_MG__J@P6hK~5_X!wDq|%SBWHsD5qu|XtBZC2 zk2mFVNoAZjqw*S~mC>Fg@6vmcZYqdk?_$wvSpQ(tH=o@tHa>eK;isnO)Q};VDp4|< zD~7&1{VnxLos@K52$2oRJuU82rfINjyL$-@+e=H~uvm3P?_E7zj`3%^nT!yqQU1n< zKbBfes~qt;$Cax)#@Yc@C^44q_?&|C67HVeuhQ5o6xn-rq)A9Mx_=LvRVG6v^;%)8X%3r$Xtv!}P48Lm#YPC;l$^qW;U zzB8)MjTRDthEo!)Uiv4wYQ0hHN@mpLwtL;fF&AcooP?8CxD8#Ih!bs5H zbN7irPNkIdX1fLCBnijtIEgE2kQawh>d#yIUY7J-C1eq>v;eTOvY^^p{z{``HDo)1 zZe;IIKmX3<5M?M50PZHUzX?#IK2hy$h-?lnIE4(y+_uN75M@16eCuZ)pnTz)?edo{ zRwG%!NBs!ym`Aadu!8|LzT_b!D#kej7z9)?w+B_s%7Xf9j^pA@ALWJHGz?L*N~y?u zTHuPJJ$G7-=6g5rCw1`sMx=yG`U|pHntC(+IFn;5V{W>&<br=b14(8Bk}K!S(gaca`1_cdSxb~Dqo??5>=!whZN ztycKib9Z~<2FHLIy!YOv#Rca*9uvsVDcJn&iaN?g6M++x@r);bw&n7N->1v@-`KTT z<9Iak9;uzI4jYTCcB_;5mAFUqr_bq{A*hT7RE-fV=>^1wx_b6xUv0^dwsyX{W#BTK(LxsuU@Ug?$?QLF$~qo z*$%jA-i-5{5lT#qq2PX=m2MyB{F~9XI=ZaaSGdJ}0_RJWDbX=@oN-mDb5jKhm;`_2H+={K+`)#1|Jt^qiRm z)kK1t?AQ^GTE2_TN)n;8O^7eYfmutQH(fLr}x=l_65gqY*cu)H5b)7pT#i76=R9GD+V?ElY)3Txx z#lzaPP-R|_^?XJsGgQO$>T*33M?dj-bZKscj*ohu9t?aNc2hrOLIesj`t>h z=4PKerKchh9nWLk(B4PULjJoSG$WIH*~ta%zen%Qk53z zYK;8(*6vsjS}Np;iE|8EAfS22gVN3*Z!_08J-4BeTU8=%zp6bkkF?qLt)*-1pkD0DQ)>j|vPtaV|4@KBes>qJ)_zf3ssOSdCwJ|w=tvbQ9#O>#QKsWU+4_-^ z(-mKr6jZ!$wS(3ou};|e586V_fJxs;iQl1nmD?rs@YP$YLa|wW0*5G+csCti}k?{O}m$;_NzI49qWuhZ>qD#w|At-=ADi6;vOU(mCZV_+&Yetug`isC&=B!3IV(!{CV2LRs= z|3ZA_o~}spVLMi#02WrCe9gS2iAOl9=8vOfB&xtmPIM%)>!GR9Jep;gsVb|>=L!1{ zSDi4K=sC40Jqt-}K%7$WgX0Cg`*4}tn;{^(=UF5|ubp?qrlA@mC5%2*y7Y?kKqLFO zB#Y<}BXGPc!8d)-RQG^5vwg6>GP-xYiKp}vdy=#rg^h6VBU;|?u#L!>;-m*R4cm0ohF8q?5L=+_L)`^PEF5%BSC0zS*vnr|z}`b`e}is9-K3yXhW^Ewn_1Xy z)D590EW!7Dse6?4BZEfx(iLc4pLO&bP83F`MfomzZ9NZA+OE!hWlQVCK{uCr1M*|2 zR4{k52|*{a<^J!t=?HGQY~lj{P-1tx+hBT* znw@jnVTJglbGh}5hAWL6Qb(CeA7bZ=hc9dskCL*8cG5Ag+!LW+f+Ae;tuHLOt*Lg7 zd?$IQo+lflHfMDXx~7I1sfN{4qcRkJ8@uZj(WcO*kYJd}dx0ChKuA9QZJCAFL~+lR zh8~2N`HbO^DjUQa%V*owo5@Ghy}d+qFXd^u*4KI{U}eR3^A;Wr0o#g#Nzaf_D<8?M)Xv7%d(>yvY4EL&|Wsa4KD`gLtOB>@OPIDqzT%&(Zn)~I@zsi==+f(2V35z|Xzo4SoJvYkq+!qt zD2AHRrck~dza&|0S#v1rSdL1B60ewMEt1?%=W4cbsaCo=u>Pe_Z`ZA^GvaC z$$ofC-FvgoOVMcwX`ew((wfUO-U`!?x{EXtrac9lF`lO`>51KT0-`6;NfhWa+zov& zTW9Ci$pv}(iZF%D^3CZ|wcah28vS^-X5BdnOJp_W(o7?MOkUfm32$bTq8y|NjmeIw z*c;GqSvB*m>xjiwH;8o7?!It}_hqjOCiRICjDP&)g$TQfOh)lszD<@2eF(tcLjOhMinn#|5fhO1UhH}aJ*6mG5n4?bU@>8*4L{v>v|nI-qg$R8=t2Bp)rJFZvSbE7>`>6}R9ks=k<3QgdmO z>~m~s*jf~DCgH-Db1E7x2c|KGr!S}43wU1DzL=?aaOtHKzhPIJ;&LuSy`pgPGL-te zOFrFnIrLwE*vXnH$g25BJPjR&7CfQ)Hk38KH)d3o;`-wS#7h*4xr|RDCOm$CC2_2{Y^O(2eg&FmhSElt{f81k0iesk z^gSpt8HTeh7By$}zswiL&*A2LQK$c?P`0X0-`W#Q*y+bJA8P+OMK&q%DB~MyYv=Z=`8WP5O*eZOK}-9hr$W3|ho^f!_%UJKCY zeT5}skQJcUG;_vU6D5J+n0T1C93=KWlng+xJ8wUnu%Ur#+5S^kp|= z-`*SK<0lfYqhq!b0;b0X{bZb=SkVo=EixV}}j4*VFA ziX~%C;+4P=sP+Y?^^(&!vn{)nL{7s&fVDa>U zTV-gr5_^XcrH!t_a=9t3c6~f<@8C?I8r%9aU5pYv79)Yqp0xL78Y_wGuhuN6*^55) zByUW&T>f~8BjN=d2@1Wt0I-r`tQU=RgYCJ=jaH|P-^-+WoO^ty-ADIPRH$55>vD;% zBYWRT=pWXN1gg&TNc^OkSG!EOw}GNK=pB|iLRCKzs_mB#f=r^~ThnL6@^_BXXA6+7 zrK*Np4gY*OtB_|lTd)`!xMiy(q+fCbirqA5CNlG_Pq!Gf>}E4MCl<|6vAx_lt(+%q zhDoh^v=sF|(BJJKLF#=rz!inEvoRw(QxfRQ*_?aZD;y<*xjxO$NYz7|Kv1-R8HRpd z9zv5OKt>SCD<3!c@@!D+Vp^19=9>|(;z7SfdG!w&^ZVF>c;@nDH+!3%LqXNtdh);s#&z2X1RnZxUD#y9Pd}Rt95r!NiPg7mvnhFueA^Ip#t(D!!CjK z#}b6VI{xVcRW$TOH-it5s%G1B_qb(lVzZq22+m&rZS0xgeA&8sRo3w{&CoBQ=f!XN z-cp?_GsY`%KS8CwzF3OpTbZ7TN;q^M!?qz8yyPj+4kLi@odS2Rw{G1iXGd;qhphSj z*R6?3LD2qFBQm&U$)G_^X7Qnp`@%g~=iLcs8TEUNxZ#~FUXE~sDMR9R8A?uh<82J= zD&(79`|X$WT04Iabcvq?dL7+8ay;)|C7OoQEUwijm4ePz;Z-U7eXexb-;M~Nl3Zi2 zf_W;^r&8+Qcb0{jrUPjqpHX*&e72nFS29nf zXRj77_ZrOkplrJ$v0IlmBwa$wuI{QkEL9_1GYQDNAYr=87|0S)T#t3w z;|HLx9=_lGvO@edCv)Kzh~X;p76 z&`qFa)NBo_aMs(N_DO2wI{cqw+rNQFnZPHv6Z{6n-Y}ly17*TOqQ9JwIzR@? zBctap%;E}wr)>CjEJO-|z$nZtR&a|Qw61}buaWg=!*)N8VTU}St-CKT79`8UjxYg$)or8v`3*iQ5lJv zhLfu%(6RNvPDF!39dE1`Ig?qEDRrP?90UYpXpwkDHZfm=9E!C!H?aw+4G6Ky=T<=^ z*4>8|&O1@Sc}FN#08fi72$6s6htm3AnK)>%Cs0`RoF9Dnj-Yc;91#XUjmm4=oXHwa zFE2E40A^cM*g=%Xf*FfUBUScl;sa&0$Z@uTLf4L6nS6VCdR=TWjU`%O;`^hlRSlQv zvos{oHXxE3r2_|)vC#wSj@ZuAn!!=`5R#3IJLz$9XLIWleL03WRYV!|TBf`g)&OQ- zs>95fMDWr^r)z>5F-s$>Y$~bKo1L}(c9`$-mkUTQ8bLOhKGF!QnE<&}j7Tz# zfYTAt62IvxD4R>#@|aSYnZWK$X~+0a3V51nV%vpr>bBDJBs?EA$YtRBn>Z`z8Eon>H;*s11rf$&I zmzb8-VGcI{E4-pNox>w0NSZq-UXKV(wXXowxO4mWlJxj4BhyAxVeGk&m z^-LAKLVH`c3{RWRJpZH+uc0(oVC1GjyoX;W++rK7q?dBva$3JP%D1a&jrcM|5_X~E z#ly!xR#^xqEnM*J8X>L?zkGNxr82xJ&kdQ{j?B-sYF;6|u^|w0ame=hmwEP`Bef?( zUS5<)&1k}OD{A`|W3TpKB&_nV8w2Jd1_OHAGPUWx^NV@WJL#XLp)-*hT)cm_=2Gx$ z-`?Q|f~eNQ^3$7M`+R!OtkfaGI{(Hex6;9k)aI=+Z#QkO#_2%PZLhJ*qZM>&(srAF z6b1#}pv;@!Uwx!4K7N{T^}&sCNX9m3CR#`EnCY5886ApK7wSI{tf=K#e5gA8X1A)j z#GvC`$~hK2aWC3^S&-vv=Z50_xj+<^ZKw%T&?*`Sp}KT_{<=?dv-9rCY7Mzr{^T&C zp)J1^VIW%%^pcZTqD63{$l4s+sW35b)aa)e%$b!Ag#W8X@?3y!{jitj+k~{ zFBwJyhGow)>pHOaT_06YsPU-W`}0`_@k;7;>$~Tm2_R0R^AM_m3_{!6pg;iWpzQ=e**QFNI)~@9Kn5ns# zk`S&=m+pIBd9N(DmeRf>%~VmLL|iSt#^msER&FV&9t9rndzR7KYjIG^DvDDZhmo%3 z^uAa{CsQcmhA=)eTj8>s-uI{(yd5fDV~fjmNZrKrXnB_orj*o9Ak$rBaO1s;g()@x z6@RIaBPzKEfXv*CWhhLzo^70RBbvgt>Vu87urFEX>>>=0uQUR@HBP5;KpXVNy;n6wn8Awn97|BE9(&Mb=z*tc#Q5rf1balv|q zLRGJ9@v=69!x%fU&Q2Z?R2s0u>bA+&cylwj$8|}V5jGDF8`O$WIlekj2AXzJdM`3L zJG~%f9n|H1lRM5CnWXnY``8YXiy-@A#gQctDeDHQc#7>ED8WuryyN{)Lj6w4+7rxE zMk9ZQ(KXPNcLvTL8nvE*zQfeI&!v%{ZZm0A3jR8{0~n90$xkb9 zAq`5R8H|#rpxR4b5b+a-E7A8BgqGyJ{VwS1`IBa4UYUqmHSO!l{gX9_gEhD`!p@0( z^JugU0Bj(x8d}KkWxX%TFa}o6&$|D9mNnx_w8QecIEf0KB<1m@uh_^$bA@v!T(NBvYmgYDHssuCiC_CNMIZU(*cg4G7sOynYHBT^vO zJt&5ja%Qe+nnv6l7C-+%SNi<9Xk^m7PDyF=$z{N?lP9xmt#7(9ae?USv?s0JaG&i& zqA^9&N;YqCbo`DHr5Dm}oO{CKDu<8}bAjQdP}WD?Kkr>B(9!3b3) z5hhy2LXK!Hn15wCm@J*u^bvMR;rs;X)DS#qlwbN8picR9iL}sDu4Pes{qr-E<~8X8 zf*!{kXY}kqSZ;%9SP&zO$OhOud1y8e-5w2q7A?_P0b{CmV9XI1ql)*(WU!+2#J$q! z7b+sE7xc)u7fM&Yjg+qDz3${$2oz%sdsePhlhySKR?n`USANr>Ls|qKw>W}Gumd=% zDmCm(Z#t5lgPgjyUU#ifJpORLsM(x%4}sdUdiHe0MKRsfM9eZqK*{@NK4(c?_*$N{ z=Sn7M5>rr=jXLP7ZD0m*<1R#pL+W;u5DxtUN8t-ckgkyqaejyO2yM-RgXL5mLMfDo ztbY=5PaxtBQL}Rj*}s(_DlH!M;|Y(njD1ETniOUCAg{R37n&$q>w{<@OgBsbM6NKU zF9Idh%Nt--4rj`=28ExH!!CA(TDeC~aOOO5Dn?jedzF$3~o2;^D} z5n?fTs@Q#>$;2ug0cIs&fMr|^0$+sH9x_Hl+PikEGA7&D^oeNaa`hFf&M~$4$GMoM zad|FATokl;(#o38h;z{l6K_}a0bhHJ;iaP4TE(OyeM%VVNZs5<2u~u`0TFr;?O~qw?by!xaPuI_tky6o zvMbIGF{&)>vR(y3YGy8I5Hvcn&J3T2)wWzz2bl)KNo|?kWuI2EpLW#neqdyiY>@Wg& zWg}GiP-AN7V@~c7me*ZPOVABgN?fFBwqJ|1mRg{K{?OthZHNwwVL{@doZqzP0-r3M zz=Cz|CK-%9KVQ*0w{nXDTxN!SfaiJT4r6qvkGoZSV6c-UV)aJT(%p1H^gE%;MkDV% z88WSb>gs*=gsC#^(Xi@3Cttl>uO~w4o?$M1vM?-vbb~0JPWdE@>!T&o^CgOz*J^%y z%fnQD|#!}L-I)!q!Mjh@ns6{d9!0D55E2beGW zG$M`+=U7~s@$J?NajcTSgK=s!nj(++}&U@?5vbq;P_O+NOl%aOY z9W*Ko&i|hRc~69T_eNdNUVRcu^`UvV^NZ@4d>NsC60=D)T(h#Z2iy-1C5!P9hw^ZbYNMX7N~nd?6y_OxeKcxB4fU5Uau$21!7<+5&nmP-Oqrj3qLZ)o=!Hkw?mSWc|l&Q?Y&eS=47NHn@ zC}>g{hxMu*tLd*}MF(V`YEB>c5a)<@lIGg!^`5>qmgJ?qr@nMUy!w&IChvxGP-Fa3*9_@X&P=4f+K4ROUamhH@+dvuzjqV>2GKF?SaHSzb@fboGky?NOixFw`W_4Ka!Fjr+c``!Slb5^{q0l-nZQ&~!@d zp%7twE4>7Pq^^QrB{BwLKr5PAX#nCdq-T|(uu8KoPo9A(I*LwD0vV^s#M5@9_H%4f-i+i_P@kl`#S2}ED*J_I zB9U{gllKjQ1KuS%Ze-GORg&bqzkZbMMHN@(TiVRtD$80v)UC2K*5_O-w_^mS@U8}S;dk~yrFl=66^(c=sQ{&=)RCalZ{{BU>jXk!EJ?C{W zAXosk(5WaCV=U77>_WuJJ(ch>yiW*c7C5#P(ReeMt423WJkRFQBy=Z(du>FS=z%X< zYBVfG;Vt7WwI$Wg;K>Cluvnbdd^g?F4KeTninDXUl~v*i{@snyyk4vpCUY$q0FGZ} zGv_k=c%ex@{;_jGo}m0RUG!2EKiEdV=ec3F2YOTw%_{L+$;b}$8M-E4!}Y-tMvXZ{oSth$x5!xy?pb{RqtD<7B?-!5$=E6y-(KiWI=cqZj&E;F z6u3~?o5P83z7JJ0gc@9@m$=pH@AL{A&(fr%b23l+nF!wNKION+y$vF|^-<+Iv)+LB zHDRN-vYp-j`kLSalJaK2C?e9sV|`I?^DOX}G`?l+oR~^qXw3?hyXMNfMCv%_)7A^~ z_hzC@Zt&&JFs3Q=J9Q*W_m-TlPn8#K=#w`)TwAw$re9I{A-Esz9-_3-@Ir5n?A?&1 zc%GWyxaFgiJ3`?*<4?iEel%RT-;W-U@eh9}85m*N)^bArG31$y1cS3Hs%+(>l>(k!lmK4VH)ACf z#{}pDS=3&F;pZ1%aOU{tQB)DSGsQFfRT5LG zGk3CxsO9;mkJ*~S%mm%(>@>jN(j;Et9hD`!JjwRkgL0{M4@*$su`b;0Y)&ru@sKw!aJVS3Jn_F;b%XjHlK27 zM(r+#7t)kvW#okth%2Uf3%0*pW{W4f_+mY$t#X}bo*a3z+_y4IRItmCZ0uepI zJ8t?y!2k4frED7d>tKsp1-U^lZ}9!G8_X*b+d>)_^@_ucGK;vkcSooewb?_#By~B$ zmo9k4i*`?Isz~wHbzD+x9l+&_ixT0l7*@KYlxn9V^OCv-Vf&_F-K3C)ux1g2uRDmm z#jcJtJnUA?B|sZqWs*+TEqPv3!<(T5-BRHOBrobC@hpB8; zMj1wxxo5LS@(P3S*%5tBX#@L0gz}@47_bl8JKDA%6eTgsC51@a0aos!cKng`b?B;_ z^v?SXf4cl=?o8IkUL8);;~45S;U}?VqaL>U;Pcr*U0^S3X%* z390>T^!fWcxU3z0f8FaAYHodoK;(!M)?M1-#E&JFKOJDJSKu*q{A>fJ!T(6VKVR_o z&3751hC3n`Zsq&?&%Z}}Taw_o%s-wP_@fK6b9?eh!R(CC`hRIa|MPkTqTxAp)3Wd8 z^u8~5|L4a|53i$d@76eo$0sWVCCuIIm`3wWn&*Wb2+3Uo#l4 zcZOBFP<2@7AItAj&hQX~fkY5hOPi^A!He%Wu0DAA{}$aP>LP?uyKwr6b!+HTrrwPD z&D?W=97>4y=Pwp)p3;H!oD_F~DMJv@qp)>Fi+PSqWv?$vy$%>xvAHiTyY-Jx+=oj6 zhYt2EBqlufGByD_%=+fVP~fZ_4l(U6`^(>ZxeNkq%Hz%=HGUKkaBK)Y zyMVwI!r>ye$ixy5zKAdeQN*Sf;ct!PXB|y8xBwGRN%7{;4^FK*A!oKEs?aaXS?l)GhH;CCW^o~{>PuhEFecP26GmctSR?M zg@LXpg+qtj1`Mcu(J8JG%v6!?i1#2e@;?*%f1(4jVs@?qdr>WS9e-=Nqk#wjX&D&h z_={6u_lasz5IoQGUt#n=-qkJ;Vn&LL!LgC}42&7)%X@NQc+URKQ~p0*{wJva@hg|8 z-yqgs3X7r44cbHDu~g8uP$zsJkH>wwRJ1kdO5r8J=TGqurZ-E}|o z6N}s*p%$Y9Xh%yWO)#T z&i|E~-`zuGVFVWIS^mv>!E0P7FJ6oBz!ttM*#duV67-_i5mUPajD!)9+YoGO@X8oohTU@ z-UX8%Q918s#B>YRIWfbxPY-`{_>0l!+*SqvX@}!;-Ek(;)gUxSDAn>cv-cY#r^!Cd zKLUM?o;&~a7MR|rEP8cAbk)T_aqNrN8u# zeUX1|dIqlJ^$qOCsDDzsBo6~vD1@eu6ap>)%C#{)wbQO zh3H@aL6WVK5}K%>N24`p5b~}G-MLnG-s4>012+_NFicB~yV!9Z3IGrE?tpBFP!rl`@0O0}-PNRgAf0F!MX>F_dBF77nG(@( zTJkQ4ZtCBL6bQUKt>s1Q#%6KeHCd$3%mK?~0x(`?HOo#phFj3!zh3B4F_S=Gi5sNv zxKtrqC_djDCdd&S3vdl}6F64iWcKb!Ns0=WSJDl#fEN^UN?G4W4ER$mf+r-9=9@$q z=~TmSp<1IKRM4Oa;J0$J@Y8I{Suv`D#?1^UpH z#~}20v$4t-TNomzAkkKHeKlxwn1YOcPQA_3g3Jz{dlQ1a%7Is~C z+2I@okpRvqR<=Ro5=bu8{3;GI-^zlk?IkNKP5TA`qhH`;G&{FCaw=5j8LDw%U z)lYY(p<&9g4CLxgFuhWGqvjS2&!TuiEjiC}bLvs?ENX9e=UwoQJ-CIxz`^eqkU8Qc zOzP*@qZlia>xCY?5p~nH5)!`ksHk&KT0cw_$s>L)n3_&@m)u#7w9lu}FOv{4nRc~^hs z$g5xm6|y`#B|(&nm7^or5)$sbpczm7gkkhZcFDY>yRrCr8EgYjpO&wN!g(ZQq)tq- zdBjH{OPw!_%RDjXy>?8~c4}2JYzpVW5>^4U*k$B^kxYe?W9wqDtWvgyOOB5Y^=i-s zk>gVXMS09=VNJMJo2!PsdHVjP5buGPq$v9}S5=E&Yx`63-MWP$<8N1LV@VXx{4jnL{+GVvzuIf^ypES zrq9m)L&wi#kv(l+N|nzbYs<1(8d(M>JCJpWFJMLqjoU5?cxy%`yyA-8mJ~ z6{S~2Lb^M8b6E{^6~>#R&0g1LGSJRg^fn3A4E*>u6ae8US{Yja022iPra?>I7crYW4bzvP93D}Ay>>6rEWfZ?`5fP6@E zXUsTlh$;J6J z&uuuA=87d_EQWKmu3J{*c3EN}j08s=!?xJXhEzedxM?oegK=+4l!`XxTzl^sYz0MQI2#Lpd?*n;Hu{9Zzeqg|rT|knRI$$RY;T_6yt00N z+u6#}V2nw>=(8il#w94LUR?}UIi<=4fZ|!f4JbY`F#;~xc7y5z$Nr)!(N96+iNG6y;$u#cH=KtQoto`Rinn9h zXO+6ji=!c@nVB>V=0{H}b31Hgm%>D9JhN)9DU#<<;i3Lwk*v-6u}?|=MEh9Fte5+1G7eMYZXK2GIH9Bcc4~<-&N3yF$4sn*_G`}d z733KmNo&`=9(l{!g_ix@@i^Rlcv_;B4ETv+o05^-a!?;AWxE@ye}a3+{vqd+RYg|Ke$fZEvgg=IYd`*C}GPQ$uAX15l1J9{%UJ+N=&Ts^R89 z-NV%0PBreyj@7og;}7zg_1H+Ycjh~t=BU8}K4xFJ)cZMert0c#7&mk-SO|i{E35&` zHrFMun$TYSZPLmUYC*1vpSO2jM$$>R1C`2ic;vh`**UK=8K0#^cj8rPZS_8~{3#d- z*qzKqxiR_Qwvwi1S%w_;(}& zCSk%51WCfE(@@zoRA#S>o$kDQJorG((x!5*&fP3EwXGC1|I4GKj8C!cpA>Sms^3nx zYdw3}{qg0c_K~@Vjri0WL@m^c)WPqMpvc^$ zw%c4JZ8A5=i8x8AhqV$)%09d{w0^ z)fH7@y@25>lqb1-uQI36NN{HpOW}qB9A4oT&)w2(44)rj|H!V10~Dt+?Fkz`n6MOE zA7(QW+$C&CquKcv#HUToRUhaIMhg4(*-;GENuE1Wr8%~q>|)_$I!ba3TpE%R<=v;Y zmm^>814gm`=sA7|#Z~>8u8dsR>+|@*F2lzLxPJ-}0r)P*PHjUGk)=@#?CLZO6QMAf zXo|c`-eK{o|GGx&F{dy_&&D&SdkTy~AU~=f^|qcV)nPpBl6>U$XvLwAMX`5oW&=07 zq;KOV^m9sg=MwG|;|4J)ss5G$yXk;|%7Xq_k@>_qkA93vgmy&t!NRi@rG7UnR+(Bb zCMrrfT0)x@(({Ba$7nPNT*n$CINS!f3O#=sBGjKQ2J~hyGhnzF1m8f%c)B8z*LImR z>H^vg6{7msbF|3tgCZ_`aFZfO!yrw-KD^Zm6NL5E1<{E?xxQXWVeb9YoW{X@f!8+Z zgOc2rd}DV*(2s)W;@9OdZ=Jv|YjHx}+>|pSi}ehO<5s4%-f`#Ej)2EgPOs_p75(NY ziIDYLiSq%fE->#$ihlHfrp&4hfgLfOy!hj>I@;oI9wRzmGPXeFf(IXWceb9LrIvja zUG-Di?816JK+_dfd~6iPISEqH{8!dAR`(LDuO2!<`D$as=Fw3zE(-GG;XHjQ4VKvg zosWTHbbucC6k!FhnNqm*%ZIq=CsP0=@~(pk)qjzr1j zwOWZ)n8(pxy{Rn1<5rL%E}=*9^QgK4Xn1O0>ww2*h~j{h<00I1+VLTAe`zi z%+jV}BH%VxY>whX!#d_dBz!v0-5%&(5zMGY2A}K$lRc%XticlN2>4{v!D7n~{5;?G zJ?DZz3!PQe0fnEFqy$m~8Q@7wF3=RW#*3Ilw*uLwg*OdxJ#e%SBa*6`qxB4VK!h+y zBwvFvB-`kj?Y6TO7Dd8^N*~il!`35V2#YE&CA!73u1k)rGc^_u-wqwcr!V}|Tfgol zFurOPU)-UUCZBQ6Z05s@3&@k7>X5YB;$$-(Dpl&kn9xCs_X4839&BRgy0Db+-#+ zVV~ky1SP|+3w5O{T|hZvgO-N9-3iD=AyC??cOIYm7m1U?6fp0K5>2hYR!kgeI|DLD z2r$QD%cF)Wg{G1D#=SDQd8SBHjoHT(>6iwIdcHQ?8e|CVA#7=x^@2KxPiAj7Nf}iY zp;aZ3j}9bGl8VMq@Uy*BAe%I&d(k)OCt=$E>?mm<4_@tsCjvf)30J*x4!s@wIo~*Y zk9v>+o7|jj*q+!{YHR)|{Jhwf4>?CusOK2S@PW|rJ_s^FDmFX~2?e4n*)cCeoOH*n zHOx*yE~H$|hSk250;BFa$nHy^EM<%?SrOQkS>?UL&JU_AfBC3wedkVObZq*@#zsKS zejbk#RL70&ocNq~ODD=rDd7L_n(Lx}(KmM-WA9|OL(@sYYjaJ8v=30e=73@`a}5Gk!uux?Ct`#me!S16W#B16DBDpQEW4uY37`N6JLZD%&PnAo%tv}fZ zps<)Bovz3X&pdL~0Ube6e=u1wCk~;9ek_lsPQKu_8Y;ET@Zg>YlEj^!0ir`&nnG5# zU5QsDk9D6Mxg|HbeA8<#ivA1&$@8g|#s*!xl3Sa`ew2I<`e*N(^>f9xZTrk_-hLp} zzXx%f<$JsK zqnGYYtfp#af!j(9VCZ!*-VBx9nLuIa#~;+r!K1GRb0qewklCy#Lx^kl%gtDRZGd#?#i-B?x@y7c8;^pL(Oo$A zsx#Gw_M7XwX4FOh6$ZvPy7{|=lb%F$MRQx$$tp^Q*be0CdRrQ3I|DU{W63FchHr8r z0eGYXDfQ$S&z1fEf_Eik3yhzpydme&y(kB(?oj035XMpu9z`aTzWgQLA$U&A1rVVk zP4++*z1y9sM%yOiL1r)weDT8>s7Ej1c#ksdJ*mt>e*AefG_Kri^{=_i&-JGhz;Uvd z(38JYHkq9{CXaIZiZ+Q*8v|unOTnZA#Nm%QjeXY)T4J8FI5ocJk}cm^Q<;hN+X5E; z^35C0ek%eaD9O#3MrAJBWt~Sy-b^)U_DMq9K6zwvBGX+@Ea)mNP^@5};fT8ciKv>B zl?Y-?Huw;bv%fmW_4xMs2q*bZX$lZD$^&hdi(&-s$IjA_9TROz7v**fa({(%i~i}( zmi0k&Aw+NNz?E(6-@d3&AIzW&B7^2!@v#wjQp=a7GmR2WIp^)j0YZM3e;l*8Q$xz{FZRT@TZ)KSf z{}*VwdsIghKUsCvxu=I*THn6ynty+whn0dFNIBYxS>R>wWwXz0@738{o1+7;!SE%@ zXDG+rDE=}6K_aA|-1g*UkwK4`K1G^(S#c4!v5J59wO8(CtklF*R8(EHnQ?%GGAS~& zDJuUDdv6_8<-T=~Dl)GQHBpt%E46 z-hm$*hql0DCT(_eRHyAWelQ1-(dFDsrni1`2%EVKpDtTar1bl?ptN{n1}3+Anj(s2 ztck;1+y7cOlBj8k9jEA3_mN-4F+pX1AZ2@|XL-q-{O3|fj$)*Jhv-EMSNF#wUE!K1 zz3KAjKXw{;PFCklt6}R0$RTwJyqJiip^6&JU8lF8;JTW)nbWT5>a=` z^mO7fl|BgoO1Z!ZU!P?Th9LC;Sh#PolE9XT>`Gf`-)GZjkO=Q)v)zkls&t2wJAkcz z?ZJzV60&Gz2}4U3zA9nj^l6lP%;3DK5nv+!2I`9bmK$gF!bqwzFOn8S@VOz4It;g$ zMjl(I$sisXx_5;a%B+Z7OhI&76rkk8ee?57*>#3R#>VYY%Yw?OCF zumPl>N#I^`xMEE6LB70KE+6y20Ykpx-w33CWd0%y5`(lSL*@SQP4von*zq}694XWQ zS^47|{_j`!==oRZJju_8dj4$^{_`jHpS^gHCmVnMrwjYL8}U~A zWBfN-i9gETTmp(6{S<-g|Mu;{rnp!G?@ecC!qWKvzL9_VTleS_)lA$(bAP_wzkTI# z^frkasIdW$sE8BGmn?{);WK<(m(I~AFnPlem*uK zH5b79{Zqb2CzbH%tT8-mEgG7vjG15bZ4pM{IGy*2rhhtWf83(KeoaTgouo=~G=!5bkEjaAtTPehRMI5vPz#V7v(hhusWy(aaWb|VtriKF$)cl6Tq zi2wHT8(zTWGmo-N`~B7ucX{x~3#1XaHUZou#bl4f2rSl`80WqEcNY#PypupHt$s$? z`qqE)lo7+DiM-2<{hypl9{4w%`BVQ+LjUL6c4vaCbk^3p_#eDC3LtJ*B^b7b|Lytx z=|k4U#CF~N(m?UgU;M|(_}@bS{|5XUq4o%t|0HT4u`eF1z4`F)KX`8*GY~r8$FLa+ z{4WRYfBIR@mne27&r!YlGXVent4@eCL_8*Kum6pU|L3>t+yDXw@nbABuJ}K_kN@dw z3AZ7CIHIDUt^S|>`hWb|iV%c#CLi3tML#eW|lfN}ntfdJw8|CE8!0zxAH=>_obhwuMpBg~8c%|=j; z|NpO?YnW@k^M6-ANxB{^DH2UfS&=Z}KPO$)tm}0FtG(2ql@tw5TJn)z1+Xa)ZIuBC zJb`cb^Yi~GzZ%9dfWMQ#2f&VK(d$@U>V2InCp-u*QtSj{q~iVp8U-9-`d#b4&F8!} z7FPM`ORcDA^ZD)Ch0W*x=yoXF`Bg5LSRPeu%=f5l-NdYtDF?4fN_ob3=iRkD^AWB_ z07TQHVn3n*iw~GnZP9e#aPSVm<=UMAq)WM8Ta>a$C?f-U7zuvkqA3#5NkEtQ;F)mU zBlWCNoD&Sa(Qs0lbfTv-058(q#W6-O-(t3&5~Goda~}rHmNZZCrd}k61^bd4Ag*~v zoi}Kt6JDcn-oe&xWUQ_O7iIKCVIgQo(%!bG{W4PQ^84H=xIY>BsYYk(B^@eLa)r(y z_B`=Fu?}PPap7TP7`6){`8yy@G%&6SMw>IUF}<=z<2l+GAj|Yc4@Q8Wb{UmSap@DvH#v!I>~#r7h;VC5;i z8`5H9JK^Q+)Vma95tbXgHfmNKcL? zpHwRy2F;DQ?|O6Nn9G-2vGWDU?{YY{Jkc9ZL|KbaYBP9LYuj1Qf}uR%fR;OX{Dz~?DLN(u%OAR{VX_+|L42@?UjyZoZcH+W*d|W zr}bRY!a$LbYd8m$_H6wJe77G`fs9BiaHSH7ejLc{cCs;sDkX}?MMWZ(i!$Y#f3t`B zklr?Vq@LTC`C1r|vGShzvxQ6YareYzH42axfl0!v>Kq@d_Tk$=!NKz=9(5FT+?*q- zP>TMr;zjOyH^i=|$zgq}5sYn_V3vcsb=LG6myIw;9`MjRGveMWV#+)k2V!_AIG=y* z?pMx#%z?aTK760k>WA>kAn(D7An*+plYq@r&Be#TYNU`XMxyDtVNI{e`1T&f` ztE6wfR?mLzlMXI6#IS@0Whiv-q>Us6SBx$yaN2%3Vq%MKvp@D0L>LcoM@78aG;EIw z*=#0mTvP7W6Z+ErPS?$igm~dA)?ZJ^2@Dc3{!lL#FQiR!63mUx2x>Mx2mhYt{!h9H z@cJ#{;=(%Z5p?;EMny@%vtAJ(oZKS4uLgvcmX;khZ~zM!>bu(uQ`bq*VBn=~o7@J3 zwhJgxXtX?tK~(`rZSTZCl?NwTZf^eNU-{`@LXBLpkN5cd5NWG-4`5SjFR zEV{tM5PQL)alLS|DRNA9M)XWe2#;5f`Eb{c@z~+%@cRoy;m5r%+NTq!e!Zkw>CdEM z#$(7zR-+Dz1qE)K84C0h2L94FGqa336JY31F<$%`3_qAUWBGT1tYbEoF-X>mAhT_3 zWHUiwGScm&Yv;!BIEjd~@P@D$O6Zn0k2m78qvtKgsLXJ)D{W@)jQQ%BH7^WdCkc79 z7_TOj8vJ^rbcEt`TKC?S1>Hb2-AZ?hvmV8Glhj-_7Sz^Wbt&~5(Jx)52kz~=wsUg2 zsGIA)92TR)6<6~Pfs82vJP3g~o9PKJ^79#q7;rB-s1srAXzmmdgsnOdb0@ybcwlaE zsJIz8rcvkDD>Zmjip>|BOI-aXn@``v1}Y?U_S8laum0J#|K21A@Sbi`z&l>+UzEt7 zY?wt|`?NTxy8I!se9Ncb|NO5|NYay&<)1|$hg`ELN+%`( ziP5jV!<}CQC+Lp!7rPy!(^WtcyamMfPnB3%*O>L*>Z*#c%4Mq!6l)(|YcBTIq0q!+ z-55%GN&rv9Tc+=bl!w@^h?JDZ%0HX<-(EdZr!b6hmgY;rsuBs>UKah7I(FjrqhBBg zinADyEN~(hMZG#LLse-MGQ)tOEUA#KM&o^%ArJgDU^S z`gHq{#w!J2AId?*p6Xw+7eqQAxfD-LE4hx{{!XpVUxS|QhSYi!6CC7e-`vrEB|!A+ zar;Ccz^2MRyP{X6gnX3!FYxZzY1RV71e3`-1+6+qjjc;7vJ}=+LH-sq%k7{pxVV}J zKEl5m>U?4(`EgLLJ6~5{A=yT`6fiAU&1I&9(C#U+Y1FQWybww%TRB4nh_+FYl;ID=&uhrT&uVi8ixc z)U?wg^S3E?f>E&)eg3~ZE{vy9jM2oaND+lh+Fd3Z(of{q|8kvh*}@kvG(u8EFKjpR z=!u<-9^s+(w#CYU0hb&YF5jz{C4&Tk4*d0Yq!)#0JYcn46GQRvjVJzO;%Tx;8PD@U z5jbJ+FF*A*hKZ}swSz9ztkK+e2Rny92rK7z620`dQQ~;h}M#!Z2l-aN` zFmrv*D#UAhIi!S#d$MCx-RkJTfkr7QjF4VI28W1&rgVK$61C$>?mY43^gz|RoJ^8jDWUq{#KNp> z9)~toDb@3RAM(nX8`RD3MxRvQsHH|!>G{15l36Yko<{uT%yfCWd!D?5ouudybilEj ztzNFzmGtys8JF#xFwE0^mvx##nV7&r+Az1ZViiVQ%^-CToEsw!%XzoB!C<+wqOE(Y zY;(RZW%=sn>Jp$$ZyTk4jZr(4xw`9IoTSBL-BR0|*XixIk0b@K=a=2SwS#T&rJgm` z&&OQBcQln%#yZ)41b`U)X6yx*ryIR0B66uW>>q3f_81Qi4*n>~sZJZa+!j>&kvGU} zUXi3a5!fPJTkSC{#e|F+GIQ+Zk0VB{QZC)MUNAMjU*P61M$XeCbJbzH%hMMjJs&B^ zm94?7nC#;$Sd_gl-WJVyy(^h}uhw*T&NgX;suCgbQ9*lg>V4vw?dD=~zkt)4ZuGbP zuHWMz86wThP}{dEt=z9d==eHnFFsAXZ@=Y3zi*zG8MW@4sm!I=7R6=EE!H;d@FRWR zB2>Zt!T11|!k9@BhcNZeVJXSjqdP_NiT*$-D4N891NAskFAp9Ji~ zI!R#gxRgf)9pHA4k-Ox8(x$0+-j`MCnXCDuGWMKBH#fS4P3*lti^hMXEB^O5M)#Xc z8b8n#&q&5a@scnRU=6q_6VK>ws~oP~svZx;dQ-RICKBSz(wUthU2HgSK+=`?arpR~ zl=0x!`Fhtu%Lm$anY(8nrj!!!1)VA{D&1n^h~cyq*gDvC`qEy$HnL-nkjcV&d}1Me z-kboBrZo7w*LS_G>BNz;`$eZ;YPw|}3L#(Y>nk633)CYA<0cBT=3Rp+N0tMhZRP}? z(Qs6KA9DWi<+7=Omg$<)t4FV795p3`1eNDqRVbLotj%7|M_cU^w2K~nd8*lFUAr** z_=Uys`F)@mY1XF^tUkUY`O1OqcvW)t;Na@ne2-u@`?CXnwc9EUr}O?&TNo>hLpW#u z!ZLNW{gm<2*%|0>G0EJrt(QC%eleDP*sXcCVs!@iz&C+c zvl(V?<|2Gg2#|?nV;tvb(vNeM)y3@?JO=S%6kk0gHN_2rh)24t?Lyuk z46=fY2O{pBpFbk|Kr>29r;vFUc_DATiwn;c{IhK9tlq$Ts+29h*_WeUu7GZsoXw5j z_GE#Mzdo#R5!e+Wz~V2rwKWr+ZO;YTQtgXaW6SQW8B<%*pu)>+eJhC2z`@w78rk>m zxnR3eKlVoc8Yz=<-90UkSC2IU+XFeRFViT;KT9w?z=>MXJ9thqn&Ewk7pJGR((h`A zYC5X?i_%_a_E=r8sQy=$?c4OeSBOzjY^ruNZpznbWD%ZG4_tec9QMo%Cin)N^KRR0YYpxntdtXzDa|~hm7H=;XL~FDT$I4{ zn3T*)#j$N^iFNpgf(`1bNhjYoG)+z{?CwJ}Bk7&@xkLL52hV4CN@$;gqG~d{{fd<@ z=OAej=x#C1JD|y*u$UwBo=IRSgC^3sPR5CgAOtI~AQsC8Luh#xtjj)t4&iEiav-%R zR>Tb?5H-5)OVntv7`EY_6%1b%J+lXAWfJW3J_3u3+b`q0aVl&_%?^b15l?~X_GNDl z*9de^q0p3hwb1J?rslsjmJ%_P?~VmRnR5Ay!M=SEx?b?P8{HOmIc+9WY!0otC8^Gb zT_K{?FHcilpX$$MA((a20pe(pOCCT$_;Eu8#vjoFQD&g*bt?BJD6>W-=RZ8%1iMz~ zpqs^8c;6=1`$_jn%`GM4!H(??U@^JiwS;^6?~1!DZ!8Y=y{IaEv){sz5Ua`69C5_@ ztVbARb41|rYSN+}Sm5%b;SyS@>Kl;G7B|bPl&xvc&4|On_JuxvpT9(u-_CC%aoD}3>zsBo{DEhh zLa0(IxQyd*Bl90-mv847?^m8r){f^OH(Lgx(DxV~7ZC-fa9yYO2o_{eA9*PQ{YEhL zL~}bMQw25EltsvNy_jT}@|>;14&QR~Ir7#3R{{f(;4)v+`g3w~^jbMKNQo_T`y=l< z9evt{&oq2Zku0vk$sFbF!k4dbtZ;2N`}=eR$(~^7XrGlg6x`ovMLy1FnR>6gJx3d7BQR5%)??-W`kE<^WD>k339w*a3s{P?w&aU@ye_HDPNFW zgxk9ek%2{bgOZ0nS!*y*3QHU~OjQjJo8F?OzIB1`NXMDoux5Om!J6vzy^j%CPd4op z4R`YB(Cp4tr{w(1S(%Kd3|vETjOAPaMrx%>g^Kqo|6q+uiKQXE(W^BHs=n*&ucD6H zW&y`K19G^2)t}sABpH@z>{B z&8S+3Z1bXP)5Us8*IJxDCRx7g($^Zm0QG?wjV@c74bXq_&>P=v{j*|14_li%wT5wcGgw!KmAldw3?ipin!0Cm(2Av1B&(mZvYG^BgKnM~4QCQ`?ciuGvwmW)sd zx}m{pl+1@F%YH}9?sImuAEYnarl6C%MBk($Pc>83O_DRe_S<^cGxQ3l%13V)N<<6S z-I?%0m3&cMF{x>y&ePf2SULHiXQo98wYJ-Fl+dg&7(C{t$_U+Jp$YSxjdD$qx)T?O z9&MCsp##EQ;6lz3r?6#L41O9J&b1#38DI0`w4VM@9^=p(cFE*NUUb)SH>V7gw^K`g zLwjyGxX!83Gd}7bYyQxk5Z515aD}wx_0m%wOd)2J)^EA|KxBx$ICK~&(k|2;yTxG} zAVZY#rf|9~RFib9gEv!yt}U8}it6|ruJR4K4rJz_l)IAAkEEXEF0DvSIP7xjq9Q&+^kdr8ZpR* zW^q*&)tc)K#Y3H)p$B^D z!uleC1;=c-q%-V;5s$@rh_w;B#mFh|^I@uw46A$E1eM8s5yKPCV7DX?(!?4$(_+uHkAnJDEBn0pyp!Ts#@^_< z3ae@Avg|s3JgJI}lf`^LsZ_WAgT?oZtE96IkJnk~K|cNXj^eA*J=qKehVo|ixdO;{ z2P*jn;zPPJ`_?sE3C`I!cP3fx)co2Ejmz_&lC5ev9#v9U8C#5OL|#{|B%3SM^te&W zvyEp%uTYdQJmTc8HaeHgA3Sf;*)>@+*q5V3s6d>0-_f$lXKwqER^Qepv%g1Su=SA! zV~t(hvHWHFi2Gh5g`~pA?NcK2+-2_>uckH2&Y9}*c>07U=zm%6TN?IY`ms)U=O&Mr z+pP;oW`QP6h59R^^*#ER=h;nk?TwU1viaCOdzI-z+9PhQR{=@AKg-PHFnu!{*VMC8 zA!~WK$fbMmZGI;L<;1Y?IQ1uPAH{o&vW@6A<^r8s94g$nW|LVTM$GDjos0O-X`>5; z4IR6t5jmuCRqvzww_bW8onFii7o&tQxnYnZt2DV*NUWGIJ zEf1_ema3mpA#Lg0g2~wXw!60AWEfWd+LZjh<>&ss0S{=4si96{3rT8; zY1y{Dw+zE}hd&e%>^lWU#9sZdRGVY>Qq%P*^ZB3Q4Rp&*hH1l|Y-nzJ$6sAtsI0h5 zY}9p*O!>i~_c*;QnWwN^Xy#eXwVTO785*j4KH;|*xQB0FxNwCAPo@9(O@c!Ut?kut z`^g3m7c15_m%U>)(douyO;=pbwhGx)C7RVWp|*6P(IeXXs&?BIY~sfTPUJ;2NV9Iu@NnL0AMb$As#=7Ip+ z3D58e2=er(xNQ3ZYWzw&NjtvHduKd1l*=598*)tgvi+tcm8QUgFysKSgzdgt_C`&PKTb+VVlR)AJiFk7_(o)a;w~t;X!g@#^ED z+;bnW_6~Lu*SD?GR!J_GWDDm^wU-II$nINHb#3nUN~|<9J+1qdjR<b8J(g!F8G(h-Jcj18N2n)(bnTjMlcpR>g?owv@xc|_8e8y%w= zin*Dwv#PN^uX5$5ln&T9NW*3Fj(kki$vU{^z(-$~p1~-)ufwD58G=QBc0rP>90lNs z#nQLECoEHwg97K77k{+JjumWg8zfnFjqwPzJY==5H0Ogpb`5IXQbu)>`;S9oY-r1D zlG{w}U}X`f?OBwGa5ju^s$JGS9WFCjyJ)E%UlhryIXEK?QE!L`%MY)j?DT|9Q32Ww zsspxWg!Wv8+Fz;CGwDWanI2Cn=xk8wD<(8Q$9j*2+$eoQTUHT^ zMHc;@(|Nk*HbdV$vmeSmcGRDdCVhGPYY^He0_!%~Yj1B1J0*c-wKax^J4xAa*1JG0 zbJzVJRue7q)n>(GW?o8IQ+4I#(Z%IX{NXyxnA%n_ui|BLvB2cS%2BifI(1f3Pe=Wmm2cM!5k(b zzk-t}y0JCQh`(Ni_1Y%5Hb4HO5ed~fP|H()BBjqx? z^DjA{{?Yl6T=<}qD$jbIYv5pB@@)PchAmrEdJ;3r3{|%!g?DSDGoz|txl^&oOo`eM z-ypWjJejj0LCs=H)e>av-~6wKycF_wnwgaheXu)HBmIuk z+f^Cy{W`Y|#W!tG{^l+w${t%BaIT4|Ip7-{yq8nEGK^m_BDHg1USu1^BWkG4Ow5x*db?<5EsEQIses26u==7+@IYWOc#_Zl?0!1* zG^l5i`=rUL1x6oIkWUxU>*)goM-0r*&4%T!gBx5k8ve{WzjT4@!TqO4)hBgq1Vifz zB0WSyLL&YuB2CEE4Xm75`q)Nq)=jBu4U9z)D8$|19 zL2Br;-~HSMs{-~1HLo_n&9*MPpAjru)pIaxS(Y4>etRcaCeO$F&s_K0D|cW1cR2D% zbwqA1oC9~X>*yJtm)kdN+_PvNeo8)g?NVhr44BGd=taNeoggwn*)Jyg?wxMQ^5?xB zTe166cTAvG^y%WQtZPFA-In(#cL-YpIWyJ+&pa(XpTe|J=~t-Rts*Jv^(>W620bb> z2{pSac>Dz{T0|2ym)SyPJAR_P^G6U;U|&A0pCUZy`mAo%^z|LVBp}E^~Y_sK)yv4}bMel9w`xGYf{ULGW0;YhyRFcOyN>J6CHwZaUQxPMOk2Jv@iXx+*iR zUvHKsb~w_lT%Re*frO@!QdA79tvgdW|Fc1YCff^L#R@Ey1wXbv0Lm?xEk-M}g0cLg z3{=nAF`J<|7qEp_1})P}+gfggon;Ns&3 z=g=q6s+qjb%dBQDM+mXGr&aO2W7tDF0<=bi6o>6E~t8T z-e+;ziQ(?8pY=IFGkB>*b1WBaP-m6C?I=V_SPJVqeaV^Xjlzs!8pQmp=guw|A(~z2 z6?;3$4^}Ak+uqX(0dP@5A7L1nx5I$ zM1=Bt53PEz&zow#QxBBM5j4b}2N9@NLx3XQ(rn;ciDp7i8wo1z)zwu1gAYyTNTWn0 zI;o|B>*X-?Inghp`my!OJb-UH9H*kmA9Ck_aGoEPiV3!r}ZAQgjRsvNX&-}i^?bLw=q9%nGf9 znxsAA9V59h!`|twkY2jU>C&-V2Q2}D`*y13xfWEGmN|#aM5yfFMmHm7RZ%I0IYUQ~ zhdy3ESlh3hva2lksV57F!5n_6RmK|HHkZgEk9c&4nuoKltJ28*Y3NQ*EVy@2g)lO_ zU?}T})~q$IyMb5U9}MG=L3vRSP@BzvR8dZN^e#6%fEByQZc$~3Qg_pS0c|s({pIyI z+kE~!pmmmG^PXgI7RfnX4@wp(_gojDV4d-Cn2ks4gQ2C>b)sv;iMlBmm2cC7Yjk*VZdY ztR@Z|yvU3*%A`8+yHdqf>%CFAeRZ*+OvS!7zpUFgfmjwbP4$CWBtu*gm zO)w*Zn2y>6)#FXne>#Wtk*-G5T|^XE$mwwpg~dqLJa8pu@(2;0?%@yNWKGh(Rjz-E z$~SRwY8z2l#YmEx-woU7Wl_njrBzPF>*VBMpF=UQEe8NY{dgbJC4MZQUK2UI<^1XL zfk;;SU8btrX}hJ``ztaf%$vONvO9HGepZH}^N&Zt9jQD4B4fK|b>`*f=fHyvxM_ zeuWlRTd?+3vcAUF^KO+l`dQ=LJY>`P`Zj=(bkq?{D+T8c21$TTxG~cy7-jH$ef~k` z6|~QfU&_-Z>rRi6moHJ*9;}=VG-rV!V3gMiMqlKajS=V!vmp))GHu-QQ3l zHOwOi)oHZX!$741Lkz>1g680jR*TqpT^jt6EDbNGy zfj?*>Htc4__yuh;gcf=?k__HQnHfu&2shH~6oSTFPxFZt*4tpX@zqS_V12HB+yP{3}(m>eg~ z@U|TPDFswQGp_jVvB_58i31I6e3G3z=9J|CQSbvRpq*=Dhw&SDwv-PRK_e9zW1 z1sGV7UU&m!u*awj+ZDK0j6aYq+*8L4dfAdKMMFNCsOM3m_E$N~3+#NGTr*uf9ULT6 zrluduk-eV;f-ybCzqoe=3}S@m>wS37Hs9z;bz3g)nDlYA<|p@ zt?uf#+OAK!^@Noxun&jJF9%4wdzGC7XTY9@q(TFabT%-jQQcGelpT-}@KdyUz(L1H zUmuojqI(GcHoh|#U6w1O zsA0ft#Wf8jq=13A8yHyxUf=7oHr7gmDipRzJW7#mhAjxb1M}ColRU7BFD8>$GZkxv zZw{joO7j}_bxN`)n{pC&ytl`D6%3JcRm53$CKYEp6TM6zrslwH513g)7#Gga zzm=GTtH&oNx1jf)@3}2=2pIUaa;1@|mzrGj5scFVDUv^yhptIZeWJ{A^F&Nddp^<8 zEJsvY__n4#V&`ZTxWjbN(0w_0mrB#LoQ85rqoJb*MJNU3kG&VHt(`?kb5Fz zz{@f2&!xt_SRTIgdQ(JQzLR%Y+&FcHymR1z-cRU#z)t<6h0#J zX4Q7Il~!@FNgreV_efS_{4ND3TmoFy{g9F)Arx%ez6Dt% zwRYqB*?)n50d2NaX{dut0De>xTpJ)h=JsFp@ z>495|&iNUmD-CI1Yir-N*-RR)l0Lf^yMC~{UKf}@RR;8t2z!@-C2)D1zrS2{?An4k zp~ln`{|UIb-?l1RS<*RiCsfRe)r`m8!R_-5yRTyL_5nDQ=rsgTQXYQHOFTINXNHu8 zK*isGvi)vO6_vRs&0(qbrcWJjb&k;;>woRP-+l(tPu^}{?1Pc4wjH6TNd8r;;G1p} z2{Bk)ZcCXhd(H(ZNR$LOdsZ;;05f|R{s@^6cldG6UEC1S){6D&L-4Wr=rWWYXoNG5 z8k!c7#Y%5yzJG%d%YY&|->@7m^4@?%fGZ@X*@+rLlSxj0qABEzp{SOwrd+W@;Xow+ri;r1kpU#;(+ zb80m!eO!O)xKHamVZ{ENQ#QDuP0{Mw6~d?L)e~+%>NwBPiMaAn1-y4D(LMNc=!p5q z*v07GJk?7qA2MoGT(N6Ky@&2KS3{I_>wiI*9%3G;9Y>}xX$4VPhtQKeqMo!^@A5oe zaSkNsJ<0(h*m7x=om%0GqK&F)m04>OUFEgbuaB;a8vb0%2uGcGnDf=4R%KZ}Lt#K8 z5bJW(7jo1oziaQZ!Xqj%88WxW`&?mM=nJxjIwx3ps1Mm%qBVOHjKA1lYE&H`m3QWV zcUD4`n@7SBddZ{~$HFF9PZQ#G?#Qz`hx9YUGU)*HR{PNaCv0P}Itkzl`~Vv$o9o&$ z9r4+VpGJ2+pSmCn>_1Z`+1OTaY&ILJkOPytv7*Qkv1esJ^q}f7-8VtF@(u&%;IUHY zr;ma);B0^Z4A=^gd|d}Eb)0?`on00&KJRbesoYY6AqFe78!ZqVy!T|D{sYT+v<-47k{eqKayF~j*=K6=s zQi32jazYM$_qxzjpL0B9?S|)qH{UCS9vj~FC;td}et_&MOtlw$HzxPjs~runQRXAx@HC5 z`EM5XOB3Uni_zqpvoFdvy?fbz_jB_LK4;K;`-tNmiA1T6OJ7Mg~k>oPLy)-}zWyZ>_w zA25Nrwb&n#>cl&aZzs~jPsSa~>C&Yu`62O4rOWeg>{=n2TW%!A_ASFq^#k(F9wS5g zpI990xoMQm;$3cYA139O@usn-ZMxnhP2)d$DPWeP`$VkFDQ=l%78NT{|y zzl)4rLE_GS$o)|pUUeiHgin;-z;NNP@S6MPxKUMK=Ct8Yu0kFKH^5%dSW={hKtdm? ze+ltR^U(s_Wtdtr??+(f_Z)UH$v?-DKE3A*tIiTU$jSr5Osw`fl1BQ?Z6#P1Zt9nE za*(H(bPV`{Iq$a~df*MGutG+-B^k5OUq74+U8?S_90-%VN<3PhPjo70Wg^gKZK={! zCbpJt(2jQHXjYB8Ci#LZGpaiZrRRhaknPPbSX=v}43**q-k9cy(~V#h+?I&KCJTjU zrrP^$7glx7orl(>KgS5@_cmy9&0ZbipO>(ATIe{*iC^5FHn6>?>-Ft{zr%)BSJj;h zQ8z74PBR%`xM1XParcK(9TDIg?b%jeV9qt+2JA&OPW5YF&HmOEmtka&-%ushxBG(+ z4GZ4Oee-wJwEF(_Q-h1-HEz<`pvU{~u%{~#Lo6|MXKf;w*ThM}F6QpL$j{^v?zuT; zhViKHjdlv~x@6>F8l*J`=6bK`VX0U~uM_GHt1 zYNB5rtd(snjXgN3y!1L^oZ}6_1HSH`6Fs^awfu^6jq63nl$bN!&~~xW;7#rnlbx-T zpiS~5V9z?D^prlny0$o-pY=4O=$^m*Ri*X*@55z0`?q|ZQ6Vim9Zd?Urrd6$Mv;Bl z8`tJ-wdNvg@{TMw<0_AK)KPhd)OG`W%XnAk3VF0=KJ!$W7W3t$s}j+W9_2W@=-QjE zjuzE$)NQ-ehxjTaBDbrGdW*c>7Pd#TzjF8^mmAjJ^^nGP4RVdyq*QWjyc4c@>E}|c zhvezXe-+F{TSMEI8Ce)|SfqbQ+sC%)xT2ilq_!TneroK;rXj=1V8u@sq!i(pgd1I& znV}$XIvX~_^h5rhaPNy@S{&-`!H*6MIIJ(&+Q~&^fMZ6d=y<$ch@lG3+-G@e z*DDo;C^zYx6_SKad#k8U*8=5k(ZS_9dMg0zp7{d$*{jc^XrIkyK;f+bI8t*%gXI^i zh_NhExq83riJnaooRfs*P$5NW#q`w@iABQd1A?hi*i)1VGPtAo^sS`3ov^Y=OQW}& zRcR=k_97J8RLw0d1<-j$2pB?hyWWl<#_1S=wNMXT9A%-&%|*VjhhWP(7nFxyK=~5) zM)VJ&Jh_r5@ikCi332hvC_R`egGN}4Qv5K}vk3Hb_qULi(le_a+oUNBmrq6Ve#9|- zj6?A3;OXt?AI|0#MXxqm(>}+4vHOI%M7Y&e2zACBH_t*j?JJ>Y4xIcAod5I!SmhQo z3Gi19li@SOQ5^-%YMY^06$jelQkFuD;VyPmY!$~1lDd5*k4*BA{w;#H+ri-%{t zB>0aXrXA)?%UJ(byvUam}ZJm^^+I`LO!_xV4>% zS928K*XAwEdoghoZLbugzmFv|4H^r1hZb;qRTwa&b5J&6yGh1q5o$?M^zaPW#B^Bd>7{Yt4aUZ4>)mylk({oV+uK>o}@N%jEgh zj<#gOD3fB|!}n<_A*!;%Cf`I~4WECrDWBt%iFbu(1n0@_sm+P)k-)@u{r=OZxENb; zy45=}Echi?nh$m|Pv^MX|K9B1RN&WM8sa`+I+11eyZ}$Jtl%@>g)Yq%4p5$|n@8_I zqPTU^jG7IKkK2y~JLqoZUBi><5Tc~XX_Cbm$W$$6RMo!4@PqGo*Pmc!RV66>n;NX7 z(eP5=ClZiqV3KKQ-27U_MYM&M1QYDNWo@$;n|Rw{_JfcD_Q;2$9p;hR569$5Qh>hy z&_%<7_xQkCcBL_+5-4{l@YT<$d3cDEIpSoo!-wjMgFRpMu+-u*EANJH%%^k}p>%`G zjuJ`R=?4fLRR~yqtSy{&R%}RyY1k2E zIy)j=o8Xq%%J!~CgVY51={o%0jpI|bYZXLd=!GWCtPCw_nogDUEqG_n$#vIPnC3iK zvrsMnvaflyTx``|5k)VyO zu@x*`8qMkMws$iewU3PhY@gD-tWkNzRp*P_3OS zT-b`&jiQy~bN+N!wL8jkiZ9c4IwM~|cR%miXkJ>*1^98BCDY^-W#UJz2a=2RIm83V zOf&Xp9M9&0kYgo#PLcPPWKemai=_}SBq1`|DzPdG^9j#EP;6kU7Ua;6U zxFl=syT6>s&NQ!FJ1FOCI{M?@mMTgO+&S}_!fn+g%|@r3xpUoe4ofzy`@Rp%(uZvl zV~;F5bRA9LziwV`SFu}q_38Hm|3g7**}`cdkwe2KnRBV+yVyjIjj@Lt8F~Y;68H#o zO`=LAF?I0KPQJ3eqQOt(ou25B?J7b(M-mssN*$n@TBZ2&GK1Ot+=UCwmYsiQlbfN=87FCOK z_hmjCKwEYxrNiyjh3i~B;P^d3o`Pd=47l+P&s5~z933}Z#*L4>DH`GuIBe+={ZOMW zv9;*+fH{Cke@FRX;Y;Im=MA9sbM>YV-;xz#JT0-Yp2#pbtOA=v#H-JnX{T7Knn!$j zj598mDn*%WOqh%IAC01TuP9G5_DCi2i!shIP3DyylJ5M@;}F`+Z@n8%2&e6(wk>Cz z$XW8zwD+B$pt69mG|tesP7Z%un0YVAS$ADqO~0GE-|0B!w9J#zBtx%yopys2L;|;c z(&nt4B5t3CB4e*<-;VC?L`Lkt;~C;`I@Wn$Gs>kb zKS1`v?3s~$$9`@1ZNt-q793``!#^gU(8$?8qns$)X2Zjy%xjYEok;Lomh!lNPHJ`D zjc7b=hiLl3u|2QD#&qxw GDUVwGB&tFQIs|KHL%j!!%k6<{2!#&NHG#)l|*$;VA zqLA|@W+1vKX!(z+se{o$bCoGZAqkc=anej~O0p;p7wlT`A4Yp2x& zrnelK%F#=odOPN$I$X{2OI#24I+jc;6^+cnPFF&{c*vrCZ#^M1Ao1pGLNC!dtSSU+LFT>wuyXGzd zquzA_+$@lMao;xc6Xg>OvG2` zB-MPYUStJ0{M6?B*6;{poHTnCM!cB1R+c=UNS;P z!ac;Yfp7?%%)i{sbMG(CnlhqVu%}w${>|H}d&a85r%!{A^GL4Q7c2a|z$jXF@HekZ zL$Lr0IP7jAVgf+3=(|CEX9tU<v2k6DE7I%JZiK56nVky4au<(gh?q-IttC!y-Ca$`9k#z*(2sMbZheIz?s$Gs zAkS@|ee(?ao0g4hgh^eO<36!+!ZNJ^SXS^%&=a>&dPcNQ`mT7pkg67KDv^r%9UBI) zEH41exULC+r2;v`I~wicC%NQrpUYB9evZTb ztXbBqK6Tk6p6Rp{QAba^yt#m8nIG>}oE93Xv=eFt$ty`1h`me$jtxZVI{MgD-npBK zV~k_#PzdhwT$EyO7H_;k+PJzNjjpJ;RqVk7&h&KZccvl*9wr1dtPA0)zndCRv|&^& z4@{bJm+nO}nSM`Sj-u#~$;6Qhf5K5fx_P|a8z)3Zr&;Ud^zQ$)_myE$tzFoPpfD(c z5*8t-2uK)ot5^uAFcL!vBHi5%iUA77L6q(oVnAT%R76p_hX!d7knV47&(Y&i&(Zh0 zzF*(v`{TXlfScL-+0V1$UiZ3}>F%bM+xR@~-EPYQ#+2n~d6x4S>PE4Cp@i0XQqhc+ z=*#I2cZKlFuLI;8vI|1y;$4NUy;lC1+2hud(-Kd5Iq#|=7bew9@2V?0!TDaWjTyUW zjH+x?p^DJ+lUcj}gdU!=OO^6+y6KH?e_;SW=`vqWW~Y=r3d-{~xci2!hsmg?{hmEr zn3M8VmRws-OG|143lp4l2(5YsqgK00e}P;cQv$G7WsBOyR#r}nXqGb>Mh!t0ejc`F z4KG$h_Uq%7#N`_jl|0X4L~%#jV3fjnEVFB{>uk%DhYx9vWqau3HaA3`-WuDZRxRDJ zFXMVhCW$^u7SUan*H#D>G?k6x-bQz_mL7+i=GYOJB)h$VR;bP{0QK5P_9DLqrcl{t z1wi+*zS=hvqUWz%@XV!sP;Xa&+Gb>Y+VsXw6-HiBK_qc_o>r;yYTL4x%-zF()y=v< zuCwRHr*i8*{%`1@)P#4JvWVMq{L?>LcaES~&aKQ60~} z&eT5+(qBJ&;7fwIE8W1*0AH@xYqFs>wPyj%SXtI0=lc6A;Zxx{y254Jynp=c+nX#Q zL(v}8w$DG-;nuq1z2Z1;F@K$OE^ndUmC*IVJ~#oUb~f#T%4!$aMg{y5FSPDju#bQJ zpe&taP?=t0(_a5yw~Qi*_9=huuSd_J_RhWi-o4EU&}g(K&ijwQco`1E)esYH_uJ8t;$I}KX|A%X2kZT5S=(haFTl?nG z9u$C9bnRS=^}zpdO$1zXX}UPouj6w|8PwlTtn+>ap=?FrJroHzaFht8Jx$Wg!6|z-#_c$ zPyNqNmz3ZdFA1S1|6rbdb@M-Xpdl_e3cruf@8k3P`20RT*MEB-V154fKBT|B56JWW z4&MGRgEvn_oA$qA9c(&XGiXF4sic-rF-rsuYy{|jN^2_Cud{`DX>Or&pwye>auKdE z-n{hOALZU}Ew}tMd}A>rd(OCAt2JK$ozTeC+tyUw+uWLYLWbr%g$x29a=RPG5F?Ue z3u=XK`E-X=s*UR7u0Zn?!aGsTG;2=;BKTomej4jnE|wcV(F)(^79o?yUT#;g@z7ex ze|p7UBa~M*?gD=ulcT*49k(W{R&tfhPa|dQRqBHi`j@>4h(g*cM1?T$h@KZr1Aj}! zBsLgy30nLyxpt=Mb#))+5yTz%bm`C#@ycd=k#d=a?UV|Xe#Oezb>yqO_YYx#CD9Tl zeWNEQ2dXEny1wG{O~TJMLpXRQstA~LSD!t5b~o?jxpymTuPO<{w!U(AGoGLMe)(83 zNqDy|O9qOs%IODyNU&<}tNYfX`v<K@>_qK`Cu8bCRKc+&S&)n{CFegd|t!IcNlES}SwSnYDjfA>=qO!K~d# zL3~C@U0FTP!O}y^l1}dk+;+N@w&v1cq%UErN>Z}M|9rp#5bMllomQSHe~}Tj9IbR82gKLaC4>67hpsRYwzAP@80HVgWSDn$ z%zkJeVeWNKwH}aXub+Ok+k8GJX#DQeqk|+I)2HbAH*RGbReGivoehP_5>PUIHYR$( zGXox84KVXW7+>8Y5xO1H4(wH$3o0tzT{eb5CY#+lWEVnrfZ*76N&64#&?TfY$k%b3yv?$VQCb`(=~-^sq2adBX9p_E8}HBL z$1BA@8jqe5r?K9s!BW~u3$v-AWknk)>eh=w+uXhFFWIK){Jj1vt^Y@Y$iYHQzl_qb zhT4dn-y?$#lI`sB>7Y5cX^R0c@~W4L1c3#V0np+mJ7N6N^ic1(?8~6lH@+zh`XP=n z!A`^RG~-ZZ)U2eBq1j|f{j0eWmX?ORb-2c~9dtv}F@mn{6k^a+bA=v`)D_nPAEdEA zHq;G)#8WA@A5eigpQAY=$!WmuUA(1&Y;rf!f;g?h0#7r)oeqI6w>I!Q{A$kiV3_1E zS>cf*M=q^MY$vROEPy9^skW5%gI7JLak{P#7vVPvK=yGJ}YR2oTG+ zO`84hfBvb5)>%S-lv*XQHG2v|V4Kd#9B8>I<3)QnE252bl2!hl^uO)C&v*GHcl{_0 zX)9=~aI5|Cc4vtK+*`MD_*d=u-(Bzx3UCRHTp!v7P3%^}C+3IXa4&OC{~*`>7waO0 z1Nfx8?{O;(m*mkWmxSGYOUsk#m+znY3>uQBY!@q0yV2Kuo4aG#bt)$ks=pUk`VFlyJX#bg-Nlpv&!xVQa7c`!;BPW}>ia?|;jK{fPo zVJ%PvFa>Ll&^MMq1w9FRkt?l5paPr(l=YgJ*Nu}<8!GQ`nUaHs>v48&?IFS+{>)Ev|;xG}m1xofI4m}i0K%rCjkD$H?cQ*C} zW0nf?&{;kgV~M~{HzdfIe_ojgkWafvjRJJY%V)J(B;js+bs^&KI`2ml)=@Tk6zqednO zkT!;&*fav&lN_W^>SCl?fYUx&xVD0~7O#kuQqrD~tr`JGfw<<48ZppnCIAFiV4*H~ zEKc>@FY!hMx9&5FHqxpn=7Q!&i3B@n*Aif+ZS78Hpn0c6`*A3~f=Q^xpfu?ZN}3|0 zLX7|V?!W!T)zd6y#rUlf^Fpc2-n}-(6ICu_nS*;*0Xsz)~mM(Rg&Ugw{uu$2Qv+Z!K zxf_1`qdUkajRNui-r%sPR(K9D=vor+1xCu6j?qXrUQCL{A-N`GFlRo<3(i8@bRe#X zOn`AN<00E=A|i8S7S1u#?!LAXQ*{&PzCUN^Xl#mqL7PMs7U}oRoEfSsgI0Y;OI7FD z(NsjBACbs~fC$x4$ZGVfYgG$1zmi++FpOdr zG*X@tDxD{aH@)yFs|_#LA=-_@rnSZKBLZem>eS1if2K48lqYaees_e~l1}dxCX1y_ zL2a%><2Bn`3R1w&hr}kZJ|$6S4{?at{%UH^Q`@dU^8!npj-dpE1DkhlqhCacxr3N? zW3Ih&c5DOQ-en*j4=~Zydd)gE+Wi4<#dp^tN_`N{R{wG$>8&yn z->F?cvtysl8dinWig9@nlub=O13pX5_qf&=F~gcOY2g)g zyqAM0%?FdW!r=BXAX97#<3T#y*IbQZ$h^5qwLMzlQ)~xOhV)8-ARs zDP!Qf`lRLS9+HlO?weDAJY{8cd@j&pqobC_6M?cv(dT&5M{*xWS5Gg)fXoMyB#W*) zk~no&6YnK_-No~7HiJ4>D%nE|3`1IMh!f|a5wv7jlbjNFo=t~2CBk%ncx=qdyEs3B z=-;CKtc+o@_Pw|C?%?fGpoJ$#gViXsvO(l{VV?YEMutVrf&Du2nKNKMnj8;+O#MgZ zf)6<(CZN}OB^h_pu11ET1#$IdOwNh!E?tzK2b8+GZAMPr=fDsW8{!qq;sg2!E7!Wj zaGUMMGMWN-r=!PsVH7lj(7wTpemN!Mwye~&j7UNTGQm9Q>YGO){p%37a&h+?k7*gjuVvnXy2!P=%mp4CLYM2nR1;uzzuD%R<_YWUqf) zl&``jDJnA5z(ih3ozlY*7+ydClh90YdSTW>Iu5J&*d}2-T8=e&wE6tEa~W z&Ezl>rIE0VTugOQ^?N|v%9rd`LHbIB$5~HGXGu4*dD_)WLM7bP;pJMs5{q%-E7Nt- z^hB!KCZ&r5e<;cy#-GzbgjkP4uVsWhKY=Sbt3*j=43t!@2n*8{k>hG3{7vfHo9X77 z{MD`Qx>thj?yMA_Q(s#uVgSM6nZkTfHyMSS%Z&69Der7bR6Sbfk9!+m9)QskLZj*~ zKZ04^)1hUQur|9vnutn>u5eoPT;cB1_jYuX@^dN0X(JY&1Oyc--@SVmNM=d*EAH8f z6p2ZW*GTNE>ufFQF&~cX@5TOfrajBi-QL`i)e348T5FGCq3vu$vg#F27Rh zCXxYtw<4Gwiyu_0bm7R;oX{#rh5XT;aAi7w>x#tH*VI)P{9iT3U3@Wpo-G5$FF(VL z0S_X^OBaPQYAppCQHK`;uNfq88A$jD9gM7UbWOSgLDoJEiK=zh@<|xK!mHFfz@$iz zAcFZDay>K^0tL7S#m!;3nL8<{&-R&2;c%|R92L5QRbo@;^}V}SSC&KzBil$)7Shyy zX`d9Wk$Nbq316tu@{)vk^cSlRftSn&+LGOHe5{iXdQcWKR@1{4W@Mb%X65b9B~yXp z-j%jJ3x;H77yaCLZ-OFCo798hgZABp@8Jq<*q(DNvdX7yzBv}#` zXF~F3aa6I~hkz1oOyoJLh6Eh?ujT0q4Zr}nkdPKX8h@6;`tz5DwZN)xD$FBX+g$jE za6{24pFJQKUzK1;d0fqf6r`Mu;LuP8Btpn9Jsz14ovQ@J?6<~2IBOXrgh=huL6o;D zy1xFQd{vV!h?iRC7m!>b)*gFuIr4Gu1=^h{j}I*K}tbeS&^@lsB-vptnpH=W$!D;5K$2I2IYvf0ZXcr z3>V@Ipg&l8L&i)m1$z*6J;U2Tu-;BoitCPJBw+e?oAo^pEwhFskTU9btbAxA(@kGOvgL7fLn+cHdE9$+4_(>H+E0SP)S3b#HbX5k_qP|e|!!H!JSPYTXD<9HO zwdBSD<&WMYv|yH5=leLfI}gCnaye;yH9f~mIuU`!Ih3v5wQEjPb3|fYLZ@{E zt@s0;xn~i+xAoYl?LoxEl3nlk&$kq4gSb$*89Eoj6sdQbPDA_s_dhdj&uPdAt!yT{ z_U>u7NEV#8lY)kNBaM0SmS6B-FBMp{ zJhar@ptV-)h8Cm+cRCqkhRy@hu{GD4Z1XkfL~m61G)79QgW~4KVrc8`Q!1`+d_Y?K z@q@6%{+~V*O9RZSkAF1LKZy4U_8)1Q^$s_MDG%Wqd4G;U*I&P49#Q}j+PW|- z=&*cg?ro2A?bsSV

m&@P1o8HH%6!&1@FxATgDUhS4U_q{sY9zAv^>$>A zhul-XVyZnt7Vq2l*x!`eL+Uo)eOu_=qb!aHvf_YahL5tmj~@N$mc1@jPW~P|v?mJB}abG<1|((1zl zQE8SHQWOJ^2?7}+F*KwqA#Us14*$XvJ(VgzFV~&}+sQy+vHcWwBD)L*Zf^-~%=tPy&C=4&<7a@z!vFi60 z^0hnGh0-kvMyjoX0y!V{QuMhN!`NW@MupR}q`L%643JhVQA04+0x*clxU;~uIW@>e z3`AQ5Ag<2^<)*PV>#B-3v_VJ$9Tf~MyXnsF+xULE_|*2FzE}g4`mTYY(*-cXQoO%m zh@NF?S0K*{Ef1dUiu!ENv zWMNTTvNI5JWRj>(C%o50Xc3|*o2LTNnWDLmcUIj%j?uZJ6T}=wlQKJ=BVm*E`ScCQ zwg#ya;cz@8@U3WN4Z1N}A7uX;vO&+LDHFfo&!fQifl>veg-UykAmO|s*q&~vI8q<4 zs8T3`qT_r|#8(0v5CISdCT+wl-W@Je0TYV^qRE-=zyuG(c|b7ucE%y95|LS!#)B@Z z$cqnoQ}VF^a#7aXT<_t`@6um$gISmR;Eo& zIe|>E$?Ecgw11LftPgayvBvRE%YoXRSf;f)v@s%>GZmupqjsQ#h5>CSkKV>fh|otx#9~8fn%)eaT!+m< z9UMeMlW+pStlRIoLJ`8W0kbQ!^B>0QR^45e4UdzWA3N}pW;DfxR` zPZRV9>cS|UOmCi?gWBiD{fUnb+h9O*Or#w0L0v$dI@nij--AMdeLL%=+cOLwk%YMs z8NjGGI0QW%f@Brx8Sg=La@5`{Wo;5{yQ17o-|UPp2{J!|7M((6!6ylS&DOxh{w`4x z@_m}uy)^F%_M?7bK_=<$#P|4qI1(ivCi zAtOMTQpB@n?3pp0eLp%MB<d#s#|kbiW9UqJvC$GT7E;h@G{?ou*U3E(rS(G#$FhVoUr5uQGXPTY5L0@>)`34i7NX@D*gVJhOd8vi@NY{L0bm>mVj zasOa}YuSlHr~!8JL!?5-KheK?_t;W=Y{>9CG>8;eg`-XZ&RZLw!VjQim8FOU^k6k3 zBLbEnC1dlU6w3l@^SBAL03<#Y{{vJwWwL@c1I z>KS3jjL{JX0D6KgHFfLpV@H5uK6U1V5Gth3RjjL}}bSscbn7V&@`W`7^^KxJ^&Sq)D(0KpIQ7@##DvjUv$p+E6F zx(@c6E^LFz+g<=`E}>SN;6XY?=uvWdnQtN$LM3J)ct4exV+TdbRshwX)4i`%n^wJm zey-~y{7Tb#j9*cOFWpd6d^f)6^5DEmhyJx|0R(lW3wVGn1l(7bO~kc4X)>;nWu*&v z?xuSLz4Zi+FnZZKeI>KS%>~o7vcikmclt!`Nw34QozMml=Q2pQ4_wQ!8PWlitn#6y z?%_5W=s*r0^X8xKKAe_#Du3hQpi=7ZHz3OlnI_Y`yMXiZnq9RD!Q>eN%Fmd4iGK00 z;DoX2l(dzVn-Q7(?M5|Eyug?VqGdsML9U*I*5u;B{t`;w^xbAz#qm`1Gy8nkqgY_F zWjO`k42+dQTH~4??y?8iHvlK?xw`2AZ#_Ex(tbc|b2Y3h_~kQ>G~Hbt-XmzH{t~72 zu(E;P2XJk>f^&Zy>}C$QBfRoBHxH?>Rsg#fk-%gp&vcqG^1oQD;bez%IdIx^az|3% zzUgRTx~H}JXSLKKk2{1Xf#609)gPXfG>aXXGlMWTCwPo;4x(d`eLYJ^$#pu~B0N9> zLp*@Uwb4{jip3do-HXM8+!oC;>SgzLno|E_+O8)^5j?a4q>G<`-xAS6QOBd6tlGYT z@Y)0lBm}*;^z2y?UUG{#&HS7Uvvwj9Sm#_1vcp+DArKYA&b7`OG7@Vq_yy8h)Y3n) zea>l;odGx73eqcbn6*+h+w*hu<4^7gM<%60JpkZX$$^oyDhcZnc`$C)A)OGCBj8_U z8i>OOOd;(V`cTX96-Zih5KFLJU|$(2g~36lsI&Vc;&%n{l0FGsppysU!fCUZuAh7H z&j&36byakpP9&1RSFh}L%=4+z+4EXRaBZh%cZ)ey*ILK^rH+N}zbw&bPxyCm8}&e{ zm{yHTR_62H|Ai=z`ZY{CEiLj`CFD!n3Wveyg@hnm)98XvzS+6!~gK_rMxJB&7HdGmDMj7 zeBq8gv|Kj+%Io{<;jpyZfts$f^~_i&TszqC4B#{{(f$b z0~dr!8{d9@s4iYCKw>I@kkr0H2H+T44zO%?@D6ubYQ?mE$fu=|aAs;?7&u7JA#ldQEAS^jUc$@?P zoq*f&{LPNl0@tNcMB@g+%9gbZ*CjiyOHp^wFvNEaffz-B+_61}{=n&V*m>xc^73U% z`*YbJu#=PEL~(4o@*WF;+Y`cmAJwxolZuh$Xt zk7Pa0Yb$eOFx+LLsx#YKAH;ov)?D*64`zu&T9444rsiZ*FH@oSdblt5GTTA?4%DZy zM38ZwRNFQMOrAZ^Oi)VmIR4LF`$c>bsV4 zx{*K<{r1UQu4~CZsH_W-h!RZFTSbrAYbGpuu96(nAcBIh9F~_Kz5gQrwq3BZ9vmV; zI&8rc3K|GQj1dG#Ky|zktqn_;9EeSh!ql$R{))A^T=6byUYa`z*H@+2KygNIu~X62 z6%u(UfEH$J_JUARCY0e@XH?`tqrnMO6d}Tpc>88ZdVrQkz1eAc@CxLHh4H9^z{h!X zI?UqZAy2=*4vJJF$)a!VvH^5j&uI~^K6`#yFtSkvw%BuU|Xy{D_@|UVzr3_l> zfo3@zF{*UQUZ)ka&adZ2(|gy0Y_>7ThNMF_7Qp$?v^k}?<$x`q_g7*$&c~l~#OKcj zAd?d9AlX`UZ!FnZ2Wq8`oYbM6dmMAF@<4F-_tF0Grw7R-pcGAxa;4+A^imVV9Ku-6 z0S0CQ>L-Xwh4O(4=@Tq9B%s2QifB|ItznvTQ??KF4NZhY9T}Lm%;3 z6(mRjRh|mkWt8b{Dn={Zqx($aL>SD*h{U}&ZXIM1fN}TE0B!_#y(eQ(r?v?agm*p% zkl*Sfb((+L@xML5SD&y!6rX5M>~=%7rSf8vFT*7AYZ@IPiPr;I1qQ*rCn~U$OwtYl zppHNi6z5z4^@MR4#;a|lg^-x`kiN@1u7&i=LWoL??{NfivTP``B?G|O0>eQ@l;&zL zS21WhgpXL+j}i5NVD=o&Pjh6@bOE+G4HuogMnxqx>_O6;%{= z*;H0T^#Tu&d>Hb9w@|TS5;%^;<)MkMNBLEffTqugMZ5h}>LP2*> zBPV@ixn+wRA{1X~=M9Fylw7M38DJD?F7H8bYTQLPhk!EC$axlkZ zr_mhSkwnl+5rDc2Fr-$ZRDxjfCWZg)p1yL}XPnl15@=UZrY&3E-3+O6CVeCwrd{0J zyBqX6fKHjy0xXa2oN3Tx5yl*Q#WvlSdmX1G4&z1&GOu(ZVwIqHX`pydJhuJT*ud+Cjrt2|o!Lp%QM2qo2iwz*COdA0%i|2=w zY{bH63E*V&*dQyfkp)B)4oMvdZYxerz45i6S!hoLJmivIcH;K+oNkjlf928Lurl8C z``1`i_mT+H-r=908NnA4K@(dXkEqEhI&jb=AtW4~m*i78j|>oCykji;GN4Cz0FWSk zq&O-TdzFWD8;?{e{^oY;&ztc-z8TwwGHE4nXDV7qkeubBHl7#(h@XJ?-zf=%w*$8` zBNo!S0i+%Cf*t#xh1A`HEDDMoo2q)>ICTLKlnG$Zfsv0Y3?v~CcZwMb{a5Jomwf~W z)S79o@FY5ginNEP3oXMnaUA7>$dzL?r15m~IUo{oV{zLgqP7!K#{}Mq2`1gaH#%s8 zUH-&W_|TsF*wQhP0(%F(mGz^=FAyGCc9POohV8Y8LcQF!yi3?B$}r(Hz7aAHF0F#R zrtYj6doXvPw>Tu+2^3R3F6HEDv5@ndfb_|LkX8{2(z7R}YSedB!z|vh?Y#4I!+%{$ zf_${I5U6TnnK!i-fK&7wa5u13BiG~tj#1=vKw@PIV=<9(A|~zHeWWB_DY0Y%R0_-L ztTX26!ENA_Odv?B^w%5*4M~a-C5VO)F&SW6B?nuTbI{9DAFRzd?rYc%B7bQ>>-J>& zSg0Il0B{|$6+e;TAcbrM$rs=bJa9js$g3oN_DTSF5LFO)VMKs;46r(Nf>|-Ww43XR zAl+oJiE58UqgJxI@IVeRgs&q6>)i@yu3V@@yJag(hDd9Okls|{~#XZfW19- z8k7vSi1s%g2Aiy(*P03<7_}6x90zyA!;qNz46lIW_fShU)UVAUg<4o4&64lh3;;DRj9dn-sG)(a2p5`8FpCYgE3Ka{MK$Wi!HMUN39`R zMhb}^l-525_bwH{ES>J(4_X3yFFw%Vff&|O(qmX2iXoby><+VlAw4BI zC2WeLjjnnL#VhsLgX&op7p{MRXe9++Nu>m^N$z0ybL3~02jFKrrVpJcW3sKkcp1{U z>JK;bCA)8KXRQ>6R*Zq88tDcX^@H3_floBia+&m0?5iBPYMLL%7XkA!q2VAVR3H8B ztsI$DlJxpI;CMN3zv#rz405H*P~P+O84xGAyY02(F`sm>p=%YXwpaPuz`-^cq6b6|fk0Lf{b(8BgYiIaA|(J{%Cjn0l@vuixKF<(hD zlwG_#Bz2XI4~aS#!*SI}jG!o!cIFCaaAfsULgNVNheLAKkeoBj$zI=wUN4JfxGxNV zAM33GlBP)GI8+O;IJP&B-Fydhifgdvtm8VlJeu*C2pS>h*BSSF~n=FKZNF@+~R6G+FX-P7ugs)5Iqr5VhV`fM}^oq z)XD4&1G+-cQ4zV#sVEc3HXYQK=S#nQiBC3EODlJwKQOqf6#%eN&>x<*)gQ^_Y&682 zTFDz6NPr{JBGM_SB3;!+TIMn}!3d2j00(SV!1DhrrI#wFI4Bjta__ig4Ng9~t)j2j zBO^GN(~!(9Ugxp$WB0D+>L%Rr=ooEzsQmz6km)Eo&Z`lL)AgOpsyS8720SmXT^x*s zBNBs>!J0z(QXYi(mr*7-vnZ4n?j#*CU85af<2}SNcRaOUiB*myI-Ll7(zU0plxW#Y zQs=_cs{0cvX^G79nwX1=gr0fT&W#}mVbftA8fnM}ckUYi7ZM?z8yWZR^CZ~hy?-R@!6`GOI-C|!?H_{0 zWyK?f(s-VjF^W*PMMFiplr!9F23(iW0u{Tt@6Zhqg@qC7Cl|Czyi}9~5vG)0;*%Nd zCZ-f9n{bS(*ojQ1C3350%;?$$N*pB)U+g~Y+HO-P7os>g_t0FuYYsvU$B-8g{$B#O zplM{y{j*Ijqyqw(4p62X1^%NQrzpqkY6#WY$@?i^?KvzMcv~=H-91iSPd7*Iy*BED z&Yg~^_Xb>IXlJX|QH0a$K}d0G17K+7!x9WG#kQOyR%kBPk+$TbAD?Mo9H%x> zN1=5RX+=Sxm}*(!aa(S(=JdYa6I;dKGe>%179Hn-T^?*orJSVJXR@-xQ1rB?dHTwg zLvrf{Jqt)S2ofbO(xoe{Ka>(*-YUbOaTOLk9-*6KZ!hENSaZ8PC|NJNOl_@n+ACU- z4HaYe%o24J6OyfUGAtes%>YVeUsk!Fd4WN9?Jj{o&|Uaqsw9Rz%~JtsJH ztXjWcgzsEzV>N7zgOMd${ST?uQeZj7V(@V6C0wet#6|jdGt6tCI}OP9-GH|Js}88d z^*;+KFUc1v7oSE4D|H(}ja|T?nuVR*4iphZ=uF8y_E+hmJq6HCwbr%vWPW)>Knq4p z$YQDeICbNRwNR574YIDJ5S0nN0X5QBo%n1?sBI&}$r_x9VIt>6PXSLiCCArE9AVLX zk9>GlpTAVPf`gRO>_l(@sDcZ3(%q>gI0DDe%EP;0SPsWz2bFhG%tg)}{f)GncZ)fs zSf7y=B`Z=gl%>n_0k4WgMDeVDc$gtP_OztPRx7#p55}k30F07~28w2}SI${T=08W-8@U2W=DtIndezkyp**I$1@07^&%vhIra4SAAYE@ zPab!UVhO@UBQc@ivC&+Dw+jp=eX$6xW$fl!3DwC#17JoE)SOu#sS@IvPW@!S)7p}S z$j?SrXl2-;xMTgWXO(1)jw~a+IO7g7)WVg#zZGyZWk{b45$fEo_L!nqnkcutKJZo7r?2%K;W3! z)jOg*!-w}eM|_nEh1r7ei-pc)W3+j-{>qAHfDErEecO3vm~L8v7znvSATH05A8j>d zq#&_ywRtc4MlSG~OBN$-2eTa`^&3 z_eT~5z2iy1Dnuffc?Cb~ll~YrgEZg`PZy;JH=Oej$NruAffA-^r>PH3DpYb^wFT-Z zWB{dB>FdOEfd(Tq+6JIxd%DKe^q30|F>mE(_Ti-hTk~obKk;SuwrqKM_1d+Z%E-$0 zTzh9G7{`@#y%v&?X=&T|y zeX{|7F6GK3(QwyITba%eF2CV(w38folX9)`fhLJ(-H2T_=4TE|iY1$jmXvbyjr)6q zYg?Y+0Rcw(92NVb0FqJ#vfJaOQjizv zGEO{}d7BmYKG21%KscuN@AEyB^$y`zRmM-EbCdID z)dskpSkqn$kZ{dGvK(k>9B?|9?xm2-UK)Osjg5^e?P(f1yhLkJ?6yFr#QkSbXf~eU zymW`l=7UNn*SZ~Qeh5NsDK1VUY5b7n6vRwc8mG1O)2T0aH9O?{&nl5 zvlk(zE;ZG_&G$9Vj(3hXnjXFO&SDG?Sh`uOqD@=$`f?Q^l~KGz4Uh7sII2UVA1Vn+nm6i;?^$zBqCqwEw$8m#%G>#2e(G{hkNd$z0HwvPStjwO#EG8 z+)NZJE=}#}@erL5)<}VfyZi6<8a`Ilvr;==QdpI_Hty`UwR367d3DTw%&C1qXsM%V zC4YP=M>BLh$bGHDm4~DhMeebsvbGRtuo_1Zp>R;Dh~;S;NO* z)|Jisho>9y_zznXj?U9*WD=Qu0YzU5cN0cNUH4f>o>0+Z4kjxkv{}7X%Ss#0zkl2c z-8tqx*{t?FO^w`b#xq@?+JJ{;zM-uQO+rde%_4Pu-TH4oNTre>ecrBP&@8C9OT@-t zrEL=l=_R8T`>TA;$0$AILd1mS044zt#g&hD?^3pmJ|5g^3}j`o6>3yMUDrYXHZi^7 zGA3iE{YObGM5K0MVButLr>^cWnEvo&?qqDj7J=rlJ{zf3poNOpfy}=+h;*+tI&%Yj@>9!7Fldx1__->D1re@t0?i>O_e_usXBpl>XLD z>q(4nNkO>rHVaxE1T<`FWQL$?ieY&;w)WKNDB$5mLz7Xu^+McD)ApB@Iqaj1pzDVUu%CFYnMWCeM^f z=}V`C`J8dleCIjFlNI8 z64WdYYGIy_;>`kKBx(gFdw>Z-M>DAlr9$1?naQco3{AY)ssPw=M_3f~v|7I2T`H~A`?^cjwLYRBo&vNI%3A$?P+c2@ zM>%q0G9)*$&Nn1lH$s-!=5{V$V*H$bJh@2-s9E}r=kx~{Z#*<_3)RERm25nT6hOGH zkK*v~Cfx|jYrO73zQ>m>@WT%)94vzkp*ii&b|%p~+vAA03s_(7n{E()%V%t(Zdpn< zlwKz<3ytB1HrWcV1llZKln=B44(-?E%%LPDpAMEVZC0OS@zBJ(%_P)8yJ~H2 z$4s&fR3&4sxP?~&Y6nA*3Yt13vER@F^=w6xVn>LEo6LQaE++U;^5*d&^l-HQlBo-H1ZT)w zp?Mvk#j*}$0}^=VS{%}nbtfNfmlq1xI^pO_cp%SI@5iUf?rZT(s*n=whiEFpk8Q^1 zRS&Z#@zBhl+8vi0Nm;9^AKWlu3xT|`kXedam}*npxXXZOgP>jSIUD?9+kk|>&PWL` zYMRE|uH0rE4sCT;$+ptVft--Ib#6E>VQ=Ji1+l~YOEBZh+L_s+x>-u8+>V=u}|GG^--Q@IfspR$9S} z%{sCrasn+;FS4-xB!I}u_Aw-9_XpTOd0Sa?yxbEUPc-@a6`1dM7UDm-+l+Q9D}=$P zP+uEqsA_c=f)#DuI`ip<2N!Ltr8l7qxNnS5%Nw5Su*NryJp{w!D-e zczVh7QlNN3f>}k#McXl$brRQhIc=D!mvo~V?B=l2eBaN@`2*_=zZxSY%_m~7Iyp6I z*z*TDlAckse{3`#y~aE$KN#I&y*Nx99xX_R6W>HQl%)0+$PCC7Bpi<*qi-deW*RAP z8+D2TH@TJcNzeHE){a?1xjxeH>bfh%YeH4ocaRf?EIqxY<=fSLTXMPk*7}#X1Z{LD zpn27Gv0S;}l4Dti^LQ|VBbSdP@or`mNuMzcth!G)XFBD%UgU1)s-l88zm)mZE)wzW z)XT%q0(1Yx)%^9G)w=7Y@gHiCt?4It^16P?9)N!h`jn6zUT&Pks}3$9Nns>(ZDriO zNpkD^+nk+P)J^_Yfr)YVHD{t}W_vAk%6D=D6DDM=qt4wC=9PC>9volk6lW9zqdRBj@H^TI4pS}qshTRh=QX8iokv-_UVwkPcJ ztYB52>Em@5mU$g-^tSM+@yHl!WGg7FPwgtes}7`oFx$TXKAzv@^hoxx<>R@<WvW8s8owZi-R&F1y6k_9VeKG;PwP#c1uIh&q$nAhrkhIb}GC*?@!EQ$eG!`bH ztRqlVe0Zz- z{0Rl7X9whinx_lMBTh~X=60@_aUZe56#}hM@Zk9SlcF7yKJq8@%$@22YoQVavOz=#(mEYC z$)%Pmk(-sQujeYv-Hzr@-ZwvAL14N^rCf8xBq51#&K$g_@m@kQDYbq@fM1XO%ya+z z#20(mQl=mJy6j`Ld`U9|1+PJi{4^{%*Q;>^Sv8$+XilC~E?h)IAKaxEBf(oh;CbjT_c{PPFujn?LFdfi@&g|w^e2t^{r(4GIU+lVDct|0%L%)?++f!(A&ot|t zu-e+%jh@1;P`)e2Ib<{CNi??IS^KyKK;>C;$F~@xZV&P^Cm)2@Jh9Yp3ghLcy(51S z?>c6zh#rV1&x2{?hw?xA;Y}Re8(`-4Y(@+=gq(uWuK5Z&Q*e*(g)_?=13ZIvbUJcvt66nAq zfQ{3TlUX_*%eB6GzP)U`ux7GfuuvG8?{uH1;Z=|QHpcP@Ym97D0lA+B#KC^yspYq` zrNXw7*(?vAIPc5)qg3m&KM31{1(%sYe<}ya=f;?M@Mw0&wOrL#2Zy(}`{IskP3DmI zjRLAO6kwb@l)eFdQzc?|qdshPP<&?R4<0L%m`$baPJxzzP`SdUMIDo!O&=x0%)~qV zs#3YNZrbtbCHJUp6#hkxJn;rb$L$Dg6f4mkuNvM)wo0BRRCj6(xDt1Zj}_4{JH#b z)7b`rrU;Bm-V}@*u@9Vl^0=953OZI2$@a0mb_1ZOfl#`6X^==a<71(@y!y(QS&NcI z0OjhbY9mDH+i|l%N3+I{yQAeX8_C^Ny@3SH8JxWN);e;_S5N%VWxy9qfVb1zxq+s~ zn8MYw4p1iu{FN$7vDDR*#w>s2-}v+n68DlMtucg%xFzkC$=Li&1R18dp0RMXX}x9{ zUf!LvK z07=LJtxQ`4at`Cd8_gmF!P7R$h)_`-WUS4BW$D?1BwB~pK;upTs++iqjEpNd-B;CW3Dp zp!1?jxDnDt4XHA`8~ZHDH?Qd1KzR^XwBKL-kr_B7v)ctd3#r^!Nd8cQAlUm3%gOYPUS5cD6s#NvI87TOOEEzUh3kFlYOsSD@~enw2=)Fpgnr z42K;*eB)hhbQaKTGdol{USXJNj(Cfle85RqH&#yLle(n`nwE_;YMr(%dd;1zKA59X zO8=CG(};ozU2!GYwlUsz+-r_NwfEH=+nsdi(TZkX89Z$W5mAQPD9oje&kV;q*pUWD z=&G26!ukq8HFC#?SsJs+MBunJtWuraf#*G;bvWGO4mUSj6g{>O$5z15{tg13WCT_c znB@*nMj!)v9cXV6HQrnG)cj_)TC%dZ=qugU`gu{N@MIiYj_$nk*wE^~S6pSuwED^1#NQ~VZBCqvih=G-q0hY+OqO*vG$)SF4?j`V0|B-?e<701sXbqh3i9l_K=BTNgg8QR(>8AG$< zUYNR#m-m>sE?3k1(h49nDFYnY}Y0lf@MxY&Y6G4W!2=LeV`_ z{Uz3?O|1*rp;E@!j+sp+EBivf@zCFgyx1Hmn_XVqti7QjduU3YiP#z`m~r=q44$D| zOY~tQNQw=H-N>04-g)$z&B&7LOdm8Ki} z`AL-(JV@eMJoD|*_~spbi3D#bK=L`!@bcb&=W1WvShW(sLL9!{U;e;&p`Q}MU3pZ-Xy}R={B>2fH$&ry327Ju= z#kY$sW@nk_pEuGu_1`b)%d;79PCSZH*7%RbkE1-Kp2Y`!d2TaP{3|cOelnvSyy2^>hDk)+8aQ0O zJmhyDY-m-ClQL@c2bRUeXMEY~ym|AgCn;CNK0d~~?_KF1_BJ+G1?Ce`$D4a`;l3#| z^9ZxB)zwyM{V&f%N}gy3FjRvk$-h1}sTH-#T;B-(iDALC-izUJ4PepNLBqx;;P=ZO zzmR-AiRo=pzTdz9ov+X717y3!cpf$V>T$pR{g=P{=ZA9G{G6Gym*s!5%l>>WDdZ?V zqpwW=wat7`84N=k5hMKVi~8}GJwuVZ>8T0T9r)%Re|-C4>ae_4#^!xrE%|?(#H*Y@ zfimnqANWhh3Tp*>w*2>^fBWKoFZz#<)$g7D<74&Py!_CX{WdSZZTfFV`d!oo>;_pc2cO>&WQTl-q{+*qEu@PT?_zemC z7=QR3$$X0){OQ4eM>4-7ng8dJ%ol_7J9_yYz5I?|en&6A3mV@5Y`+o5Zx-aQ=;VJc zXiPjhKVVAyGv+HYqJKKq*IPGXdpfaS)j|B*h)27ELB+1K-FTHX>A~N28EXb?SKGjM zTR#1fFm)`5@H8^GkB^(hyU$|({&#=m^2-+>#ZXDc&8xef?fvw# z9mhzZJJB5!YMaBJ`QH7m4t8!^Gmy}c)`D|t&oj1t@s}*sC%e|x>BKW|SKm?ixDNhz NR!070@^NjC{{twIl1Bgl literal 0 HcmV?d00001 diff --git a/Svc/Framer/docs/img/class_diagram_framer.png b/Svc/Framer/docs/img/class_diagram_framer.png deleted file mode 100644 index a598c9b1ea73a6520db56eade6770f9064208b47..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 21120 zcmeFZbyQW|*9HoQLwAETsC3Jrkw$5xyAh-tq&p?0LqS0)>6Y#;0cj*fq?L}lj_)tt z_xr}Zf89Sn#yEp>_Fj9%TruZ-<}-Jcs?shB%2KeQr9UA z1tm%!jXT8~3+uYQV&3B;Z6y=_K0>b}TaQhzEFLUg6bWf}>F(~aEkcV(V$ipP?z_7H z&fB}Y1GBdm_2gtY8W4mpLq?kv*rL)vrdpOdPpy=c5Lm!>Gz7#58w4o$h6q0Qzy|>V zDJdKQ75pavAL+M{f8RyadyDj+@3ZiN66#V%5~crBLI`|^U*@Ez{Zquv zR+L^xNtIU0(Z!OMkK+*s7rht;EiJ8xi-ncYGilj>Jq~_}(p$T^ISFxcdU|?tc=B>M zx;*FP78DfZFH+)TaL9b6gys^s7GNL#v^yVy9n**H4T!s|6Pb98qT zrKg8C^q;@K`f2H9^WT;nT>mvJFhEZD9ZqfzF3$hd4IUMNUlmfd@v^kjk+!i1;sI@l z@jily{3-vx?)=1dGD4U1p_0YMz$skDTK7vf$H>LO9kMPCHHy!sC9 zBoQ%YuaFyE+{+yGof?54lsx%wyQOO~yYmG3nsrtKk#lsqM(%Yb4N9 z-5q%LXAf=eFZ(zioSr)PpIm%CSlZjKIT*e@oqKNeyyQj$KQxQ)f_K z2P!QNm2M|U7%yh{b3F+Ci8Usc&Oi((6d0=I2kwePF%-om^-bF4jo?4-*Ze@Dr-jg~ znn3t4v;8NMjhj8nzLo3MzL4Qm;6VPUTU}VB_D+^VjaUvUP5Tf!_{=)v-e;$8k|#@^ zE4qn>ZT>AqMlEiy&gN@vvt(c0%Rs@t*ZqFsBN?bvlTNj4ky_{csE=kOmYf&MOrIl_ z*1dye#jbi}7`9+%Ug1Ivx*#7Ru8Yo2e|53_Mqh#@=V5>Ado+$2?+6^K`*m~XQ;GDd zZjb_>$2p-6OHJ-p^EEb>tW_GMk9j!~GI*aqoHlwaBMx0td}|kaT2kK1V)NLpE(coK z<6`{T%ehX?EgOg@5&d=8xY-DYZdEsCUP0TckJVch38?hjM`++Wk7~`!-#;d4b0eOu ziRo0Dh5er0q7!^T_eUm{bTuVfWh`^vRi^W4m~e56U&AX~6JnZ1C2-lJ9~N7MS4DdZ z9h9^#i6#%&|ETtE_%*XSEc)e~Wm-m&`Ui&^_H*-%{=}{8ld*bNwhZ^w6e*R01?W_aC?uAOgWwLIoZ)1^u{U_o@)=v$clzzV^I;<}_ zAoQz(K~?zkV`5jsv1HtxzxJ0FC|`chvtj(T;y!D*)vzANOKRkmr`zOKB)A%gG+fz7 zZA$}r%gL2_R~~RPgz@5Rf64yr{CqurZ_4Ug{B3eq6l1P6keg*V7P*;`*SE0HasSJm z4_jThk00sVRfg?MeTbj4NLI4bIHnTzD3$o?Id8)_Ric#NO;E_PM%h98BxHxSH znOJ8Ld2#WYvm9IJ#OP9sZScfObtG>te=B`Z&M75pGIwmd@et0xOKZFCF>oE>^WfzO z0+(i*i1!=TaXhWpTt~A7XNZIPPj_d>9B4#e)-;}s3YP`0xd>eStS0O;ez{YiWxe~Q z$eh~eXQlLQGNTGij>`RYhNw?n2ESwO&PrQb$6YCW6U;*gd-JhjUDp>UBfI5o4)b;P zwy-6)scsJ0ok}A8dWW2^y=O8pBoF)Cz?2yru2lo;@Dw^IYmNWJw_1+c`+Y6#RN~`}1gYWiJgKsA z9LslD1oevM0^D7=gpJ*^-OD*4njSlIC_UMcg@0L+Jq5kilr4zXmYd7kTSrL|jY z_3VgZs+=Z`i-d$JLUH3tt^!*fzNOgbkHnAx;qB( zKHGpDlB-Qd(xw4&hu3J@y~WQR3;G7U&IU z`RVk6Me6NR(|y2aJCnXwzhYEPKp_1~2D+y3){br7j&00@*Mfli`eTO^*v@(-NfMj} zh;t~uokh~A=ZXvR{O+t%t#&6f&fs)BqEjUyvCkvDwyHzK<*%`un;i9dC3RxT&f8yD z&)%KKr-6dsulSaYP0s+O$N(XuB==?+Wev|SHXM5p69vk@DtIKe+M@B^5jm)ga3UC})l zY#Vl={L5Zl9B=wNdF3dbLx~qPEGJ<2c!+K2uT$b-gM}MGLFj}J?>lVjGRcBtSRDEc zKViHuKdA?{{5?=1m|v*IdZP0ag+AJuG>Oav9S}P=BW>PDWl(QCjpHo0^-62Y&SXK1 zp{mGK43+D!>;$M{FfcF_79ndP+cj$(V824st8P;&*e=OMyY%$RjM5g9bZz+1Y7E*VK(p8W!q{=a2lO8WPSBi-(XaxIUC_2V)Q-(DgT~guVE}v{@B}6>WON z!yxfzfRu>nWekZujF^EZsq+@LGcuMa5J!!KtM)%NBLIc2`5hIFiBoaWGR^Q=uUTNM zcIZj5v(-Z;xJ7^f9X!Qf^yNROvK)eIsnVY4gr@f00bTCl7P83}hFDU;Vhij-2B9{M zoF?;&z4sZ~lSTaz0VFX;m>{Dc_E1(Nq@&D!{F9-ua4lO9}H&j-JIH-z|HVkc|dv~_HzH(Ct?H>cz0$q%RcM%WXMGGMPzjb)~ z9ek{Rn+CRdyh9>Qs0cm0!(V~u{`O1R`hV43jUy?pq48J$r5Tz#xIp!PYwY>NpgSHU zKR^1QW2bKWcJ^fE1e{X#>f7(Rn@0Byw98dgHnyfMZ5SMQa z-6}I!G1BlQQ3;mBti<1+|DUbT>DGYp;t_+o%cY<3Ge9oR=a) z@%Pb-{X?Ap>-m4mzRFsvT^)!P*z+)HbK$)IF?s`3f;l_{cxUP0ogLSKcm5y0GoA4u zZ-F!!|438spP~XaD-87k^J*6Rc(?98k%V{g*s!_r+yM|Fyw+J|X=%Z9c{ZhSu>&ruzV*GC}XWsQ{X@bKc zS_({kaP!{;`;TWfK6(GQ9dM}dwXptYgNeSd)6@j6g8*E54Ypit|1Wp`CXN3w{>)`! zg17lGf0jP=qpD&iV3ioaWp>RM|F?|{t203T&tO3(EWx7w_e}Knrpi$Kr;>l}pO;_0 z7K8Ir+!-7-FWaaEs7eX%(&FD*Et7jy zRt#z*iVz<$s5S()ux^{b-=~Qodg|ZX0~Np^dM)GUQYQWT$F$O`dwedhK6%lroaw8BT#S_G5 zB(H#Zm08|;IcU;y_~H3=2-)wPT|N@AH|%;f6~U}5;H;%Uvv^R0_Omk#QwbOy-AYiF z2kkj3$q$u=we;;ZcPfR%p}w@LJ0@hGAf>udrMOFUkKNywv*}c{``+E0T|8ASiWH9` z>}RUMI`+N!J$u}k;>AGv?i^U1MSH@nxI`o&EyuAmL9vp}Km}sI>?t3SFO;^O{lxc+ z4jKP2M_e|~(nDe-Q*aF7B&Y1`_w&Koqz4M0w`mdR6SSKZV@tIg5Hkx0QW|>Roi+K_WP43b9J(Ym^K1|?mYah(sA}`s0M~k|@Rez+ReGT92Hfa& z-5Rc3b3Ga1&yu6@`%>e$BBod+^Gew3(4>0KDl6k%oY0GRF4^8&8FfnO#eFhI9jG*q zgnw3a$@YDRt9ny33!?eWp)?9MxzN*YLX}6@6tH2PXmu6QX-eP24iAKlKqMS4QUj+T zKgsV?Dv$YS{Lk}-Y;dAEtrerss~0erPpeZ*8P5q!Pm@NH)kvS?mxb8i@yBD zrIZD$^=>9IHeV360MAJ6rxX#{y8G5(Wka0z`PTgbiG8}xr<+2GvicgseA8)ugRO6jM)u04hOPU`gzhDb;#JUjL6@Yn+Wa z%Ub@~Y!^70ee=FkJ>QDh;tJw)%J%VX2Dft8nzu4-?I?_ZlV}CN04?h%Iq%0;KY8_O zjy;3Ok<9zz_^Pc&sw^$uD8yV$1Lwc0#b;-_BrPT%7)U`x(8){dkUn~t&WG&&?DQ05 zHYI3M+r&G$Ea8LCQ@L-m7XdinK`%734z`zF-J**ED;^rnw|DVkJZ+cL<)sz037(72 za`ZU7ba;Z3mtz69$zPS{!f|PG&tH8MsBFCaQ8Hp*zhpJl^+M(~I`FRR1cC2Iz{{H5 zPjK*BU77oAC7_MC-*rrMb|yps*yQgd(&x@19$$B0fl0oVCE{%U$#c^8_;vyZ0Y73L zEs`m?kE-)z?6KolRJk<+_i4?oLDupbGa%Ud%nxt;=X*0mysK*Eoo$A*_{V-7tgOs1 z8d6@r73rwAo}lkSCXl^GM&ckCyaL!!7DJps=ljpjx7um%)A4HwOXy zkq_1a)189Nu-C4-<@yPw>K9#Nh&c_gB75T>-&&XHhK`pZ)SC5RG{>Kl8v9l%^=*b& z%84h4U2G86&t(Jj24zCv^834y2Iuu*u-hEi>ujb9Gw>N?)B9)w7WEp?Fn+HJNH6FX zM}@Mqn)G~A79Xx$ttdnV-sx_qGun{o*`hi7cXD2qc zUoiq((4nqV4GMT2v7_}RipP}{(U?tp{)6lGC`wF@Fg|3jYh}Orz(HAP=e@K%I9lo( z*P>ZVkw5oQ`{+!BMdeZ}(oT}%e~lE^B4OvoyRTg6MnA;8*kmqhrkm?AZ)3-^-WOj# zvj{M@7miu@FZiQ!k|~FN7k$XB3J#_vX!1O8$n{!_3f&AV(A0fvfX1jrK{6YNh-63f ze438O0E#CN8q&^~pG{eTfzRrh6+1Q)#oXtza6mHaOp03P`Z)_HA}dVa0kR{=54pOC z6DN#}?v0G)&oN1bbu z9I6OOIQP-N?4$C`7F>_z9bRm7C9FUB*@qe}6S_hqar?VGz#f^j(r)>4<(M`1jx3%#|01^xMA!&^Fa zcDm8;0+zqjb&g@Sxgn+@-#W7SK=vv2q1kV~_H_AmQXxTxR*-N-OsHRer|WvV?a;hu z#VOr(y~(-v?MnvcM>xFp0zw{^sz0}Kv+p@WphVSjTy`#gWNTLD!eh2W7ad81#1EX@ z7GgX$X3sTxsE%=@Nb0kL<(9qDz(E%&yhGG=S*Q9+tjHxWmYINPPBI02g?n!pNpT&5 z$iJIoYqH5+cPMXMo$lG*dt_~be8S&$p=3FyU*Eo&X6&$pLnY)^k;;&GxC94wJl-Y< z(XHtW59Fhh-l8=a9rE&uKOtwL*^k-4i|uO774?~yVBz0IaDFca<&Z}E4)%cEAu3@5 z0=EnfexHjciJ+Fi1pwoeU;!M;I-St&)VX_OA}6s*xN#h!K7qGUfoOKpw0k^JI${7W zm6=}{fAy?r12vV}e^x^amr;zdmLk&SDP8xd(D1BzdnB6~#pfl)$I?(^=i^e0!4a|U z%BnzXo&s#!OyrIMMnR{cSGD>n;5b?}l2&q^Qa9DmruyV_{) zNyN;oj!Ql}p_pmNsbZEZKA(RG*%YUJH|~G2nWj6!!-R@wx{F6NUtyD??i)(t`Rur- zEc?gDrbuy1=p;_KGiDTVl7mS>RjA)Wd<^8SqH_%TUHBJ6)Xy=+Un43In=lf}NYwgM zj1)p~MXx}KZ_gnOZ@x=m(60&uyCf!FMRM1NbfD$-SB~BFLgV(^bb8f$P#z3+B(5Tq zC-U!Juvk{2bE#@gceI(M>0ZQ$(*Yf=$783@&8eO|ff>~LdFuTbbT*&qV7}OcJ|RQA z0Mz;FB1Q3JqFu)-ectvb8*$;giRU~@R|Ks1hf(75JB9;z6{=qEUkj!{w+vr6Snxb} z9N>y*HOd{-7v=qWR+MXv5r0|_3VWDPJKkii`1AQF)0_Pbmn+|^jYLBZSSjkN>uP>X zJI~?fjQwFo#19V00F*~8ILnu-O)$}ohrHPf#_Ef&!%H_Mgmp@LLkPU!RPh2aJ;wo! zXU;Rj?m@`Tf1&17K`i<;I|Roz!b2ieIM5PjZss@B4LY2G^^AX@4sjkt-I@XEs`HWK zAS?vB8aDFCuPCH+WAx}$^uXbVdo;up6l$AFsOJ{C&av)x-s*@8k8aAMx!fDjyd*)4 zq$k`;hS$o_WTYujb0{h3GyY!)OcH<|lA|<^vn05z4DH%(PNNufH?mNLA2Fqh=Yt>} z1QD3d2(g2$Rd^S`rW^SLkm8BSfMJHs6v5BxG063QKpxsBzz2D+HsHx$5JURlA?hM3 z)Kl@;{|0zIhiSmK8>-vhD<@=Bt{FT0pqCh}JzEipq2A&fV8)^FUPux88Mt>NRYl%P zf|$Ed)Q+TgRq?g7UXAbn1cU@2FHJfUKW?}Vr*og8;|aq{q-xHVl9+-}|(AzyI&@|Hf-l2z4v%ks zCBsn)u_TtFM+P~wW%}CBHb>=5OSH=!iZx48+P2MjXp-)Ie zxXHbZubco5s5*cEV*9jptt-v&=al%D9+`K}?~o#Pe*#|fOw+6UEmo~kt~UX44q1)qr0Ay6%-FdPDwLI(OG{D```p+fNX`o{wpf zt{bmO@qY+e9GN<6J70^5UDwdXWET_Et;$HSrKwi~o-2z$B#8YD8frQX4!$jheoxzx zoRN$%PF;{f#_yL#Xk+#(Pz@66M=0$@#*oq3*^&%A3hId=)#sNiJ_mKZYx=QRg!e)} z0l_b{_1VWjM=kXR3>od6a60j}_W^|%ph#+TD2!Or9+O~o(5QdM-_2r#1C3zztO2k8 z%ULyn-gWiI+E5sW(!CXzaXAbd=VF@P`aM5Ra=$l0^BQ!VD&Y?phoLT8{3u;;*Bu6e z)2oH~etl#7Hk0>vcNc(1G&CuBdAi_;jjQ35vh<>)OtC8*n_+z95^iBtp*AKXBmGmW4c2CLBy4DPY(`YZmXCCiHo5L3;VQWhS8V>3~g zIl!s40wHOY>(On}OVwtNJ;^Ax&Aee$Dz}8+_PqS(aDd3~>U5;><9mq(c&J2 zw*tZEa7O+Z(S$d(RGy2bP42r^al-oo0B2c>on8XGgpnN2<%`FCse+fSSWrMC-*?R$Yk4k1x#T*^aFjy~kbvb}XBYo)(`6h*rhX_YJq@^0wRg z)U*SghT#Z*fQ|eNOHMY)vafr(@z`>ZNb04C*%P72D9ob4t<#>(YNM8y%vV&n^NMf8 zmS%_*h>SUJ(or47Zhonse2bvblM3|ctJ?Sq1~pgr7_d0ll7X+fJYL@D#Qi*d9PCc% z=|=naDz0a;%_rS>+cB<<&WX>3{nAA60$Wb!hkE<)@;F~ni_V{_G1lx{awjtJ`o%X_ z?bR)e7D`=%{V|(*)VQ5nz3_GHLgEQ=#NPSzj%T(?Hh)Lopn6Z@?zZhE#7_R$|Fb>keCok<9(kySy}hT#wL)LuUis(aXwd@z z*}1K2h%79^7$5BM9i|z!wtK&K%-wTQusxSM4;uyVPcN z32cL-L3?Bij-?fyxqhd*3)TVWT{OcLrd>ZBPn{P$W^|wHwxN+wZn^};`Fsl_&4kC3 zb2SVm8s?wfu1-(8iz_4C3y}@Dz1SWBgR_m7i@X?(l6$!rry2)m;H0MMGlf!8FJ>m7 z290`vQVR>I`i?Er*8mHsUch%597d0F0tfY&!}iLwwz2(O`zlZdFsX2?0W#DHIca?5 z!qj#ifi)FWDt?D-?_U#g_DhSjlOQ&0^-v|(ZmO5SA8eGLXYpc}{ntOV+p4Ids+>*T z=?v!VF+C`ZoGbpzqrd@^%=h(G#7; zj7#T2SCO1lC$)luDN;(L=*&-Lb7^si+XHHHRFp;WNcwiK65SDE(S z`dQmu%LN>|5pYHaaAVU&52wFro4U%UbRALv@ih?3m&yon*H`=jOPs%iEJ#6YTzCj8 zj3VW7BiVxkz&tJZ6|LEUuszICh+TVr<7FZTDYFpfRmIwqD>(3-eQwuB-2F8E_mF=# z#5VPGHCbFJW6%mWdf>72%x_^f`O8SmFY5!0Z))Ndn(TFa44XY_Q(14eQuQ4wZ!&MV zK8$>KjASI$<*-=HIqXAD^}mM|$p}Fch9(QMToT1rI_$)=bt0)8dj#EvAuC&3@6lM0-*Kbh{} zJgs+Yavw^I;1ibJUsMx%lIx7lHb)!cWJhrYd7G`-t9dVP8#W-gf-e;M zr4h2Y7pxG0^EFQj)u(x6&xC7y0G|VLaY&`M4IAIwIo{^iR**bAjY4Ep7R$b)R6wOy zrIC&;VGRm*N32IAMK~qI(J2940f%aXv$Z~C8;Oy38%nBOx@oe?fjX;ln7Xv5vfuYhlVf%N$ebgU zOspfpU{ulB+IZ1rfKEMo!@T-N=?c%FO(l+$%@elm#lrqndFn=ab|zbYhs=chB%(Ym z5I=oLh*J}Y@E#*0qX|bwBgTizjnmY)@7MZ8ap(@~b@3fAq3mj+M$0E8hbEM*yiDDz zq}t4rtM4~3B0qjh{SF8zE%IwuYjtH+fh9qKZNHOM#411Guwg0RDw#shm z(sXXVV?n8+Tk#~ABW+_nq^)w%YbGu+whrHHaAJ;LXCy z?Tp@DMQ1#Dp&iFwgTITdJk^-MI+l+@){wm^%spf;*Js~GMT4zxLzmV7%Cg(cL9@SX z%`l(jjJl`>XnbzX*f)r?BsT+5&V>R$L%QGy-I(nqck6dW=l<9^N-|+G{)_RD4gc(2 z!CZvIUk}vvpPRKCvUpOGIW=TwH*+&z#6GSj(JPfeNvK*d02^O*f$(^j(~(%n5yPgp=wvP%68DWv%}6_xzZjVWEh`LOk@N_U}sK zukQPu<>;e3EL38YH*Vddh`2fDe~OD4p4@SPIG0BGBu4)dV3)J0A;Ku1@)uiC4QV>O zI0EXNZKD;CY>8rmVn`5;Y5kd%O&pjT-#Q&TKQn)z7Eo%xNCZXcY>+9u%@)Br=U$3b zO{tnglQ}1~NU}eTpmd3B5pYopC4_vRe0qCdsh&OSm*5Q5%BRko&<8`vxN4pAmZu6; zVL3`o`)2)t%CEz(DuI;zu#V?t%_u?&znP;k3_7r+m3Z%%g^?eV4z|%A$wn} z0<(O#80k$15fdEDHQ49!o+x)-vanU#N+Mx%t4t2uW=?C0dW zcm}i%k71&|MnSx7lYXLzb%8r3DY5zchL1-#DRE~y{K`wqrnm!nJu^msf1AYgH~ZWwOG{M_QUld&y<}NifM= zmIUR(Yu-KA9hnJj1EY&`>B!075x(zL?!{uS7Mf`x@**`54)*e;Fb53g6de>4s}~CF zjJ7E{GZ}Mi8#lcy*zLO*d{V8&*GT#v?wtUM|oA9Ad-RDzhV=1-cY!izR(E z*IXR+?ej)-^(Ff2&$DBWi(;D70h+|men}lO)%y3_^Z8F1_*Q9tduJXa7Z_vH)M|VY zITbK8Vjr0mYy7#GX}f{2y)X4gDxdLYA%k|0XHL0qN*tPoY+y`4(@{Zb7>O|+k}?P~ z$05+i^kj^VrEnN&*75#`2_P@gl7OyBwqu7*JXQ}Y4NL8}XWiQ7epXBiDMB0PPv_A3 z-u~WS+7MnSu#&Z~s{j+6Sq=;7`q5L`63}2Mo^Ea-CNB?#BIlInb&ev9dFJay-HazT z#(C)Dci$s^^(js*ROPzkv2m$uczt=DjM)Yyw}we3s9ps0<-bqn=EP4UsK%Pah7v`i zP-Xjnr#9~OEb-T2nwOu&e|xabvPzi7QvHO5B75YiwPCm-{Z@S3{z4gL@}-;>+YgD= zfhxC?XM2d2r}1^NU+}b0T95hqxV06B!<}#NzNLNDQYJ9B0X)=Gaq9ejw*`Ig7q^rW zD{>kcoljQA9>ohjd9b@<*zsgvm@!>=K=oX)usTMa<4x(t24w8<31u@Uq5@2r;m*xt z_8W6nXx(vc|9U$|g)-`{9+QSLLf(kXwj{cJg^sh(QSc^9ws!!OWanmJ1p#EW7M+Dp$~ zIb?~+(0+n)5jasnkz!g|iQ)j?CEBjh-6k3XSGg~Tabza0!RUdT96QdeN7=U zTrw<-FaY$H(QD86uEJv4=WDO=$tYbN4J#-Berxt5@Ca&v488p16U0)Y{tcqegat>n z8-;8GH}NwB;x$)|J~5Tl0Yuwt18Q)$xg%=S*d6UC5-II;^%M7Ih!tMisj9Bjr!B48 zB5J=Bvh1>I6!I+0!u=zfv}7RaD=&S7AbzF>38mRI-B)p*1I!z5K)*2*y_qS*^d5dc z8KffhS|Jz{sOA*N+&$e@hpveuB+A&43*xpu%;C>$2n%%6)=E!J8n+tY6L^4Pip^2c z6)lPti;ri%<-!svzKA9;i_rOFt4&?Duv_q(Ol-BEw&CIr((U6X08FM@ggD5@Hcw;7 zy6+?9K3nVY!l1`vgkS}7bK8cC-@waX}kyQ^S)H%gZ-|BHI-_Vv{$hl;M;1jMY+Z}HVz_c$v5*o4@oHiD)8{Taq zXS2<$*U1?yRt+mlX311Hc~?^ovZrT7e9v!6G&svrS$kp~BK@mH2dd-Lhio#^ zCO8RtzZGNgu*%vMN}0V}u)`%NsZo=U->&LJw}gqj_r^F`GCAThBMH0+Y(y{1G zph2%ncl%^mV^PT!;51C15=b=xk@VZwXboaRUxR&!>R%5UzpwA9L8E;inQAAbB$*+NE&~VW5HK@0RgkA4GN_X%99%kbE{AlqG^afNSodt2+2Sk+h zBX9y2ZwMM&uHyKQUv%OuFWy576*J6E%tw$$1R_ydLSgr}sXV@R6t+X18gV5%HGTyX zw%fN0p+ILnF>{M}0J|(9=PfYG(M#IdVT3$SWk`d9@tt-bxbkml?Xu`t$qPt`OJ<2D zE|3b9>aQg8M{yXpiqwY^DS-SL6F|A&3c(etXsqy%+ncY&%zl^T2?$|v(vf4Lr(e6i zlrXf)rLb%xraktfU(#=51mKs5#vw;!ZT*kzaWS7T-UX4`hx! zXubNRR1H8IJ?V$#ZmcSblKO)0O5?uIlx3MZ;~4p$&D)k+63d}RiEBWC@x;D6V0Emk3>Y%Mn>6Kuu`Um9^^+9=AXea(E-`ai|1{kf<1xulmAd`nB zD4v2}-05#L-cLUi3YZIIg_BH?;@s$52&cevn4_;idj@hoVst4TPg2LXDtB~+Dgk2R z!FT_<1~|9e`=W~8!?I7K#Al!ltIhQ*ll?QxwTg;QB{oYV_q<-%iv zOoI6RaR~d6vmb{yrwc0a3swJ>itf{JyBwFqvqsK0>cN4=*Cev4d)= zXW)QkLWXwUnY=ZobORi|Nl7#UVO?JH-dM=ydkYy8a|qnby#QPm^O!$~84 zpjWJ&;h@_iE(FH;1KPz`9F@LpXgcq6WkgqvNijkb#7hADkuRh6W;r3g9um1&3yPs30q*F`85TFF;GsPu#>F0odDTo9W^d&gpnR z(FZm7eE14XV!ywrpB@?HjtZ_tGQinHL~8qkh1uwEY-cr755U5PPjM7dWp;?y;A}-x zeK@YHWk<@cXW_bJTi!B^h)QXKXM~LZkp*$fI-W{+CiWiR;OOip?ebiA(nmIv?~9-A zoI?OnorKKE<(Taq870~J={~^5D*YEX%zx`cC-K{Hh26f7cfVVX+y(A6>l-^E6Paa> zJa$Q>QvLeT&quu!z3fDB4}!lswEUitVR}`?#s|TA>0D{_*{hOWh=VEj(yTB>QUpZw zV!mJgMJ>X-;N5EUODZFr z!PoQIS&=kfNFJkPVqL4*o8>=7&q5~Cld#riX01B0OfMk!PS^;ubeSPrf zctr_ldQ%UE!T#nOcKx~}Oe?5js_}Y;*&e z$VO)@y6&SqFD5e!XCM7^mkL>_mi@w)_YoONobTM-1*+GxpC zK>MhQF3=~?dm5f1CYoL3FT&Svw)B!g5(Zrlhz*6^+FK~}AA1frx+}1|@VF=pP$=mZ zJEnsgczR=a1KEK>8-=jk1RJgzDV~OAjK#>UqD;qw`?~_28F~n*^bZQle%_@43 zx0b2~32m8}h;k89cL5$~38-Po(pHKC>-n>Q9oP-?JBk2?lHx*U2g!B410BJZxyQls z(&*Ti#o^9JLaw=e@cfgKc1DG-W-;u;08p~4Tk*f@v?$h4073b>`p=0_5nIUvSA@cl^kF9MD?k4k){& z)6=!K+Pa3CKT-D`f-Ko}(Zbv3p`|iGkAW)@3^azsJ!;?QP533hcy+ph*P)Gs#WRO& zrv1n<5x8ij#XX7;BdP8l1qtY13<wU2d+=ou6={D{0l0QJlkNFb-e z@|Z3+eq5Mis@V(IO(Q41UkGy#5cN1gWK%{;iZ`{+Znc)pfszshpQb(jp)An z;1l4_;bJry{E?q6v|(=XXAOuu`heA*T4MD{aIjJQR>0XMX*dR>1Xt{aaTx zeGn+8uG;tNIe<}WxI^>iejZpNTi^ud2dbZS=cT3oIXpDjT5h|)*a*W=AX|HAVh;h4 zt}rkb(iha-rm~RT<)*$Ty4TPl63lu7$Bard0E_!wS)}Q61`Ady&Y97Xf$}M!ytYej z_qv*q?`sE3E|OwFK*Sgt^^D;>1wbp810q?=n~`K3YBfHfID$Af?UGi82iFVES-eZ6 z1ViBvH5Qf7qoeeyWdQ@6vU}x1PpsFcsVh0K84h&(L?#tX5}ke13Ywl^t9XJb9&D|T zxvYreY_(=bK*A351v`B!xe(Qct_rTyMW|#<0)N88CqQR170vUG%Zch>g}3YDe2kd! zXDYH{%jlH1Rwyi5Q&(k^$USO_#RKQi#vb4KuHi4wl<8;r-&~S!<@Pdj8Dg@go|WLIi%!%#8n+zLD!dNm#)w^8DMrAB}K zu;Kj*vwZAZUG{V--hx?qN??yDNOtOG_0!>sh~OZSrj-YW6O)Zk0;%gW@{w(=9EmDI zWq}U6+G#DBBEk4c97=(4uC74Fg~L7&=_z8eR4eoc+U;`b7P&}NMO*ad*HpN^N4H0N zAfg9fMX*Kc!-=>3Jm13}d%(jyt~Ib2aZ{i`F^6UszL2u%n1K9g4WddV5?uo_5CcB0 zW7jxZBm8J|P5%+P`6Q6IOpk6Fsm)$mUpmr3dr4VMo`eA*LT_&q{Re1 zW~1FnSVX%Y!@eK-Kp}M_RfnX~Nt5d^Oht=63z>_GfE?&bi;p+MXqA@YSl^@&@E5>& zy-9_lJ`9hdge(LGac&(C8YXxS%X7(r`Y1b?^-iHWa;qQT#Z^HXKmzzxAX5C%7Ased z9Z;H4?wIL@Aib;E_d&UvH0>i$yLG5MEd^x3zCLGXuKI(hTW>7+>5au)_s|v@$*zZE z;ofpfbD@(Zl2V_vJW#>R4sE;(fSIk7#$m_??RLKWwUZZgcxtq~D`TRTMJ@U=R9PK8 zQoI$&>O@In$MU|@xCH8hWzk-!pX?DLo20uX-a5JgomNGtA61luaE>{+j+8MCBO zSeI?HZXsS}PhX}28Mj%esSs&NSmHxmIbiTog8J6KvRE1whGSFAYkyN6$so4vQqC5r z9OSc#lHE?TwCM$oh=w4x3|`Pjpz+_)m-)iz+cEU867aniI2@NoU=?wYm{~j>Iny!G zvtd|q9AOX+3>_N*0jC)LE`WS+(vl!I^MoN(<2gMzeB05V$WR^Lxwh1RmCiY&K!2fu z7bE~yOmCz6;AcBP5s)z(=maqefl4p0!WRq`fEivJ!4(tanaT|OWq5a&B`uA_i~>T& zQrlUrSTKP>%q@bf^+B1cYrYDDUKInJ)CJ@6mIl3mK6}4ZZ)~QxtZy4IFKp0Pc}zyxSc8wY^pNqHh{4=Hvnk@? zU_3Et1_4^zeu{g~*grJDlLAdUp*~pqC?rK{ctOtqOu?R#%5vhe4??n0X@Wdlsg!uS zzSSbHSE<*P#AMsx@W=fcXM6Io!Laf=Fsiy4pkFhHr)eSESv@0f8QX&`ezgz*5i8`S zh%hr~u?IzvI?*+7dF~rj15)_a6xI6ajyhC62m@%f%jw=pe~q zIW^YCpaJU#aIbk$oc%r>Cm5w<_Q$$^(U3_gcR^ zc8Hp2e)Wv!Q&q86FOZ1kVncxepONdjgQ^-$X@g{tt+;fu&E%8QBP&x;7o8~M{-U=P+V5|?OY z=n^~LJGcJGy`so#wNt;TH}(2=vDFW4yOrtvlG9_uUM%B;Lb9fcdlxdxyl0Nxd%1Q*7jD!zL(+b1J`2w>2F|jUYo@NL~52y zJV6+hJt-Dl*-v|Yb-7K7Re9h$(YiR^xT-)$zdliSxvtaiEiHr@t@K4x%eS%c`0xS& z$*eW_xg3$IE6|l{=Du$KD4#OoG}4(|YeEifWweIoQv2SYYCc%5EIcb+s4=3Hf5+3E z-hMd(TTyK)Sm|ka&7#MHC|Z%A`2J&CbyjaJI5bY+Zzj-~1PVE8g#Yf~X~RVB_W-!J zshA@)4NuFm0x36FZ|WaN8|PndKUr$M@mT-x`yRi8or~_IGvKpsy}7&oz<&P-iH-qQW8?#}CTq4F?GKlWQ!L>7g^$MgnjwCrr)mt)&8kIo9ZZl%X? zwtn>mVf;D-Hs^Ert1ZC0NCF(aW7JDk8;t;GJ3MAV3Rm>?lWh>WeS{0RB5VA{91W|G ztNMvvHh+zBqb0khox&|ZOo8%A4IfY7=etWkRC-!tx3IVt5*Q|kQ=_e zI&ds&f+qzTdM-`>+L`Jz0KlM@g^JjP#Z;xa9IxM{+Z0H_&LYuTO`wx1wf+rW0|HNk zvI2Smo@`Zb*&%5MQsOUuR*wynKhHJ=%q8nPJe$&1Fy1+MeiV$I+WP)7cnN~d$EyiB z8vCJBkZP4Nkj$6`XON`&fHaCn5mX-O&M{v=#HdLClZ35exIf|?o<1~k1#(rm;cwp9 zS!}Fs1e6_YNqDx_!b_`S-0P>$FOE0i#349U#|p4PxZn}<0QjpY>>0D7Zc~WCu@sx> zYTx5W$G8sM%3*k9+heX^jrwDgi_?DRnb^zCq* zNYvrWM>VZjJbg%TrT@*#D?gxoxC5>hR)#?;nthMs>Cd^XvifD7fV-=e5x@-`HoiS3 zl@bZ1u*E{01LT*obGo-^s$9P3-y*h#dBU#5N(s27J-#B!}31%bwrIxAS)8x76+}SU&Vd( zo;kodv&)SkVXv}r#%ECa0cZAIX#-nN{{ygpz6z>qG9#L7tJG zr38dR&Ib~-S;EsvAD;*k6AXcO1|8JS7#F^DmZS-|K7yymtbFHkSWyw)d&K$`jT3P< z?U9P$CXsC;JvBV5=gMpSC!CRjydKTULY@5)O~)#dAXrWh?V$Of)fPaE+Y;$;Pb2yW zBnDcnnw6&1DzssFkEHIYG1?~aq+ z2bgMeJXB8Yh+4n4$KD*|r?1@Io^1h0uC}ewNo{5DM>6GeU_3nnY^bIp0ASS?Ufjab z&P`WkZJOo7EAWmFouN0F2)|XC0szh2{A;g{<6=0?OY5yZHn^AIvm5oB1gimuqv?D8 z>cd?XUyy=VIz6CoiLOi*6>k}<{}yn-JZS3cLjmQGQ5r`ZVTOlyx|m+~RI;WpAYkI(Uao9Vx09`ulB& zR;_~V=3q+i=9^-%owbHNoi94Qn&=#kXFETTY_DfVqkA+7vGyBQVSb!`5Q;Z>1;%fZ z$|V3QH4LD7g3hEONu9X!vm~U>1j<9pwHNJYKS}{K7u=S`XKQsXrIX{BdV}_00qy_U z$$Yy9=5@D08{0seDSu^bbdaz4;P~1Ybh6G);E1a5yH4OrnY+t^Z|*POxBU9YsPZ!`z6 zIe+^2COKe5{r`VqEpqjL3bXer{z;!(I!*RT^}C(V-@LWZ<6)Z`BlXUB2C%V}AljS( zI`zX6c#O~5{bK(O|E07@2ZCla)|kG1w8Tq)`mYIc%+(PecQEJe`RHa0?D)Ut-Un>M z0!K5Zo+*#f){FoC@|5tOBj%^Sn7{M*kiEMhUheguWwY~)K&vnBrqxbkWL$eswB4=d z0Z+1x!&ss%be>FstWL}h zgNLU)@7=Gt(Yx&6kAtGi3iOlLNzL06y+7H@VO{eKGatpSsa`8Kom8LBt|;(1q-ma4 z%%!P}j)$e5>Brt&t+naNRPWjy78d_YcYO-mHn(a5-~5*r0qM`Luhp@At1k;|$XRT; zn)WqUbJhBvhI~sqeI@nwehE4pzq6&0nZ0eD*Vn86-zsl?{81#~1y|*yh8ke?|Kgam z+u3a0S<>y7R`3|A1!P~G!@D&5iq^5EAr~PdI3ka~pJTrrV;*U9{lhCERzVNf1m?Wr)&HJ+7LoqV;&R3tVNvxd*D|{{aXy-NT}(L6V0Qhs zhk=>K556DE+4OMX#2wS4pWb$GxV-z(72$t{o=20|zuyqjeS2Z^Bi7#QGq-*+Y~PX!g42Pc0u3Vwb2<+6KQE-w3Zinm{8w(ak* zHAjEwCujYA|L680Q8&%!&A|SFyvXO7Yw=XEijWahUnpZpRjzIFU{Sg~~oi0h9rqh${8M@9%V8!(dGt_c>U*0)B z!&dtm+q3OXCxOE<({e7ae4wPjwA9JryW-MIL0X{QtY{KW(OSAoi-3Fbr|19!_N3Wd lF5pRD0b0N)AyLCWd6ylB^S?a4Z3#Mw(9_k=Wt~$(698?EPlo^i diff --git a/Svc/Framer/docs/img/framer_example_1.png b/Svc/Framer/docs/img/framer_example_1.png deleted file mode 100644 index 96c5499bea781fc8827a39cd574f5bdd97e2c823..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 46223 zcmeFYWmH{F(>91}umFKTa6h;QcXtT{C%BWK!5t0+cb9{^y9I)~y9IX=-1&BHdFOqe zS+myso;5#DpWa=&tE)?{t9Gceq7)hm0SXip6q<~*xGEGBEG`rjv^)|5Fwzbi^9~A% z6iP;1ME$G&afYiW&g@eE_+p~MS$lLKW!^*@61kqbI3_d}Jo1|n7?g$K4{dLLE%_-x z;eM51pv%TN2%NAcg^LBIH?G>Gxe3v%T}jF>vZXM(U1tq*?(vU1c8s&PUZklZP~1X6 zlS0AyLSaI|2ty%3K?6Ttk@}+Tqw4wn@3FroAc@1{K>x3ae+?pFL8*Mg6x@FW_aBS+ zLV;0={;c*Nqp!%JAl;;%6L0^P^nd+_iK`6zul#>U@x`IUgG6q#+5cN4DJUD^-$_va z$Y22j0t0@DnE$s(VRd1&eH6ruvn`R}BEROjm}0w=7FABe#V3;ka&0)esmchdhTHUP=Dhy{tn2?6H6UPK&z z=6@#ryUzcw=>Kg8|KC!y85Jn;#d|Cyv6LhSi}Q^!FA~`?5?viX3_e+EUlA5rx)Q}< z&3BZubwLl=@|_6vMl8l}O4pm8f7zrK^cw~GTLh*%)k2kz`a$(2OLD9RVrE3WzpZ(V zihi8QowM}L=xi82>){}f#rr|ua3U5Az8Z&u zPqTGbya9f-d9Y-rg0#Lk#U;v$c*>`9e58~D9)nZu_Xjix@+tYD=GcnN*;rSg2$p#U zL?{tLabK}5`woNmZjB<69}jKbfbihpCTX4*uUWTO1MV zQ-#cz)$d?-$rkT=@^0y@fGO5*G5%zOpeI zatJFBKNdx>FOY?zaG#EZSMy<+y-kj^b`u>^B~W2zwZ%J5p@(KzYc@Prbd1oSZ%XPd zWavxw*Rs;<(z5bMUF&fCIdf9L&mV_}JG>d!`2!z~+Z2pR_zjLluolpS_XQPUMsyo4 z8Aqx__r_2>vZ2$Ly+^uI1s-u~W1Yn4Hh2n-NSQRlVNYbkz>3q4EL44-QrSA&!`QK% z5UkW99cByLX1HGw8K~4k_Cs6jZYo$ApARY1&rOD?dhBeHC8_w{D7uB~RrXyp@Uz|_ zDNt~4NkC;PghELcIrRI}MJ21sd%Yb#58Mvm5Y_iOfVD}(f+mm!DA_tpfCR|gZi#d6QTcv{{~*o+huTbaTp435x)!Qa{?x}Z@qoiF{}CP71K;D5E< zw`K32Y08Huf55H8lthy*C`Ylh1a|>N_BH@2BAyRVv3VZ9BH|}IFB#8UG86k(>l@RT zNYP#rd~f968oS3lF_UBB7Niq_%jsblfmKqb3?_Vw_L)=W?9%bc79*c2L9gS+yQn{$ zSmhejbxSupdUw9YEyNOac_MFQ8PG=tCgZA{p+T?>3m~qtPbKi+Fz*CAd>eBhwqz6E za{}?`iTCNr>lY~qzX%Ew_myxR12!p$fj*0cfCz{Z6VPus>iL1m49tZrta4S3_=FV6u$ zsH6?^R)7+h=v4IaA>jw3Ab_CEK={5ETGYboA2kF&aqwb7spP;iSXj9M0qvu{;wN!! zY+!^Flw52G^}&Y~8UpDwA?QP9$NhYdtqY$4ypgZ_em^joCED}P9EfQOkQiv)1y1e@ z18Y0^!YeRF0fL8z>B6P0ft}Pz!n5PP%06TUL|!Jz|9JnY0LBco0rE{j`Kko33s3ZC zEoCJ6QS}KcPP_7o4IQ5M#qbR-RtTa;lYw;|!AdGPHI5hR*Y%a&W+dW4=*XIN^$t6u z5xRWL2Jn4eHx$qZ2h0tVs5UO4e3Z)~4XH1lp zKdl|J-rdZl%6dDy1S|XsELM~2>PHIK^>;g%v1gQ#4xBXf$!!U z(Q7d;k(W*&W6BW|$)kGSh`B#fe34i`QK)rs(m0s-P*?yM*IQgxN5vh1$+zN0ttra?GJl4fgd5V9u6)ZFU+T!uJ))OF&{3<+v1JK>fxKY zGM1O$^U};RP03GC~iL#Lr#XrWkWY zr*ac~{K>uOX-!yC3Z)GihSPMhzxa9HbeWg5#&~+1yYWcZ|A<OK<0-;Xl2rpThaqE5A;{@0NG`e!F}BrC^X*Y-4G9n8C&fcdRy)Dg|+-rt4!IcYvI|t_$(!@h4}3k!B_+pRk*l zsJXe9P$Z2P;(4Wgl}pnSSVc`!bLNE|9u%EZREOSO|lCY-d?G-wRNMJg;B{o zRDVUtTJfoGnehCI7|JPdM@fFhR}dn)Hq|rA>o$ zH-*l96Cbq=KYS+Z9pq#Y*YM_>_1?xFrpKMqP}H2SW16S9)2D6vyd*O>^ZkN^r()6L z7nlo;Imy>h>%%pX&NX)5(MH}v#b9i!^{|(N6VRc zGh6ZM+@xt!G4&+o%DS7A{S${m?&h#LQ3>UNiztoxPPS$3;b4vMC?}@FOL*`m{T>lc z4VPU{fa6gKRiiD4-F`71=0sp6;j0PE3jCRW0@CYYEM9UL*7<^bG#muC-y!9J#009rbo4$9&oC^%dIL&GV(hqcu#5?fbx$I&xUI+ia+*FYfLh*?ayUy`nycc}!BQ_Gp+2|PXtGh}pxk-((aSnf0;~Gd z-YH$>V8Viu?v;lAKpr9iwz!hZ0=ZJez%;p=HR@S)rOS%TIchAn&JsARXI4p~UOf@D z{P_5TRsQSJ?GxQ|dutjz31iC`w7Z*4qRv7rEZD5Sf;2Q%zUqcSW|mO=3|+CkmRf)> z2hE>rIU?|D_ZwE;Glx&wuWowyPwd3SFFVa{Vr?Pe7MYjlone3zk^Hy{d}w6ypb6e^~o=e31$*zl`=U zPjmjJXY0_osLsbEJYtf9-}!eH?;oF+Fv-J-?>?rlTH_uq0#SZ^W2F5#;51|Aa{9da z2jbd`@aR+NI%qDuf$}Q0JtDU@Y=u<+@tWRXu=+{gF%Vr*c1nYNtMG)=(4kX?6y)9pH9!n8&}6_jIywYm^m38)Ma{8U$3s?G z?94FwA`OOH^x3oTGWgn z)yUqYM3U+|G3rs9s*6h%OckS}T{@rJb%VXvDqXcT5aQ<>?!}q{_qC4tVZ|7x+4?mavJq&T};9OzpZ;sy)YUA@bwdD#>H>HWzIg zXX5i4j(DN{*cH%|@NVL#2Ahyp{A%*KxS%*;JK0&H6&QktLVNXd0q~@@V@$Id6i}5GoMs`wBrEhXM>TW zyBswVtM@>PM(SWYy52^U!Jj~dfv)Q>x=j3aZ`#wg5<2cd0Y+tV3qIOoH+gz-ln_A? zr#(jK*Yn#5Anm$xK}JsqUU?BV-rG^y&JMp^_i?#-MY6QZ?xcRS*rfC{X#ay8zatvU%EoSAbsCAz$5LtcLx?<9 z`JzYnvnxrXcQ&o!ba7ucjo+XlXWT1~R`oyMt;$>J85))$WJpP%QRs@*KiIR;cpUu4vVa=0Nr1dALl>9U(l}WMSL1-9P^qvR)ryn_lCI{ks zoI6r4PqIkOcizXPdMQ0U5x07o+}O|K_Rj^Y2OoIea&7m6`3EVvpGCH4=0T=xOqPW< z_Inm^F0S*UN)S=U_o92&ih%!~=1(|GmRZb9cDa#MAHAA$LkIwe4TW=rcw}nb&8z92 zkx^({JFwY;+qFpS#%36lj!#pmh1iyKqqw(R@1kj3wk`2PV@95%7so^9d@>Zodk1JB za>1hp+T}7K!B^}akp&KL?O7K2<3T78h`AMz7)0btXgtg@5x(Q}_;k0B&q~zEnjs{S zH1o|KrcmqN>D z@1Abx0|rJPl=n6B2q%`wwNmO+sNb9QTl{M8YS-mBb6q- z_){x>zpT7puj5-?TUMIXQcu4>HV{!T?d3{+LfUKeK27pEkEX#QwF*kVxNy7(j(H1p z)njEn7_t__Q@d(hNjyHda0b zzFkWcvJ{taTjFdzt+2GUFPge}+WtT#<4Q`1!C9CRokBpf{ylO>$@LpbckTZ9+xgZT z4;HsSb$&|0;=GVT?y4Ly@#!%M?d(cZ45HD4frlX5W><5<_8?pF(Uop)6o-2nP zx5_=A2VkB<1rIku2E1_Yh;PE)t?@raM4^C@T+q;MiKe9{>cn_Yd z8U-BRCEpL-iyDcs6S8iNM!329aC0Z%>cmj#i1$PzikZx1&>Xw}a9cN<{(J<$x848vJTt2{y?d@of9~XR9Ggt;*B)@MdtBJH z?N3@rdATazJ8epVC!hnM3cPs8;4tFo7zKA^2u(<=!k6dVGuyVeox@4TrKH1I4vNGM z&CeG%&)amgi+G=H$6b67NqkbwFno98Ba!L#>F~e4T=tP<-aEd<(PBS(^P1@hRYfE+ zzI<@3ib|^QwF(KRN7s5}&aAUikfeGv?3g4Q>J#MkvcM>~w zfUWKPQk}*juV!LQgos(2Be2Yzq8B zfq5V}Nq9Hr4ZDQlQ)Q?8%WK*ywCMd+@BQ~0!laCX_UBI(5#LH<8Fq-@f00y}@KPgW zI$L=se7(Vcx4Kq$ohZq4N0@?)&$c&scpMj^%Q>7iG*z*b@qD;WW)kHO)J^Flc2fM8 zA58~(-VzOGfs2r`cnUKaJjl6!-H2B*Q4VKwK>Qi_$T4h(rz&`2sJ!2G_zv;6%{#8t zGUE;t9NsN~QO=)aZPaD#mZQAgC1gC*1kTJh?SveVlxE7{IrY4_67iT$+nPsP^ zsd0_<4uk4W{T?6$w3z4L&r8uIBOLwx9ZSy3gZ9GxWJueNZhLRCHcR(1@W4JTVq6i| zylTHE6Xl~sR8(u6N?NT`%V1A!@35PRy+R@^+kc&Cc9?L5^oVkGDtaHRdg^d1QQiF{ zsNY|F%@!c`ESZ=SO)@0{;5D3wgL@m7G{GG~iATRBZGl`zY8~n>-@fylzUk{y!b);X zJ0IYoE2xe(ku_@Ue~lzYh-_~_onJZ+tn}`P?J|^1+UQe-;6z&s|H!#GrwM0OFcTiR z=0+Bmh|)}yrQXT2S;SZN+$p2CTyR^*<00TOo$l{4spTq0K3|pPvXA@0@XiZyV1SL* z0W-*Tri#m9AMWnu#~w3dz9ovaID8aywxa#BiST58Jo-b&4@quC?TgCp#4t8L;BMu1 zhMt5A#kO%0LioO+)G*VUUeLgD3|F*~hj7Q3s_ZmYEIWfy7!Q;9`K9l6bH5*!@u5?q zk9M?Q?^2%vA!YmQpz~$Z`=s9%+T={-y8!kJ?`dLACEeVJZ;>HXJ%E~AP$)&l&+MSJ zZToLKUpU|)1jA4#lL5#lYNQDTaT0TOtNSES*L{*L{=TbxG!}f|S&|ho_jJuGCxQ`3zkl=1-{GHE-0Q78=Np`+Y}qND@J7$+=-56Il%fHU?7$H{ z2>&x0wR{`^n@*3&Wl1DFFDspLW4k^GUSC!4x!7eA)q)Bx$@WU)c3^%<+V0juDvJyS zUsqYY2C&m)ae@&#u$Og`M05g8>Icv+&ckZ8e~}@n2M|jC2kEURh}d56#&ZbnWMYrf zeruME<(6ZppcsrsNE7xw69wTl0`*7|Apc@CBZj>5dCP@)54!6_WUG+FnbXleuj7obP{NNu2VQj_3N=-m82CRiNew?{4j8eBKmqcFqWf>av?r=*mN6dykA{|*to##U z=MT=#0uTY`0{>ke9u|{v7!H7yhiJkj5dm2F{}s?I8g-*Cy!ep?5cwuu7hl^R5P2yn z{jKwde9)WddrfRWD*Zakk|La80nAX20RVkZR!*<4BVqv9B?^>E7nJxg8#JW5<{UY9 z(hpD%k)ep%Fn|nqpF5yXOr-)NsT|}$7vVG%Vt88 zO(W%K2Tl-$Pkbr+-db~QPsjZ|Q>9fB$ofQ)-gf^e`WC};ik$;gZk zQ8#Ts!GuiMkJW^%s^a9quV~fIisZjl)MyEeIWi<^QOLG~F}v@V)K%+BBr0MxhvP>V zucq$rT})d$8nUwvfcLPAJHtj*CX7ZIBY7%or0m8aOkv(QkIE*Py}p+iTMW4u#5Lg|Md* zW-kk4J}L@ps_x5que<1dMLnIn*|1#{+f6^NUBG_eVR?X10ws>k8RJ7STFB4WpO)~; z0z^$iXGc%pf$szZ@fS&^HVcCn`8^M2Rj3?O3|loaLUKn#6ql$3k2F9N`isJbNLtw1 zL6TP{2zMMM$=zZKRNfJev0E*JD%82sPLBBr!$)Qj0n=nd{A0+}7LfdkF5Z)#LFoq3 zT&!5_Pkt{Mft81g=YxSHn7H!F90G*pXlUJO{feB0*Z%FR0-p;Bvhco(Ygb)F? zi@)*eZ{g&7L!2)q{-PLMV(iz`Ag?|Yh$x9w!8*;Ec8P(6eg{oyjM1gLqW>+sh8My9 zEAb#dD1|zY=PSYv0F=_V2@b(>r{Pn1L{1Y7tz_5IvbGF+j#cPfM4LK9HB}HF_}=di zFhqu=DSvqaf9eVn-q&>2wx%b8qdr*gMr3ftxkTQr2E#$R(`)j*%8EmxB&5^QZ0pXt zgyjf`MrB?L4fs;c0eq4n8fR&w-8&xQwYeFS;S#k##a+sD|s{N;6g z?YX&zRhPPXS)JCI(vO5|N)raVcxhS0jENiknq%}CFZLR(P~D2Db#fAyC$!qjjaD@2 zhsua$TYTMZr8}L0s`8f5m}w_`i(8 ztQ%A1Q|}geeyS*r!rGU@3q9+9%&4 zWm+6*Qq294WG8@f!sCiN1-!K1rEk$KwvqESkw;zu@AGJ5g9;x8QX+Y{im_HseMDR< zkS{Hta1=tyBXknJOivDVsT>gS7ex&3y;w?*D_J||_82p1Q8 z5&M#fW?+%qaPccK?qzQ6Nn!Aj*pse6$sNZm&b?+tfq5xl~} zjY3Bgp7Uh7zjB9u{h3GF$p>!9nGTV2$Z3j`6m+TJUg%vY=;c~8x}qXYzwW6+rT(1izXF=0^D(dC{+rkiV4Q4rwI?$BHgT4`OKOtu^yF z9hSayOqc%DC&)Wn-rD0nTyx*^-RSHI&*9?RoHtg27rO!?RVdtbHJVq4!2{%(?eRjd%DffFUF}nzP<{x zA^7?N%b91O;1W!vM4LAdp(=6jECs;K-T*lg9m)=ZIZgTKvnSlfeD^Y&axj+MpD)D_ zHs*Sc79T@1-FWjt;LDoyW?`vlMJzXU0SC8~Mk4!&%6Y%r$DAfJ3p2O^Z$4)xmRGL? z@PSNqEf#5CXa@^7y6NoAU$PUkk=05{YT4fb#H39(NxIIQsundvn^PaQ<9nx#CYcX@ zH;NVXt!}-=yzHyh5Re(9``f(II z=2a5^>R`^^;}K-H?&N$)G{NgM26;`W=?Z^m&#C2_9vC?m1`Z*nPnerUu{&ADwlOuY zZ1TC{OF^-u=VmBj#O)_TEtmOO(WT(N00PpR0wXV6^`rw`L?qRj` z@?OG~-UD%GLn@2b1s$KZd~~!f?%nd)^4bjPuU8~fEZfzEvMCil^g151LH3;}^N*1W zE$#y;B|d-K28T+HMsZbpDg8M*Vc@N3j)tid2OaY4hY$Wm6JZ)J7JvK)e?ZY~RuMS0 zK6_$lO@CHfk8VWpDr7w`X}z71=ejlO>{s>Gow<^G3mm!)au!dcs>3BWvuysRxZvYg zH|IIq2WyXp5Zn3IJ0s)`!_nh?HX^jLg-tB-qFqAw3}UlG@^bVb2jM{Bri$YvdMk+{IM)X z)A@KxR71)9bYtKTF=J-9d_}U7em>f-vZdKZ{`2$u%jTwWasU(-vh39yZ(iX^#(aO; z%o#gHn4~LPX>d;ZQZdxDLu+rliIMdp|3%aJO{Th*7X#LBUwM?MGVn>o^gLjw|(Pts40JoxP#JgPMedc#MM`1 zm$30UzF76YPTZu&TL~D9+e?3i7&S3q_QHyN2#}yov>gs}Ui-#MxLMD;xkZTU51Z7B z{a@IK(u zrz?0r$W3MRNmh>0w|-eHzP+bv^vLqyX#}ya3cjq!j8D+9)3=uVNRQ85qsa2)S|4=v zE!#eHOFCbk&j>BDC@p=HzFNcTu+UbBk_wV7AGX(Zrf~LYENVLIov%^!x%h;G#YNfR zk6O3_#_xZ}WP7yBgh3!wuTdWD2o~_bAaV2hlBr-UlcV4zQqf+Qvt~7w>dMaSeWM_~ z|HKZ;2tbgHDl_0Ff9z`ReaDnkF+AR|ha7nL6E*3o!lJc^hW%;)Gtfyx-KfrO6mKPZ2*( z3VIHdzE*eAf6fz;6Nm49*V0_Kz+}@$Vd_oM&uJmvn~k`uzP8lZZ@<4nBgdLFU#%|Y zV3O5XmZQJ%hF~(?@g5xY0{*f+T)(wN{AMxT^}4C>COQU9P)w5ZgJ}T|j=t;{5{{?I z^BDtIIP1CM^|hDM%84$S!GfZ%cAog4LrQX^Q;f5ZC(&XYR3Jf7B)3Tpg|#@W zK-M*p=}XBN>6wXAG71hBXBCmmNOTWRnNUc6imT_A&JTnYN1yySdtVOQv#2ftppojs zCxNf0arq{6>ZX#Z(?z}Gcvj*;>)>kVm!cmN;9WUBZj98nT?1DjP|DWum)tJ7ag&1v z9HL9Yoy>K(8(m`2$%~{Iy_p)z3l8m-tU^hfe-B4)&{cX)R5wC49%UL64`r?09I@A} ze}NHzCJQdiPpj1jZ7luQ*Utv9eAf(G$g}y}6)nzha2tp-&(*TpxjAeO%OZEwwvG1= zW={pa=IIm80vTTLjE}iW*VYEcDU&fd$Rd@RTW84=fjp4+y5aJg4B}s4*?z4TV~sO5F5E{h`+LBc?sXxsK&( zan7fx_2Y7)jG58dgvaYSv&dy%KNNIH4V;K=zubPg@sovPtF7ab>sQ|_m^<8N%>Wcw z2bYbmup$p!iG^#7C&8`zz+L5G{Wcaf3s$CG4usi~TJII4q`%G%ie1L`6e9Ef{^ zCc2(EF3Dzk_AuJ2^IYeAG^bpz-Hu}1hGhI`BriWAh#;G&g1rk^TDW*u&@?f&k^V6C zO9xh`^+tH(i(~EM+=s$U@!leuEXLy!^oy~qUruN!wq)!m07c2{%aB0s{Pj@ig@E7T zx1*clvmYBw>hW*op?uvMj;+%jl72yNF97_Wmo3X!jo0)6qoU*Uy2XQ{cJ1H~?Lb{{xLw1x}%)mR>91$(|-t}Lcs)0l!eT3DF+W4LhUo(gusddxCg;#29nQ#dj}~!o--S>5$M{KCKn75txmwfp?RD6Msf}FaE#KC(SBb^IANMfVozm>xJk>p8JQxg`BgqLWd*x=4NmGykZ z$(PV1t`8Gh>I=Ml6yttm14|uyc*}colosnRC!*)qE*#9f1VI=?1rep4^?uV?PLgKl zL;xfd4RlxEi>TA@yhBe?0{9#-yq2**7I5RouFq^#7MXTRmX>+u6q(wY@JMYfIV0TN zX@a>X4;}N$`j}Fjqf6a&cURPqRx_U|-+b#g3|C|6!|3nnacb_+O{->I?Zc6fXf)2V zq_no$h|?yQ`!*v>Ma@}=7FTf?ytHrPNu}U)sY^B1oz~wn39|4EFVz zSvfg5^{dKx2>}`M^eH&`^VQA#eE8TC0FH-`Z1ep=>m>d{>x`)Xz&+^s{S>Cg#>RNY z;RaEmp=1w?@|(sQkZwwFiZ^C37zI`e5z;N}JF)s1=FhKoYeoZ^Om^NIpdpr>E$$2osPAxqW+x~}XbQ^*6%m%+zP{5gd^sZ{BS8*$ z8&Z%w8R|$MK&^OWKJ7?rorEU)$T?!+zB~yGWLvtA4kge>9mok%sfi{k^BgW4ta}5f z2bFmXunm@I!hc|~0tV2)u5B2^?o&8oPfyRjhXa~%4-gQ7r%Yb?6-@}@0=?nprc8{Z zGV0*o%{`uXV`8kVtQVI%0MlULFmY!02hb}5h=IRAHY)&R`?BtRorM2sCOVFkx*zfS zHuT#!Y&Dz@jSf3QH}2NU^FD|wlkguSp;+vM}I{Wwes*Z~haTNnH;j?#q0!&OyBIO!q2K836c3ztbgYnTf zEpSKE^S*+Y70bBA2$vxh)Y5;zaTx$^2EcKSFHaLO(puKm{ncOwZ*%~NHMibUVt7Nc z_4)mJFQ91a>5j@JfIgwG>8nq3zx^0k*PODNk;cKB`sdYur;P&nqq`r>{5!2Wt(eSLk3 zQbB=%oWm)4(eoeD(R>wqt-Cu_(^w(i_Q-5r#R-NR~j!UC_a}*}R@TRgKA61-u za=GQ&v_t?vprum_GXCX%P*71OEo>EIzs6a<-sb@U(04NDiLsg3#|e&hCT_ZG`jgyy zk70#0F0J2R+stC5P4X+zrkMZYfjG3hhuM1+mAuYo>JtpgEh_fu9}MT4{-O^^{wCGn zQcx;KhFxt-%IlLFWy;lM^T`ZaI7ExykU1evULvDs)v_NYF}e%X-<{QQYsvBTenk3n zM*JS$e21Oc-}8$L#`M>gKqdvxUl2qukyAI1hgMsgQ|p?0!#rQO z=Vz80+0|a0k#b+9iqg=byJ~uO7Z{246A=>9Tie^aYBkzrh{%PF$xsSf1wvRO3Z{`_ zb`0#0$jaym@Q`-Tt< zBtwFPpBb$n@N#jvP>6zUrl#*a9jQM9+VO|% zEC3%I@iYgW{R$bQmWHbk?L zc&NV1V4{n{8eU^zeSfLxOE2;mi)Pj;z~dk|PhTNJx}6+hW2%LLCH=!fLw_2D4~meM zc?qjm1urqY141Q>0x1K2pru&>3uG4mi{OiQ*EU>(SX4wrMj+17v29Dcb+VVMNLbuXr?ab)wo;ihLk zrWOQjsM7{Rr-6AKeoo+Xk_TQ`1~MC$oO~Y(!kEXWXk*lAc(w8QJso)r?F9ZaU=#nT zUpN5mU*_u2F1G{xw&)v4;OiUP0kdrk@u0UJ^zKmcnAB?(0OMco zS-hdKwW=u@VSYU0d9oEvQ2q4XL)(IYOdjqlLia74WQpD)vd-`V$%lF3xM_#S_nud5 z;gcNHV+Wc=bRWK{uIjHASPa@l&vMq$?-a0UfO9dB@I}<4ReJjRRA*;r+kmaB1&1Fd zi*Hh7ADANLyv6@19T?pza#pN7O>|{2E4ijdRvvPrjvq@jeTE9@zI24cg7MQw2A)rJ zXkPhEuTjQwOC{UR+gb_@M$rpR(e%(*D~kA)n%={h7NM|PCw~4K@n@w)>h9$ShDPh< zp^6V&n%4kJ`;Sh`7Rca*}h(EOW&!DY(F!{ zEmg1vD5=;SX%iMk8xtH6(JrbobNHcDLvIekldAx@=&j{V<${EXES6x8X!*qvP~PN38BDumK8KAQIq zrvag`^i>{SbU?6EQYv5qzgY&_EDWvw9g28L``2qY8=j8={@iCwFnrYr2}s1wSo`oK z$R}NGFo4z!z(js0xiZdHk~6Qz5!t_7`A;74Aa9O;yb8tS%^-6lGQOls^R6Y#O8{c8 zycsicnsK9rf#hpkqv~7CkRPGnLPL3q=-2<@rd8*?gX_laqBRU?twF3k2$!4!fWMMw zroqI*oJjHg$ncC~tjqj5^kX|KxgU@*@#vXNl3o3(MzVBdw^m}}%bwV`P>j75X@Jg% zk&c|;NF6L#?{mq&Y+PBA=koGreuIQBqYl{4YgR>XSgw8Eq4@BT0HiIgmTUGruYU;Y zPhhltYj+^RBE@>Hymla2wJPQHD3;{rJq-q2f`0M9a$% zi_(6a_eN+a{KHXmP9QjOv;NsG0~sbd=0u3Fjmw(IVJB_qb8u zVEWCoyc#5u`17S}2rw1+4yHmv8~!1!=b}W+$z7@@|Mcc4zZL!tg9P|%Mu??5kV?77 zp8N#-aN5`P2ljvH>Z>QDms2t-wW;8bD|scq(INgP^0gb|(h&b}1}3Ic8UWB-?GhV+$g!>Mj4C@`SBo3}lgH1Duaa(CY0kwEi z(gyGx4hsBhBslkc`2XQ8;}kLA5aH@5s@yJi2X&cl1Y)E)KC}{#)E{C%AUQ1a!S=?b z0Pk$JV>G~qxw*>Ah6yO}_dHDKcL)fOl5;j3e%f~t zX(bQ&=CTl@rovonk+{0%V!g$}`g}&?T3d5*6_MoL-dV6^{O!%Xp2fCyRZaeiKhd642+*0GH_ZE`Ihc+(v$@KT-0)S zxK#5@@A35IuitU`Smp#Y3elh8Hr<}gll^2TVQj2%RMuOsWlXj=u5`G@umQNnkDNGo z3nAm_YKQEe@{RUm0yJyyEks9-7L$KWTDJ(3sQliafHE1~gBVoekwPa0h~G$M>m@lT z=gQ~E$q-1W_t>t=dceVxHTptp_qzYu%Tm^nLv`N_!UgjeuQu5+y5IeXiq5UA)p+8J zke5*}Bf#cAmj7b=yS!urnkkYJuej`@$6%1j9z? zrCFisV%6e_-|ZeMVzy}74BEvJX+Cw(|28vp=S{+O|g}N%e)vC&Y=mAM!^8@flI%fzoO%Db32c_{hs#@-QumF zk0t9t5&)iiOa|d7S>rWcU+*H6{zT2B8xV3G60K zoQwA|-lrP|9pKARm72(t8;4)l3A4MVi+BbCX9sWCihgJACk+%c@%jMm5C2b;_amW# z`UFnU@#;#ns|Efhsz+ws?YMO%M5dNl$8I{{?05y*gp9}p0=whsr1Zj3(53ZBo~aki^4vx?sR^xyhUJdh!Rf%;y(#d5wDh(bCb$A<^76-)FfE2)aH2 z+eS&axmfY8D*D}zP!83svH9jfGzwwC@eL8>7PSbUHgSEmrHf$3RBaCWEMu15p(2g7 z<%JKAuJ2Wa#o%x4ZXeK$)^_I~J)fUiEZ%us?!EI3`EerjjNH2*?M=l!IeH3Mu*bB zM5pe%3XZcBHC9lCfS~MK+`xBOmw?mwI;a-%P8t(^lwp|Hr@e1^ zN#`pd&@3-c^_SJh?GtitKq^Bo)ppoMf1HPms;0N{xpl`3UD!S}Q*p1a^~nGen-&wB z>f;NYe64H4Mydw)Hzl#Qf)R~6YH)u(R6LFGF-QtLoXA6e4VhTqPRhnmjZbH3J5{WX zdgF{npdZX>*z2k+TS~jU#f2qx_0}K(bWa(pQw$Ls{0+{qGu^;3LEtgCaOx3epKwsx zSlPAaurm7tDcly%KxmU>=4$J5V1dJIA*I20Sj}ps9tJfmOl*=gb@D)ykBe1IO%BQK zituRTP-lK(Ir`I*nqyO5?%Dudn-V3vjCKym71s9W9l~^F8ZC@9Y|?bCG_4877-o`n zJZANYP?`o2%>B;?#GWmzsnvR}iv9iALDQ_NnX0dw%&bI!JG9PmMXd(zzK5|4|qOgv7Pd4O9|DS}K3Pa$T20y``%7_*6Z7w3SEhO|_%vP#jVsG)@ z_sp7ZunHIuZ!E2;mFeHoQ6^Mob05C18#oj`$2*Y>*E;{qJil6kiEDl)1P53|*pWz{ z{#XrTp3;jc|CqzS{yTwnzM|6lME7~Oxko(O_>I@0?$Saq|Fs&FrVMv)mPFNe9`pP( zI9WB)=kGpictL%wsZNxn)R&kFu^z{bE+u7JOiV{#w?37E>WMpj*=TcRe>R%QcX~G5 zGoRF=GD=8@mD-~+f4I)>aq0-&;s>FTJ|z73yT9Z*cG=)K9yM<4LBgP#^=&S3^<J7QHBLQ22|&}D3~%R1#NY#@z5h+%`8r1Z>peCsJ{7L`28#>R zuN1?usEze?FY}~UU^^b>u2&4i;S+=KA9k^OjwvupOgX)=jtPk;`2UWJlYGDx2nh|X zJ{S=J=A-*J6Q{S#HBw&!8jzAXi_RA!7hk3yDJVRdquVrv0vUayXJ(O(iDigckLMGr zh?~6@r$b#va!bozZMu z+m>(~2cEl!VXm=-NFm`FPEKAupYOlbFzl6Pz_vW9B;X_Jb<}b+IA%wXt`O!SpS%`@+c#LkE>Qu+j5oLJpqGXb z+(@JcjCCe)9{UUbAl4t7+_4kkwB+|V&-I#;l;7RkcYt4pfqc2;e94HbHj@ZAb79W`NVBYk6?i-`^&h=^ch zUkAbtS1re3oZ4oa!)Uv*Z%8P`lhONkxiYb_TS8o3A7itlSj5=F%>s9^%awI@h@Y|p z5`Q8AjqfH8YmRYzR=#4Z*thG)6=t#J>G%JtMj!aNAEiyd(5%1!6d?V+=6R0NvFS^U zlOrs?QR1IZ+?JzV8%guTGFDcMJVWmlsj(W$_Y(eAIw_B1D^|Ao|7pfH%8aeGAE1|8 zIJX7dGYBLp>ZzvK3&}+8UY0uh#{{p>OG9TCzzjNgT<~Yp^TFB_J9hQ_jTcXd+9kcQ z+Ce8aMb=h;@h%)NjZtWrhp!z+h0%be$TzpYMrN9780Qa8B-R2 zl%JoTigN)b#5A4b)%6AQucp=aba#`miu-RFuqG-F*r((&+V zo_ZsEWvV>>hFiWfha#)99R^=q?crBc#yK&5C$6Rr5q_)95-KikqkF(iF$Sxsas{8D z{u(aUplK7p8kMU+ig{mzgkzJlffb`LO%YMkZSGqBVaY6fMe|)=G#_G8@#srY;3G< zV`K9PV6?tCTeJT_s{OEZ^Atu0)^^0|DP~y%@M(246Oy;$^~uZU%BR5lZqtFOwNQWL zrE30Pp!Hw3I@6HY&mg&zGQQypiFeERB7cvxU@@86?ShM87;++o2RcBrwk zRdDY6iMM9V^Fpad$-Zc5K;Tp_7H;{&K;?daLH0mX{JsVxVf5Hjk<~+hR``Kn@s$u0 zq&dR;e-Jx^bC-y%0EhcMYyDrz<%|D_0rP()mzV#&O9N(MUgHA5b4=@jq~szkLxM;d>QMt6M+}p#Uz1n zHh=ETT6V2aA~!!0FLc_41@i$1H{rtvy+uqKuD`{p&<9B$Z;2W;W@CDW)$i|K2yYPT zi_#Ns(y5vC?e1hxkv*9kIO)>KdImw}baKHHV-+ zzi@_S0B2afhU`@?*N!3%PvOKXiWR^XY7+2C!dj;%ZgAUy)5{;-v6=-V4lPETLc$$Z+IZD61T)Tc5|Lyw=k5Zc?!U8wYXU z`Td)dR)@}5_4zzSY&~0oj&Rb9H(Uuvq`&+w-%S0d?z^&RF#8p{?33m|jy=$K>;W-s zk!%sJN6pvs*i=Ve7msmXFM&p%Jm z;eRlIWiMQ6utPea{Y8MR2~0)XB2Wk!-@a+flkl@yXfWJoSN&P&$PX}QJbV~B8gQC; zxMyc)e-;+B8>Fb;Zz5Le&j%(VwUldF{P0J5l;!HZ~e}#Nwy& zCfaXoAr2UfBU~j1BYaH(e-g;@P1yTl;|^h~#83S27@&@U5hm~ly*<%ob$@+%RKM}-&(&jU#_t9K_4IOc#(rqQ9zp01&E*1RSy;4FkW=x(B zw)khL^t9nr_V>lEzqXd(?bYMA% z_LZKr%nhk38FFQ)sA2f~g=R^iw}^@i=H0X=e~GcGUAY~Bi^scdKeUN%O8#=plTtpP zcsu&AP1Dep`qhRsy7UIi&ujU&JbGl^L2AnnHBI;D$E)K|1of7b=Ut7Jx>W7kuE`tp zGcx{4`-P$tTpcayfv==6Gr6AuxgC}{p$PDlT^SsTfqysA-^moV(%{w`?40o5ar>=K zw@&osq`H!W*6@-|6_=N1|1wJPJmHJLFlEmQZ_-$n>N^2!Kp2C1pXo2$o} zk!erm-xzS%Oz;%>xMtOmbYZ`7;A*h^Xu0o$-i0TP#io0-Us(*^JbBcF@~y79#|3;9 z(7I7n8Q0YtU=eivBfgZedW%lDOw4U1SGCt$0LkTx1-wD)i@tuL>t{-;>J8*By;eLv zZKvH78t%$zbY6#365`5fQgkkCaFJ}XV4oz zuYEVw14lY5$5KPTUb{bn+}--Pc^f#Xww z&JSL}6mlIq&DRGX30X@BJo#LXBvZ7x+uFZ9iGHk56&o5g#CM?ps%@VrOk7hu;O@FM%W%y z9_INnog1_i9CL+Cyl$piy0Y>|i(3zJw{W@1ND&c9*=i}QI+w0o3vH)shDJ2O+b6sp z14+r5!J9^U;HUeQXI|jn%ozJoHzyS(t`)W^m%ah7afrrd)$OOg<=e||p2*et>&FSKBIz-jJgBn!Wpney0Q((>mBvEyV- zt;4bVMYc%5C(*~#->*dNX(N3EE8tju^!{vgow#`I04K81pRdnsOGl3rZ_u*J`*@^y ze&&?LC*1>Ki53BurZ}cvFWlcg1xQq{2K&sm`|QJfAZz2fnS4jCspGR3_IKhsT-Y9c zxWwrSeM0}wwR6;*kW_e3-sxZA*{K?`pgzG<&A5Q%rYDO*bQu23{vWxpLy~I)U1?qE zUeMyqYNbFE7)4(~ytc|ig{zik<0=+NXz4TNa=m?a)u*D840G*2SGm|w!(^yHx23rm zhQ5FucSK9$$5i1yMCOHib=yD9{sLjtSpV6|b`nJ3O0+Y@9X;(4=DazKsJx#17<&vx8kv(n5lZ&WX?%q9-Cv zuenQC~%gNPE^_~YeqE3$pYrG*1S^dz!tKrw0HdKg`|M_G?Dxe(3TI|JFa;{5tR!aIg zL&<|zDrOtJDWXwxMdA`Djl6X>TgUQq!UIA7>`=?8nDqp-B@J|-0*Q_7zPi5tG|4_} zoXngk;f4|SUoXH@H|N=LT-4Nx%(=^+(m#N%mU`>r zdGak)yHI$No|Z{VCl#743ywR^*Kzej5x3LZM%Fxya9%J z`hE=DOs6b1b2A#{Q3vEyK+Ew71`Lg1IUz_;wZe5fZhZia=-v6v zW6J8th~K4^Q1C+nGHZk>P)L0=tS`MI)l3eTFjq+gG6wj-r42NE^124PtGnxXISS9t zo(KlJhN}qTz3~e&!9WL5M47*25Yq|}*;#a>JscSZ7r>h1&r?%SOm2fN*~XSh2&$RPq++!d>$)4V4Lurf2$d1Ki%~%!(b>Q zcqfj>&28`WX5ZnxUJ$cQrpg@37}fYFf_rwZ=c!y_Xr`%-mO8yi}+;zJA= z)yvCZ21m5VYH8rU{c(G2b^0I z)%Es}Z~L5(_SpwENJgtVvX4B=Q8|*^{#2GUo3$ldJhT3no3;x+D-7xXbT1T!32=u` z=qU4#1I#BxI-dqVsVMiY*?nH$*x0h-T#i?P)ZPbUOtNSFTx>-<3n48i9#C*>Q3rn) zJQEoRI>|BW$flV>?EWm;%d!~IN81W>pTE%+{!LAe8x;>Sg?f^YgaWy~|B<<@-It1X{!LFTgbn z>e*5Fi{f($&8n?F$`cAV_-ipzQMMeJ{B&(<&TTusN0r7@Gc6)zAC;Y-!0B|T)}Wl9 zdzyr1YU^w5ZSF5>tW_Zj43RooinbU|RJvAy!EKF8&i)G+@(U?bms%*pC=(K~^M8AJ#tx;{6n^p-F57X* za(1KO@Hrg~1Q7@F*1t17X^cp3=0%{3lVJc{@27wN{w-9P8eT63j(SR)4=R4sX`HU^ z9s?ie)dfnVO(7(AB^K!+V_8#W(~TC&eZI%{syXX3VbJ;kav8l~Bx1UqB1wGc+2z6e zX7YO%75{u8RFBPp=<}hSKQ&A;X`Xi7!|*GQy>ij%w_lxOf$nOC0sKkJXDh|@Z(viA zZCt34VzZLlR=&KE>ZjJl+S;t$DWlQt1q(>6^uPrPYc+-0Up-Ve`-WEa9thqJ&sU(F zVevcYqAHTJ#~U=P&g+ATTfD0!pYBhDl~qmuq+|t&BPxzo){DY`fEw`AIQyeCUx?H% z{3T9Ya7lA(7x)h)?g1i4Y^@hHjJMU zNCYo1YUvrZimjHEfE0ENft*ncAypFLq1EI#cAs<}L&aPqBNDUx-k|?WPL}Hmq{n>E zXRA{8*~Tgt2Bw}}$RxG;16y=VjBK^`QJ~3Cyw=rTbxnmeJuY6WVnnxU8eM3B0stPq z9(Km@RKD_jBwpgLfw+zqbYx@ewzdP8yZ^6=XU5pH9v<86^1@&>a%miahOQ+4mBZp? z{-Sh{a#^ke`q2e+uz6q5d~b1{qY`B&bZCcPg1@S~phmcZugyenbNBY=d4vyy{j@bl zUBjvHEt=098K>lgqSz0%v*>QISzqo=oRsqXbCA9A-#Yz_5yG}#~!T~3Ljthno z_j*aFrO_owW8#6q@!~<#occ4?xeIMs9cR26c=!W8$_66{#+=du6cJ(;KNtIUgamyOw)WRUH^SvN< zx1w2{T*~J;0~i|4<4onjdV;E<9v>J&eu2I7>u?HSjuLG@@3rvdWn%7H%yCKA0g+m$ zHs;6%!1s(7P5*h}BnSt8l2Fk++TP@^S3yZ{C7&-%@xNm=)LQ^RT%0+3R@vOM_B8{8 zED1enI>8lCy7IIJnjR+e>>zXE3^+}DI6b%PKtvovF$=vNW0Tj6=lO)M$>4>FLM3q1 zcC%3=1oZZ_MF-%e>P+SX9T7amuMdoHW~e9`e6COv|Mb4 zkxRl$JoJeP15^Urk3RUPW}#5=bFRuB$9JP`Chh8iNu44v_Qyr-(5v zuL~FeIe$Un?O#JCa9sE{%Y@Kl^BOJE^wXWr&=eh!8&1OLDG5n<-py$P4s1mcj0#TY z&gW|1GH;(R>>q0?{dZQ6uj*Pf&UlEuf}i7p;d=`vl{IlrpU)N$``0L2^5VL%d8>PR zCUdn94*o`@32K8%o~O;j)qX7mO43(s#X2+bt%>2W z$`j4qE-b|xjy?yLwBFhOErh;Y=VSd>q*3iQ&5W_C1OQ1GXg^ z1PRrjFS%YRkiEa|E7Z|m$SW^*drV89bnj1cQ-NM01fI481_m0>Y}Rq2Ly#;7=4}N% z<3n?Ds7n(PG&lq82;?W-0^9RuFPb7s13+OF=I^BJngI5xzTA8y7On}30Yw1rqK9yx zD|Qf_3v3@qZ3>2|b+r-BAh)ff?o4_un>*2hkZFsBjqO`S(^lgSv`DfeJ{R*x+mmaGS|H3Js$Q7NUj103fNuAXgE#L7YLvcjg^Q zOus=h5@3Zxb#J0Rp6QO0$rbvDa6?N?ZS{YBz7kmbT!ngMI|?F`3rv3+(9qE2{fcRA znqZuBK7@n)afCU1Y=K5!R|SVLW}C*>vt7A3|266%@T2X^Nv*psCaIGxo3tO97XgFJ ze#=7YwE`r-aiyXN1He*dwPIEl_{G4*?@U*26><*=Lc>sczA{mO-ZjuiV>kl4sM0)r zSj8^Cc&WMuPcNxR2^Y9Mm6)^l3XUB3Hu;<^^h^c7o)ygXX*Yw;K8iBJ8}fy9N);pIeHY>wsUQ+pG$CMpvka2 zQ(2Lvxw*QZ+cX)U#4WJwP(^c4`19jo)(yfzS*44m;v~A9taS~@fo^km?Xk|9clgo2 zQUZJmqkr)|_*>Ffj#E3FZxeTK?Fz@%Q{nljaAg4#h^&;9riBe(6D0}2YGj!Cn&A8g z*6(&%43oPt*(PkZZTH5?Kfb|d0&=Kv(Pm}r83^d7p2x#hfS_B zF6x0V+p~!)JxeT5O1AF2oy34O6Y8$Nfp$<0or^WOvuQ+bz41 z)t;*YU$2{2p7W+8K6G<)6N-@OJI*f96YZBOFPoE91$V^dYp>mC(7-sG9!@CoE zefZNWNp|3G_PRTfE-TUA4ewdQ^-GDP?rB2JKXj{%Y38!lVe=X(j&(+va?P+bCB9>pe0yS zU-EwfA>g`1GDtnf`nupQ6-cY6j?``-kOwBecRQ&M$PQCe+a@6`RL05QBqEB+Mw-FQ z0=}J=V^oT9r1$#)_4iMYJ?hO78~Y~ zb^W|VI}Q*J{qwP*Y?=DxBcrHR{He(0)ZLLM=&d|)$WtEtyQiZG4U_4dHh*@DXAfwJ z!h5waI&VRKEM`eQsGu>LFF;$7HEyO`?{>ESlceXc@Fqmf33p&w8EsLe!e*(li7r%I ze)1Au2ZQ>5mk9uW{&{u3qQ~|HU}>x5kZa^|`>1dMwBFy6y`H4#`zW5Hqh$8eQ>uP{ zaO9-(`$(!m`xf%AVjW}$BY-!&8*$#PqjZEi-aV?YO0AaMu`7W z7<6ut++H*ITK0bQFld1*kFUfZqmi1L`gbD*E+3{y6E-%st0v*x!sSahFw1vQ!GxR4 zW$U6|G~L54-vk8U)chm!hDLj3ws*_}A#GVblbi&pXoWa6{E*~)7~4-qKd&ED<*a3~ zC1?M1+h3!Ot=%O#)=a5i(4nCNB#zU=UMLUzf+rz>QQG)NvN^DKstOHD&#Bd4J7gh7#$XMXoe_L~b06HvLv4!qsx z<3oww>lIB~ykRkDZMF`7o1DO*qU^Q(YiL~kMB>*z&qD~_;A??9Cu{XylfK83(y+A3 zb)j1dSNTuNP!elHgMuXy;^~?!N3f34d3%Iwtms zd3QFZCV2n6G9~>_Ggmm+F>tv5S^TyT(^N%3u9a;Rr)h+&gLI`bU>76wwv3PSozh#M4OZT zUEmVJE?cIqN&`h8<*D8K|MLro?g$!8>Vxf!&l-dDF0lhB^Op_y1lMXRKdcm^MUl)M z9BghCnL~@-^18X1@5t1eZWAx>xB!}FX4R}sOP;mO`or~G5=+9hzZ)w*Poii?oAZu1crGd*|!4@4h3iu^sxd2Qj|TI6l_`U$4|PHkeB~i%2TFX zVm7v0lS&`CSz`-Z8x;z~2epVR$70J*+E&Q-sX*JW7WqvF?P5TiWJ@P5e9(_5uOhr} zeY!Wdo=4D0_{0LD z;Sw8V?D97WGP#x*BDny}PESr=i9L4vG~xg^4wk*pihfGcRkw#WLXSR*I$R09Tr46} z^)R3uzN-y!Nl*iND!x^Ed05(=TD_Ps4*_<-E#kg%EX_xM%Ra~ch}agKFa3CW7?uer zanq7=DW%-!J-(FkKU>ZyvNZ8Kd*$O4wXe&fV|x^PZo5&eRB$$VJpv`5FLsm{iC^3e zZlm?NIJ#zP`m{oA6@oq5kAL-F3(M%U)9!hko{pDXHuk^Qrsn~lfAHG@f%nPp{U&`~ z{SFth3c^S!_@a7gR*`lU*h9f7Ep0v!2;j<*%mm1Xa=q`3rH0as@P#>6T`vQP|82L$bO_dS*L@NRj!7#E|?2U7d>67xv zjFXjIrNzDN{pqYnXZ(~$C*FO2Zconke0mjJ7~z$M13Y9y6-ewmvI(iud>W>xs8t?k z-;`aG0b29=uluj`Q>aMCiY%j~#DLl|U9f}Aa5h!&F!f4bQ|YVEo%1&0Kp#cPl>v?uA~DK;08GSB zJ4m;lIQhv#PexMK=aW+KXo>>{Xy`(f+8`;W);lR%GSZ={s!GQ^X?ta^&Olj5hd~BV z@Df#L#+#cz4jM9A-^cV%)NmQ3DJ$lQREQ61r&k&>aeh|j=z@W&QduisBr@l z_)SX{T`!l*kN5xEg3uX2)<*CtHI9Z9(E95i26^l|LPYi5mU_a_XSM;ac6Ce|SJcU- z6+Y)l(E0iYsEr$H-({W9Fz{ZCLU@){!H3&6sx#i7eX}RO>mMd*(yNz*;9jGVEZL3f zq~mOpES=0utN7Q&rrs^Q3G$2=ip*F2CaGaNaF=gwHhzus?F*t2 zHMq1?|3R?Bp|6z}GP|sO;j|jHZ==X!8!Vk$a?dzzml@THro-9gk?r+E#401R3QmB< zx&R|=7V(GHAQ($iomJieoDy}@qS(0YsmPo?9ylusT;R-52ilRyPiD{4Op~avId3(& z15~|L^#5x~P=iqnAiVDWX)-=(I+I)*+hg7H6YBj2#fI>#dq|y<>!uc};%2$HvQFwUJppxHdquUlTwRDn)u>gWu~%E){Mn0Gu@lncYppVzau zV-vtJB(D)x6+N|@2-!WR%WfSAEMcU{KOxMCfM?1K$c9)^mQ`HH8N#jbx(T7>1rZ1^ zUeO%OSTk8(Adq!cG?g6|QPaH=zwE(u(Ihr>cX~;daP|U_WOr}9=dyK_QsR#_n1`-T zdL{5NV293KWvNp`C?HbcFo})bce3%ZW&bgYS>k^us0WzW=!ijq_&7ayipwK9J&jh| zkNx!=Rd*H|@zR5p0x&vKL1GiN4IQ>Xony1Y-gSW*HVISf?*OiWU1Fi=WQ^UfFGZ7p zmA=&&wj^A}$XPfuScTbjrcfLHbxYc!eJNjF`;KHk3@8zlDT))hka98EsG#^NS|&Fb zQzRXr)JWSQfIu(U)G0N2X-P88!NH*OhJ4dGwzO#FnWE^f5+Yojl0QD}OuMy|=Es!t zS^7$P_P<_$uJ5QF64_^P@{^Bq$9OM>pSla6oF6s^NL}6W`je95N}|02>D_rqLaq&H zL6~%l?5=}URu@q+xnwY)OLqC^H+}j|F4lBFbSDrTBn)WS>d$KFQ&t4}WAZ>fP&f!W z`{#Ie+ z60~+UTt!<}4z{Iz|BjYcQ3AnR0eH=_DjNW9ut9#3lJ_?{47l3iuTTGaeN>KB=K$`l zPexS-azLE`au*tqgF5+>@&x9-i{=260WPGGQbDP%7*Kr!TEiO^Hec8MAwMJi;{y`$ z1>XQrpn+AIfO`{@8#OJhsVdHuikH`eG_mi_NUB$ZZW;{8Ej(|};8-nRXf$<_?}y&+ zw29o=z4q(PFBlkDuohs3kDAYBtX~Va4w{d|!EQJ?5_e7RsU=q32TE4s&Mh=~|8!6P zx~sktQA3bwLl)inDREtvg>yW-Q~j1?d%hVc-chCc*czPBO+3{?6$wjXcKxlO{n_eEv#Gx~Kx5f}rsY2}6wZ45j-1h;{~uYlR7s=~+nYcl`B1_J&k z2mY}=r_~tTp^k|gArP~T&DSlica?ZhJG`@7sB2FB^i{M%hR&56 zy&5%RuN`A&+7+8F8I;NC1Y5OmVM9Wf7wd9NTD}246F%>u^VoQl6-9f2;YW;wraVaG z@+@y&)m2CDBic zp2qf|tfZ&3oMYqdqGac*K`{zL(Vi1O6Q@_GGKd$6LXyUHFr5CK!8B1k7p!RSPvs`ucbR z4+$0Ys#+=C69f073M0&Mz|1^LY03ut2&&oi@DW6a!i3$w2zR78sdToqAr8DD0Fje| z%7cu48MyNUQhvuNYalBD=oB?jDLN`j$*QnO8hmQW9Qnp8`|cIq2_G5F({h#=>&2d_ zjZAm%=reNj<3oq2qJW9=1wh~$zgqGJ4$tjltU7ZOZ8yU&S^I)NciZ2UpKP9dw`bp? zT;qD)b0ek9=+iYfIyn8cW5n126M;`qFVMQ4g|u}wuI+r=`eP5lT2%^VT;XcXtT_h7 zenV?dj77hjSUPFD`^mpa?`95yzbojsu+A(tS!wTs`s1gjms>tOO@& za|zpbW5zkKt{)fG=mO4!fBXWJR;5Y?wUcImXGahoLjW;~fzkrP_Uncn$;|jFX7rh% zY71l_R%{R}Jct$P1O>nguR!&%pi_QYctI~b&{$Z$#2O^@IziHq{4_kQ(b`c^yA?&w z(`{xL5?Th#PX_k&el!0-R$FkJ3JKkL4KK-M=9JXZFx?a3#mqIPwaHD>K0JCUpo__f zy^^0`BFINacWh{{XXGKT+7&v!))j#>BwIQ|hbt=?gwCUtN5^1cWo^TP`)=^lRyur* zNz69^uQzTXE$!BXLB?+xHQV<`DgO7?`;)%Ib&-!&D;>p>l99>c z7Z9MT*R{duVik0|Mi0bD7bNz>aQKd)(5Mb(WrS#=+@TVpa5uM|a5g<(|sqoO{aDh{PO_304S~9 zrzHd?iHd#jz19jWLj@WK)kBiO==V%@yew_P(_Vm{tXw@s#stxbKt4YuSZBJXP%-kU zTL1(X4#Mz0Act&fd$#t19$i8-AYetpFYdAC~o z^p>bBV2jKLP7Dq0ZB4}o6}At9TyToE3n`zHZVhv6g_>VyDdei&@*<~j>M;!vZXc}k z2=;%ln{IeuaO?gi6(p`_?EINXCaBktwVqL{Qq0nMtE68lrxR$9>13rnzT0ZmGG_1< zg<)tz+H@Kl`HZ6~5n)7Dc>xY`Q-K_=G4Z1()Xu^6jo=#Q$K6e*z5=(!X}uMnSAl3~ zer$xoQ|-d!Hgl{$E$0cKr&wn}j-Ma0#k`pDA}bGvOGYdw2reCsAF@xA5D-AW3oHwl z43u=P6;Pyt4? z49}OAK_7UHsR-xj@ot6@|{taA`JRF%%A07f|#Bz9=0Lt3qh<$d8YO%EPcIS={ znIx(DwcgJW!}2_R>c}fND>__WwBQYVGP1~7v;6) z6OdfHJl5a~6>8Ti;+Q}xxH}wRle`O?q>ZhG{iK4J3T{Sz)kXuY`G2k=azI;Yeo3y3%NAiCf8fq$BPQ#T& zkp(Gm2Egl!OtK5c1Wf~~Tv5Fi;&=SlX$v)d=c%;327G$@p<-jVpQR81SEL;+&|LMm z2qQRs@Hf_)SH}?fw1ZBB@!n>*xOHJzo~oxxuKlfw|EST~_4N$kl{}{%0%1T6Z(kcz z5Ch{9#xK0uPj@2d%wzI72P8Oji<};p8?3w zmUdEJ!_rD;nZ!l!_XYcAhJNCo9~ zOL>U2ivU-Y5l$i+8#W$`J1GILpY44v0>zBa^7Z!6hkXu@DpGAmYjkN_z8BaIh}f-> zk&2EYBCrP+<45Y?bF`BS7zDrmCex{3j$FjIm#Hu?T@phifB36=Oe5}4(jKiU=2)aA zm6xNd`UJqGX*YmWrfiW!=ne$$FmG%a46O0}ED@yI{>^0|A-2L-rLs!Rsk=~15w^2x zWrvJpZVrGKz!sL0ed1mJ$G5+~mv8zgXEWw$PAR1u2}u!@W=JKZyWh?I+~4!w$ML=I_w)Pp@PmV6xMpA1 z-q+f(&huPrk(>2}QQG`)3;AC;$F&wl)CiddoQjbQzD0qV#tvLI4UTo?N(xMgl-7!p zl4Y1q@wojLp}L|49WPxW`U)i?@9TH}v&4{X&ZABxC2vB)9%pBajoEmD&lEd_#vbRtT#qJXAPcnsI<)6^FGIM1e$wvSswfB%(&j!S zMC5PGPHN5+z>d3!OJAq*H|UI%ESa6z_`^CE`3EI0*G{tnK*H>b-fMA=+lTsTZjO&y zJ+(LypY=@}mf%363Cr+h=ATb5nj5BA69}533pO9KHTMiPA-VCu^*PE(Idwp` zZYsPVc6VY{(4u~qahOh<&w(^(Cx_OpPz^%^O`GQHU_x1oD1s#QQ6?fnl)`R)QZkZl zB>+}a60A@O!~6*oO^>f);4d)ld;tv;k{I#a1w;6^;|pSyqQ`I941sI}cDjLzk`x*F z+`JT2Y4_K}uGtovnvbLhASP_~nl$Q6@cj6>k|;^$wS=Dc_F@e#@GtfCJC{9OfI8jm zPpBu?U6&cy8Z~X!?i%yh(~TtO3qZn^?M1~nOIC9^ShVm{6tmr$)-5jKrZ5FD1Ucip z(#up-V=Gc_582Y|kueIs+wmfJ#P2VjptQ@fzk9n9GiGc%dJm$|7XUeF`}T~Na+zs- zy_<~SeL(|r(F4$E>$kcgsx>2{+SQhGT0oTB9D)E7*+tv_+XpY{#sjL%$uL2*hG4*M zWsu$DtAnbmjmgTZnFP75XM6F2&GA)w**AgKt@5_}+(Q|!RHZqm%VZ@jbP-NVUXr)3 zss|@DQ7sln0XL*Gn*6JPX2cgIOxadH%q6^jKW}ypRtx@+4nxBW(KmYx*cLY+oYasx z2Y1$udn>PEP|B{OqXka~o)J6BW4+%UrTgHWF-EOZVcCI;mpyEtI3hR|kub5bsp*@O z^;x@(`Fy;}<~Z;E_PkRl2Yd6|gp;$uR%7Nb5!dp~OP@zXb-znrk3 zD)$Te9)%h{8sN$mWys;|_xiOP*45)6P^4LMCVDs<6qs(CVm7K{e6!%I2F=*g<67Z& zlu_M{wTSRsc;Hd>n{W8KQwr>=Lm7tz^dh-=!n~?~80n@c1wBjxy?*Jrubxnt)k*@g zz2Q|r?A+R7;Xw{+fz%l2k%B_tr^Q4V6 zzwRx$8Khn!bLV7VGJLpQ-yFLTR-x^@&PCGuz)bk38J8&KIWa48$QT8IP^QO44VlS6 z`C+o4hC&!D4hsV6=}CPTocVT{^x`4>84f_7Iu5cp2~>q&Thc~laklaiWpVaGSp@+; z!J|Hcp19zp)RB?Ryq0*cSY_sj%4Xid??-#>b3=j;OnvGriE~OmvVoQT_)pbPKw4Uw z=1q2Xq>rg;|DCVtiU4E4ib=n8o07Xgy++fD-ksMoJj2_`8c`IdSB+u-dTZ3;tue-v ztrk3a^)zi4`25mhG1(bT;gGW#{r!W4qkB6Xr`N)2KqI{L=$WsUXze?^`jhWc@Y`RZ zOK_QSYKvL$DbaI?OT#}&Sd7>2=2jnd+UYilcbtlR?r}oi!ce)`4NaDLEolfB+fHqX zkI1*3W7C`|!AjThI>}cjBW-Ls+|6ZfA>qf@IjaUU*o=W5M`cp^Vf&Yr>Ow7tkZ?x8>r4G3k_Ip3w8(qMerfH53 zcR#^g+{l4@cUdR=w~p~N@^2lZAG#K$5|5ZG_$^XK>;sh8_^E^wsU+d>)TJ!9~|b5!(CX_1lZ{F zU(N5HTbmiAumR4H*6YUFpRUhjA44t>wdZ1=aa214mCem6{Ajqs=hLS@+m+vxlC+j> zlKzlEKkoa0X3p7WvHJ)Q{h=4fF|b>pyl0<7RVn@xQu-g@kp49|MCJPW&NMit5oqis2x;!$4(;TZOFA|aaztZTCPh?hm*jAaRf;4Ul1wu_;`F5tM_-< zWT#4a#9P~Yc`8)CF(Ppn?^SfrO~tYwS{u2TNl6EGDsNO+X?7XYKrBzF<*_a=Rg{Uu zK2W{y6xaIAQt+N161~=m_4TtH1}_}n0eDk(ul--8wA4ZfWxe!M#5$MZAOMf{!O;o4 zCi9#A1PH3YDa6BkXeGkq5^*&*zsves!Z=D%!DTGba*rDELG6;Q0C}uM)!yIBU3?wh04r=# z2`hYge2%Z=4x4@Zbzef<`6d4fOT<;n)(k$r8U3)4dAHC0{xBw}w$r`V<;N5oGL&d< zPR;a;&tC9d&yS{#s+*tGRhTq6UzjkF$_Beg?$aMU_*m4e0m3jyd@&`T+x~_iMIo8h zWlCkg-A)2X%%X!K-&on?KC9C$?8HE1*)UrpTMx=0vK^)94s^sDNB@jA2fFK{D_)su z`Eh$TrBMeOW}t)nmO$11?I&a~)paxj#;eDy*yC{NzlloX+$?#JwYTwft(Z$#d7=SP z-icXuT`f-=gBx2!0oSED58`0~<4c~s%AieFAeux%XguXG%b^f9NO>CVrzT+wnd1!F zPZYRO_ZFxI(wsf7dD{x$Dw4B&)qp;I2#%(T$euG~F!A*?WDO7_a+WJ>y<^qkIzyb_ zKz4vz7z`O2uamqNEOpXyaz(Ej#`&$9Vi-N!;V|WWyPlP-h5+OFO1JDcVHLN)-|#35 zE$bURwU-B{E7A>bks4`VX7mDq`mR_h&I5{Z#wMN9etC)@leWS7Swp<&+?651%Xq!`ev7&1sU}Dp+kK zbn-Q&NzjU7%xW8R3+@K{T%yB6Z&qy6;W99ZUchgM!pb$leEL&mu2kxGJA?uUr%fSk z{^YJyewO^$hcTtW!j;^bfdN|(;gqA}a9h^i1Y}v9sv~-0`ctK|bR_Ij1oY?>_Ix~l z^2^*QB5R!udKHg5BD=W0jQPQ$4Sdbtr?`UFDI;rlc{t8ET5QQLjcJdPErpV}OkR#a*X4dI9UF#?&QH%6SI^9W7NRoy(1b3Y4ZH)yDQe2mW=Px5`P z#F6~8Jd+qjdnHKRpd&_UgfyX+h0qp6Ge<;i%r1f9Kk`N)P_3z{C6v||2&GgzK zrGujG1GIX=2c80=$cTxED1qdFCMwGWCTj&{y=+OgOujmzk{v&kld4?GfIC?7O317YJK-}7^bzI|b?FF`rcS5w4i${8>~zr8`H_We#zhg+3yaQ0 z_@!z5ZeRB3RLC9<>zMx}v0{B60%;_K95ZGJK8eHT#xa0S22xqk)$Wwx%Z}f|%`1bl z-jvr?3Aap9Gr!Le``unpc;_S_SHIXfu5YZg&|MInvXv$7{D^SO605>9ZM zp9qs+ZhN~#EwKq(#~C1{&4Hz6l^uvW@UCO)R6TaZf=XHll&cLJc~z?ze*KppIL$>R z=Cir zs5h!?O8=NR!l}|0?S|@9zY7HPRoY-Y870Fg7nhRXy?N~k$!79i>noG|Gd`tJVRlzm z7PBBrNDlsXwtH2u&Me-Dxd=u1!0v5ujk+kJf+ijJPv2u5f3p0NOu`ll*?9%2PNpVH z{YfGXF~%GFnx4s7qz(m2U*qvs-UJoE4WucnsZIANi0cvorsBJ;6g9n7$X@_aZ?B*5 zA%0vWGB^;NAuP==WE@8b0gz#{4nc}nryk1bAK0*soKUz;eDv|@It${UsPW%+oid|j zl|;g3yo-m|w`!av{H973cHmaX8hRmTxyenzg;WkYb94%&LER5~pVGpW$Y&lNyWPG^ zY^<#F@v+~%m(Rem5| zPQ+$I3fB;hMF^lruc3v&RB6X*qM=6|I>2cUeii?62ZaTdbw0!Ts&-WqQL5m4lS-%X zDIJoJot4$nkfUK3!YxV>_ChyW z7xysawe>&$OjqEVBy1bd1x;IvkT7J!*c{K0S6x80xUJcZ*b4;E;gDn4kr9`v~DyF z<4R*n6seXLH(d!AWf>{#7}MnJ(hUvfA0K$%zAnX;!1V<(uA*`4^7q-ezD~vSi_-?$ z@RPW_)!`?XIb?+v@!q77@;O;}Pst0d%&)h7-Xlo|u{+p+D158wE4mFO5WX|JH5G(i z^vibpxNk=~eBcf?}&R3lQ zlZG7GB&@JP&aW8nd7I*@>4vCzl&^fGMSIv3D-`}%&64O`z&a6HzJI`@B5fJc>O}0) zQoUFw(>9FD*72l|d+2k4d!S%NY0h;(@g)PvZvyoZ$tPJHI&HT$m|)RBb-Kc?)7h+c zjk#?Ge)ragS`@Ypjaq5)&e2fe)MBOX0bqOFgg;B3-0 z=7@lXur3jw8!x_X+p9?j*Tidm$>-#zpY!-!xn`hj`s2Iyyj-&??||dzir3x(CcId$ zK9PkZWV~B>B}e2QQIgy|`u4WU=gK0)#N@6tQj_+zoc6B1>H2HB<@<{OC+{$2oc?fZ za=E&Dx@(|mr^!vl(Mw51Dt{U-0A-B``q7a`F#M~ubW z{|hVfxyDv6myXtL@2QpQJt-y%7!xOTJrh?P&4H)88;Ot4wn5;>x!qoVvJR2_1l!SK zuSuNHQ0oc=18>5kE>c3eb6wkKhsP|WL1amN7q^SKUEAj7MC*)z2+vhtjc|wHYnf}I z9nkEg51QS3R&{Prn6*%0e+A{H0=!C*?ZHuWz5W&A3LjE2m&+s~)Xyt=#1A zZ$z)!`HUo@N>ozvlEL@`z(wWjBfwTaEcYM^QB_6`=FTIKXLpJVbNy$jv8*;FlOtGT z!=NY{7Nj^5mei&j!Lp=9DbI@BUUNJr-LfKZO}khmqlE^rWxE(hyiVlB8evNJ^2}LS z*ObJauc)w??2q6n^0fPjuqbpRcf+ACOME<^c?VDfSGSAd{$?f?{iQlPiqE}nC%#%z z?R*4SAp-9O&u0xbdN}*rZ&-1Ni~PioZnrA0l-R*^C$bz!+{x;cc&W@gmQ(ViEDMwA zmTBtNOe7^M=(y>rB=?n+P2B;p5-R^{bNMBRb^~l)DqZ;fufGhbz#Bawc6QhU3&vlO z*#;nv;)UKcdvX&Dki$bVP;=Qa8uCR9#bvM4UJE zIdfC>(S_rKTmU9dhF^`}-T6zGVjsZ7;wBQzN6oVIvU6&3cVD6FTZx^Z5SO#3S*VeA z*|1Y7PxR6{#`V@5tO3{i(}!JhX)~LIdRq+uQ<%Nf#n*R3V%$W&2ZVLb{4}xoFZ%K| zLXJhym=8*+11`JPElwhsG2VuT-n5jl%WWSsTxr~twKOV8s#=#onW2gYsZ7lHA6OYU z7B;dg4rj$M11iaQ7T%JEICm@M_UT-SL`6h7MGLGM-AIomTtR1vtO(+E0b(V~<=of` z*z4nPOGy>w zisi&&5e;S6d%+{WluskJ*psSZ@eN|z_^%{Z7jTy zTFVaZk3n`hRvK#3zHbaxUPwL6V+r;p{<3u zS8cO*n`;-KEZZHQEBgWEDcKy0nXm4U>pW7_qZDQ{bcyaP_#hm!(1W=QF4`TCN=HFX3@B!IGR zzl?-zVuaW#c0{0ea4;J=JN}4oPa6VjrHi0j7OI7_FN6aoXJ&xkedi&UL2$nZ6hyNjxHd>3qAp)qeG4Zh z0AHV9^|DAi+x6n6xyImqONs~d6@d4VdH;n4y9Dg5?T$~`*;p-@z%72c!wVnWvTy=j zzGnJak=55~<*nK-2*Xff0t=*HOk?%~=75s*!{8Ivsv>6&evbnUj{)IEIrzP}PpMmF!vldRdVcq|NpUv(@u=VM zXe5DO*>L81zZAi`)d`^a>$AA$xsr=)rrh60P3H!d3NN~UF+08b;^YyGn1?J>wYfkn z!rj4FObuchtFjaGZTk=qNZ+B{W`UN#EQgLIZcch4Qb}HOonHqnc};>bue*IWImFND zeH?*-sXGxfojF|md?2ZBJVx2dOA5pP?X?CC4+OLM`uTMYriqOmYx30Sb8T+aZz^_#(TWY}1YzR`?I28xu7I;a`0;x~^H`Nn6(j4$U>+{-^gvvN@P}e`AD5tqj zAfv>-zJnDcE8E^45lt>sJ_l4q0#OiO@{enzeNgC#CmDhSO2VWE#a%JQaU!> zYH7}W`J^QP&*LH2gZkWSPhb7o)4%lj+pP{eUh=lcX)GJ4m_+qZRdLnvNWYJ$Nl7c0aaa_P5-UBMTA_8eO zOUXkwGZJ%CMOp?|<#TLD$6zw1jqOepmjx>eFkxqNXu90Fd(uJLYC5usE7uiM0rdt; za-Z@XIA)QM_|+L1hAFacV_o>H<{G}b(d1%gBK`QY${6_)JM2spKW$$jeBOieT!hN3 zP+vcR%h;GHavOiqol|AD$mxPVTinj1Ji@iMI5d?aqfg4z%v`d4th21qaAe=u%nLu3 zf}8sO;49+D%TpEi2hT4an^*)XGAU*X(;kRb-SK3K+9%$F?J$n|WlNSd=g#VVq1o&& z>N$e#;AoOSW6bDi+$11*0z=c_U3@g>uRiV#l8?UnbceLNLmK?Ke)d!TaAI+-jA ziuwTzU}|!aUm53;DWcnnf{=zeLySDYRU4jsvM&Hc4~xIAaAu!h&Y|+tDZEz;P3ktPYQ}%9*M&aID zE))>;mo+>1bzirCvNvI)ODXreAtcxr()tkj?Kaf%E<_sR_8J-xF&E2Bu;ZYO87DWy z0bTdb?>{cWK34ELh>R?`1yqEXdbqh&$#@DQLHmW87lTZmzFoPzzbkq_Z2z9DaW~;7 z*$16jH}~(cReOhPL^2w~;uqdLWqUXE+RQPe9Xhj_bjPg^5QIQ7zS8J`!Hprvv`TqMw}| zkm*)_uiV&nDs#(ZXlP|?U+(68KPiK0Tux-2b@TkG)Coh-r zHxXKrlZ^%vv)45&0z6K8A=O>3Ja^5Hi+!f(lLk0Hc$aGJ)Km*>@LbNO``b~f-|0~s z@LSfh+e0EWd&gXEzrUKktPW3RNqfqN0=Z@~X|SPG;pcA0rFTv;NY=aBeP>Epb|#qpY!FqSPJ;J7>%XmThz)Dad(eLzOVMCxqU54ZdUT0ee!Lz^rF%Cbs_ao> z|N1GXuY0YQ_SmXaMZHz;pTTG>2|4wQ4bnrqJYSt#Hn}#$VN_xWlau{?v8X))7v90t zdWRt6(2EDJ(%ZJBw=CEno3mM^{K}9Ly_k1HS?QY{B9{dS`yw_G=gq6gGBFrKxtzS2 zpJRQX2;0c|j<~jAWv~|6NJnHSnKTP7M*1Zs7Ig$X)5t>Id4`&-PS4A9?LMOQP0(0L ziP6@#&2Z=SUXTHVQH!q$v8$>QE^#?Gb@2UoP;B@3D2N5sCi865ADuuv|&hG&!FXBuDRJo5($kZ{yYDaX_n z*Vhd3JG=s0%U!Xz#1M_gW@o6IBeyi}4h{6rd>?l|PN$Q`%w@ zvFyo5&)FR4=&Tg7?|IG!yw^3P^F+TyMy*Zg_U36Q^^x&^v5B;7!L`zydarR7bZNI_ zqw(n>H(7_H1dXUqsaC~Pzsn^Yocl?V``^h`y%{8D8|^(@EVXSN6EF5}ot-^G7b>~e z#emYyrRR$IE!k3(uL5#QGDknUUQLdzZaop5S*$VVb}>rSTNm?M3Nehg%X>zo*%KEz zW>Xs>+gYsMZ9IsL8#-MWd1Bdt4`q213_-y$#5LqCN^pK|OdHdxySLo`=~a6v3ge3@ z@7upSRlOFwx0pHA$1{m)zsxExF>&F(%jC6w7=eDKtGf}T{rdF79a1%R1d(ZXvnNc5 zr&xp%pEPjj`3-GOa-oeerI=BJs6IEU-;WESs%gumY6_Qr0|md}(7! zSuxqUEIB76?)s$eYR|5F{T(o?`uli?>IH6dI`;S>SA;MwUqO~&2qrYwHV5DWah zwf@`Dgpgsc1va-t)0*qx|DYf`y2>5c(lv}XA^=O*|I~0` zX(^hY`{cb!0UOO}!#*djGJsM8<&H2}t9+Qm+?c2NaF_HkRhSsjUsJ06g7rAKmPSD*5ac7Y(pv6LgWWya_RBgN2g>zF;vtjSZjXe;2Q%b6zG(#KYJDPytOOg4-hkYmv#r}jD%hNExu~}_Exfk zvRGVOAj4l4C~9UgGuRY1OnD>`ZV>%2Mu$I!p|A2-tbZppx=BVZrYo0U7*FIA@ScAVGB~Q zAndEPx@7+T7Wfxv3?=(n^xz*~{H6wsZ$g$1?;q{|z(f-KSQ!0l4E}XbX#rqzwuCke z|7afpdWQJVgZ(uk{~57=o6mo2?Eg&D{|~b=4kO0s(>#?wX(>xVw9B4-g=DaEAnULI@BX26uajD@59P4xG>bn6EXAu zJ_#J6sD>yy9Q=QO`W_n|3xvNG_~#!O5I3m2mQmkIvL2ty5n{~y8-nW^Exozy<6ME_H*SRkxt|6c9C zWavo3Nd`;ZWWD{j?&1EC0Vw+U|F7tOAKU-u6%A1XuZJH$o-hbLq@!$L6K1~&_{xNC za!m6Xn;LOVI!G2?{H9h^!tZu{P0qEoq9Fega%%UwjW9=my_1JZu@gniK416qxX>3- z{d?TWAR>d$I!@BRwI8du+KRY@Iaqum<(X27Tg{?uw>FJau4IB`KT1 ze?*acAs$S)!6BQo+_AeAG-5`+#L7R2A zqtYv81(hR3-yi04J6?%1t1JwNZ!ECsGwquE$79oG_rFMIEM}ZhMvk7Nkb}KeA-YFz zsXlB0%W1D!d^b{ivU&Bp28DVAH|R#F26?rP4iTjz(;-91F_MnERI@=QEP}zEJmYsY z<*QNT!NK@OVR$(81Q~D7) zQ`5`oqK3w8>2_2eNG?d`z!tz$%gw{Rw2C!$HaT(kj&YS^0psUKY=5>6*~OPF*>WT_ zpX*YZ?Sw#owxzmT(u+nY6McJndhi!_SrL2>?55%c-etaj!L-Y|I9hIp{VS|=j@Ral zr+!Ow#`C=EYO)crN};J7sdBLfWwlGGhTeWpS2*>UW$<04THbQfNzbb z+UZUG_lh^tfp$dHHx^O|gcNg}&Ze1iNGT0M=0f5he}Y~}sMjmP<;162DC^k{usZE7 zY%Hixn*>QaTH)GW8Xyp6*N|8$$wL~2-VB{H)EAUeqeOF*;eS7BMLY=xWDDC3zyLYy z4tLoi*qyBP=-56r657%Z`0AkD@a)PP1wLSpdnkjmEY!oMD)qd+;64ZowRRSZ5JHC-<}y**-!SWB z>Gio#md|nku7hVE=NI7s_i!5TTvM5wu?;XjEx_mOXu~0pg^7D8WzurlK)4Eaq81RA z{xas-&q*>wlyTb>AuAVm&LuLt;f0KE0a#9ZG43pAn)sY|>z<0uQ~2an`m3M;q9 z;8)6JvOFhB<>H~J#8@C-^W5lthNaT?X2v)mfp;<32$34mkuk!ms5C?Q$-eR$q|zvS zS6||SS&78}|Bw9@9hBTaX2FQgzGt=)SO_tDhOq?e)u#j^29|FUTv$Y#z}2X;*ErRn zh7K_@5EAKT_xFHtt`ewZZxi7LH3$_@|6Ixg!P0B1QoJCF28cks$~??S;DBdgtpkW* z5zAZ|qa?UM%zFcmk9X(`M9Pac_F!@%B|!XGAwL_+|8k_L#;4E46+htA#pr)bxf=RiGBe{`vHd*aV7k;z?C23u~GEE z0zYazjVo?51;!Z@SwR>EHGU;le*)Dq00DbF8xt2!t)pZ0w;~cUmUq$%EKsYBU^Wju z*5_nY-1lN*%QA4l^d#z#xG`XQ!sv+RWYn^E9j}P@Z!wJ8h(ksgdVY$ch_PsHiO1EH zC_`2YIr1^S?{Wi6h!U;P>`R8O3s&_l%k2>36^j$nXqEMpU2-7^@TjmDGh0NzF`J?; z#wSu)V&34peO_49-s7WZU4n?NB6_eSRNM3Yc-LH1!{rfW9_l&?3u+pDh6OT2Ay8c4 z2NXdX^|got)cE>tDTdCM)NdwKjwnNo9o5W0m6Q9#-(&mXCL42*DLRv{q2~v`YW~90 zp?q$GY?>r}PdJv`i+t$~=^q!n7SdDqq#H7M6c~|F@j5ze86CsTOHYbUnrD(fSTDi6RMU(2^sN=N#<9w=B!1u`G_?+}hx^Dr( z$C(;uGqOdYDfJbjWJ~*Ip(64y)ZaN$F8oo1A@6B|tt|0(9prAiCx-dUFhZk=SMUT) zOQYE8%@&Mhh9AU=C#Q~sqdm79O*4OpIsIOSHA|+pqfiZQ5MAO7rg3{Ikzs)>F!NqJ zN)MQZP+eqXCRMKtjkf-5EH?147Y(^``UaA}2 zR#w7XH?i^acnw_!pZJc83eRO^sJ|G~s)uk2AIs%OOPc5$jL6_q+Jx#Bh+DWRv!NX)yD&0Uw~ ze4_0>cp|&{HEzfypZcLqW`L~KXR^B3No}*s>Sg&CDn?c)95*i=9C-aXFWcjN;7p?f z4`MS?Xx&x&<&j?Ik1u821+h(%D_+{Z>Yi1FFhwM#I7VK_*}QDtk!23*CN8J@GNp?l zJP@d^kw_WSVLpD?dg^A;-T2N3W}f=^v%6wjCZ@eCJRdDFO?b~B-E~gwU@w2yf8gSI zTzq6X=izsCGr2E65AE=%Amim_%U^!W^h17Y-F9=tT;2js@VCrBp~ypE2zOG3!0!6$ zQC`fCPx`n@0=8_7dy!||n%ZoK3+EdgtdPmUsGdwcH~zXA&gg)lGkz|a^1va{?6|P60YR(T)#x) zZPNAqDv0w#ZfQ2}O3d|DU{@s`BiUnG4 z`9iOn`xyr$+t>s35JHzHsU2)r3yz`F4A-N=$6wWO_mCI)N~8;>Oku4**3jhC<+2M` zZ>V@OM1M&u{wy0C8_=FG(iq*}PE1;6%Z-^P*p9evxlkm9JzjwW64`{kCy_XOaJU?; zX_P$e7@6=u8M3a?r2aN${mC1{)>2Gt7V|=vT)Nr^C2!gIpglbeh%ZT&N;8p)`rE9H zQ{2XhXrjb>6>Xg`!&UbxY_3;7Nx2SdA~$@-GFR}8eq%je`+U#R*Qnl5ZeDJu@3eu7 z{}x*Eva_}d;p;!`UZ?T3^%Y4+`zT*{E>C16G~m4w-0>h*Y6C zt#o!&N5&wV+a$qVak@Bm5sjAbfKY@4$V9~*>OUBKP`c8zBzU9@t_4rppOp6g2^sWj zX=*LZQre}c2Gg$?IXibM0~rmduRR8i@L6)g5s@{4{VcQ`L#70WBL7APLeRF_-2rO zXLt`H)!oNHko0gCLEAGnAj1WNx$?ET+Tn#okc6S8V^HXv%JZgcW}U7${JEH?!W2}i zGh6%Z$fVmb? zUHg|=cn#(Z45=oKWvCe}%h+co-TEc$gh#nO5a6?G`~f@mpu78J6q_b;?Pa4WZ*+3P z{<5LvUTonvp$|V5;3-0~#WpT_Z)=|Odw3Kfxm`6i-P`sSIovZea~{?@_wwe9h>V}T z6Br4DBo+g{S1mq&s%z0rWhuNu3u(gZqFdu0=FCWFoZ7QYy%ztLQ_xUIIS&PZdt5j>fh z*#?sG=b2;~@|mZCmTEd({czq(!K9uSX$~h%ujP+^9+_^)bpa*fa&S}|B)gs>AQghh z5A3xU%wV==NMf+^!(5dP(UV~wyTNv;ffwy|GSfa-Y5o^k1WHwh;qBOzjJ!WNQkWQ} zMOsVWKd^!B`a-qW3 z@6(@AF%EJ@cMKFQwJ&d={g#p7f+cl-NX=IE7J+iJaMM;pB;cz&?3B7MCA%;84ve5W z%)fVPil^~~$E;76DD3*GuP??w5!lz8zmN=GJN=mXkgK9OzA~^YA!Q~P2eYg2Pm`e# zrtVqM5>P&SXSG(Ou>*vBDP>PrDP=R0jHO$OHjI?hU2W~%g^?JRdKG`b!tGs@)YLi% z!e<4RVS+MLcB{umS6!b?Vg(JwE$O3_6xbKfg;fzGyI&&n9rsa`%gmIA5i)o-Qknu$ z#j>IF+8HzU+XT_}m7_FIZR7p9#g#_7lQks~W4w93N`a)|=$BCxV|aWf*3Uqo-xQurn~T$IfetB5uVY#_+Mvgo zP422Uv;D4lRt1KJ&mNyUu(?z)4s%K`ZH)3sBvh#f^^?^#2TS7 z3HguvZqJt`?Ur_8sx0x03NaU7*3XErjvA|Q2;WjGU zVvEcDx^~3wL03$7Y}boJvRZfFTB^G{28%9lscx?8Nls<}9WHJRfCZ(E6Q@3b#B8g?nC|%m>N#oY!Rf+sYK;1$8vND_VeIG~`@Fw(bT9GZI2DdxP>E z@Fz%qstk(i`ufEL%ILIDw@j|I7X2#VAe>k>N}hVB&tlsiCw{ko-gz}74COJM!3E7U z=evvWu!Rg)tBT|lEE{q`i_EtcgHsN55!6gP6z3yReSLiEcbcCs*a^|u$< zX^+b1K+4O0d+Nsimf&^inaPR@d1&+VkXQD;hdBr-;41UsLy70h zu=m|3eCJGJ8ieE%HguvIi&*$dmkSL(x*BG3+0W8nU{G)r`JEgza&cY>^bje9|51Sb z4jg_5i5{LiTR=*wo=h&By}qh`mGOCGxsjT$pp^!C!QfTFCgk3!xva`Y`qsuCDLwAz zortjk47Rj$HxYU(H`1ypS;3*F{kSkuZ{hGKeaf%ultn{B(ci(2Ug@Ra<<#Ei!4?0j z^ai0VL6*k>CN${8qq6V$L`zxh3fE5 zcdwGwTdFX3%&e4akHLg!A?n5oV`75@{4o zC_MmvDH(|)&JH2s8c^x}Igyk3d8)@R5_*`vO@g&Rq-u5_)s0?@6;@xzCeFKo!3geR zz0T&SQ;y{u93Iw^lTRHdEVY&|ZaPs@h!c{ap#-2;?*8}PQ#s*G;#)6WsTuXiVaFA_ zo-!Ceomd$4_HBZf)!11;+N?hpPlxxIGiPs%8Z!bg1c0=_{o56o+WAq1T!V7Zpy9GQ zKDIq2pS6GA25Hz&toRC(f-^I9n0$1s*Y`fjP}AD-pv`1Hl3LqWvU$h)4_=jTW%BUhT|)c_R(Z1W=?Ko41c> z*U#5=zbX9k-kV^hU)FkHnhxx-+j}Ak=V23Xsoo>|J&ZWG0lCygaV&b=hWImQ@ZIKNJt10 zfZRsWS#`IL9R{nL6Kwlz8!yQFb$bHC_oTlX9A9LAq1SkL8C&!0`O4(DuyNwUNiM8% zEL1rO8G~p}c4gdc@hmwq8MP_zU=u)rvvmij^-D5G`gMF8(hH+{96F8mXp+Gu;FY0f zfn_>M9bxFMd7fMO(L6;)6I+JxXUUk<@lO^CPFTjT#+7_GCh9L3pxo|#rM-+1$`p=y zMflehb53*p3o7UP`)GGu37~~;#pVJ4l#9CV?i|AiLjYN@m8d@@1m$)^i^8y7;ND*a zWA?hzGhV#@+|Y7il<}Cg#uDN^8>;ZR@aNj<#Nn?AzePNkn$0bQhF@4)ZSEQS6n^I{ zt}Z)mSB@6PN7>ob{HBX#btXJ2_JXZec5e**p`+T(;|W7bf>5&b7lc4Ml=1{xg`XIieX<#3WjNpRdk6BhK7w~?YE!|R_FXh=7KhBR) z9JdpS%?OR{ypg8-z;S(eMs&IP4M)l>@E4()kEr(HYCjFrxA zGvlF{UL#2}GcR_<53d&JnR27=b8JM=voS?n)U1DfjZ<=AAU%F?bn=Dbw#Ed-#PIXm zm_Sm%e5+n+*(w!NBSE7#%7*7+ysa3QMdTsgb25L;;@5=6)TAo~Qc@b&o^sIxQT7LlLor1laZ)RUsL9XZ|n*({lr|n)u<{;K)L0xHtd6Aac_#1sLi>~>Z-C5ogMN?LjGp#!lED6|=STuOV{%_KWX7KDnr#?Dbwkz~pHer4T;`JnD zLwEeu$_P8zMwIaJd-CHZWVZ3U=Fu@-_f`qoMh|5$Th^PvvFKr{x07=*GoF@PDt=XO z-yHYBkH~O8ek*ThAgs2F1o+9-_Zm&&8lP72e?Xony{1^9+QlJ&h5N(-M@C@nYz8WI z;RCGKFy?0imnddnUN7QkdeQT%6WrD(dN3V;GM{Ig6+ah33^!i1vVQ?KkNbWp>y?t& zpZWIQbaD(i^}U}}s9H^F0Q1Qzv$#Oa`*=vuW>2*y-{ji#u-cL_FY`pR0S*;|@`@D~ zAQfjk#2pkV0a6iBN454EsMd|$_27AZc;Y3cbM{&&|Cb{X)cz|Wxzqksl+1!mJh7#_ zYsdTP$Z8#8h`;_PBMER-2+XhM?|{(|Uo%vpw<*Ama@0D2afQ$b!1DuiaCYV!^(vYz zLMmDGY&gXEr-?-&zn^sW=H~yROW)`JKkg$S85KkI5(MlQ`bSnm#3UcVf^n7cqY4~Q zvXr0zDAj<#j!<9><^0bVp79z63C62bWhKt<>gyw1iCIQI5Ag6VCHe*LV~K0Ciz8PO zI}9(^ly~-EyX-Bu9KJ5V62H&b6S=Yb@!5b8qzS_FlC{}S*I;2WEt59;*zz*{$RHGJ zSTu~3mbr${VP^jAZ=+d@a0XG0+3jDSAPEN3%;0N(UAy%7Z>cvGGKA(>_^|%BEkj5P zGv7Z!%BAvS%*}82bvQB2ID;wiLb1+T;>5&p+xTxs**KZUxJzn_iG!sRCnz00s#<@? z=R--bd(t9C2(l!=|Juz;szK@6t4m2ASzXi=u>80kdYf`tZF2?`0T%piEw{<^;J834JAglzWwi4^Cy2Cs@Y`AaF6XKF6e*oq$wZ(eFy zMgEos&JJawM^RTy)nK2U{)6N2aIPzN$geB`N=9_*y(*+qs#h1EP{aq$+-S#ZjkPonE(ONOwq04BuUF658x3(zHWI z4J7{o&xW5a=*K{Mr;#+YVpis}`h1%uSpA>0wt&Jnp(%$m{US;DI?2YXW|}JOUa#G~ z*BP|zCOUh7;ycQybO}LPJCh2*dZs5aJ&&+BTtyufckz!iU7rK&U;Qnz%wR+o|!{HbNK zI`|YTZ8jfycngP@;$Bs|H5cj5MTcQ&+cexsXkAL>B~Ix!8-A?V2mH+HXO<`LH~-^B zwBC@w5*ZjFJ0DPvJ$J}P$PwVN0M({dEWKjX1D4KDypw156e>tIe&rGPDru6blxpM|DpZD0_T*WAxWR%;=f1LDa&SRxZq@;o0Zy88q zOfZ=3d0O=49FCfa$-VoCVlWa|yiAKGTlM2K3SdfTsY=>_!|gb6Nh(ww(Dy9kN}z5S zm2G5SqU0wl?{8b*BqyILwzu1Qow664fj!0&vR6MngQ9O!ypaEah&+}TdQ;TJYELY2 z$?sQTYmHTyfSM5)+R#*#J334QHZCawO2W&eYE-N2kPZ`*!Y17>f}~xAx!Fi$Y=!Jo z=2)P7oc&xM8#_(?L4J?h;wbi_xQ4U6vl>#^bBuUy{H-~(12UJGWk2buycu=Z9w~yj zn#dlS7Jnuc%JunfwuTRi8^tVZ`2M4_Y3GcFks3dK|(Ak#_qxghi|ZBOV@7-LeVQ^kQ~?^#eoa#(ntwd^Rtq4iE0)jmu-A zGQ8Y_`^I#={q{pXeQAxKW_eXBWn|1`&HUOWB7;9?(EkJ_rTWv-NL5!XG*-#uH8Mw( z?u7Yv7;4Nqg=BD}m|3^i9J2rA+9?vP)4E2^N{UN2tbOxB&0VYDceWY*wDX*=vm}zt z=?V+j^f!TVWkv_pEC+4Z$0)rre6ra(G_L6>a3~#Gbooph03d2A=UnK3i;J$}9uc9? z-1ZVQJ7=>MeYw7Bl4Aofar&O-BeC$yW6wS;!`4$uI406bBF@MR?gQ|W{2qigUe(W> zb-6Vqrl8(cvd1&!*f+L90eVjiFe27+c&ed5%VCx=E3TU}l@(-m1o-{UjSA7A?!82d zhhN?luO~M6FLw1E*(Z)(pOd`NNV)7CX*1tZ@d{5%;{wVYSzRo=;zmhHyFV^_GvM-S z)gZV+m2uOp%dw~+=_G$BtK{o=RM>O$atfCbV><(=mCgIDgh+B$cq*1a3qc)gfaA`8 z)JpZ8(mYttk7tQf-bB#OwJZrN0C- zbTKuz!y>wIO-FCXyZ#u0CH123ToKPlyh>j;%n#unra54tC(%jk@s#0TKGh8 z!)`)GpwT`)YUJsf{SRib6*b16!NAoi+B|Ti80mXZ0w}rc=B6L_>@pgk@E$1{70Frl zHL_~VwXg08qu66n$PVg^)EwV2GB)i$usMAi&$w~Y8@IH}@9z!2`rn5=fBf=0_lW?W{$S`Bo_VR$KgS}s_C-Q^DiUDFlkeP+Vv-+y zl*jrtVtdBLdm#%J8XqX`r!c9afIPU6x5er9*H^WT66)S1J$0X}A2Kp(jwTB|Sl;dq zc`A?a)o2Uc!9ZdY9sklaixiiV&DkIL#4hA&mhuMu@+{igU^`l}zK=*LaPr3G1YsS#s z=1TVS%#oH#J7=B63tc*4_GhUTFP~9;JSK?@Q8Iu|C*;Uc^eXzTwGN0QBO5}?S;Xw& zv&-Nmq&W}$cW$W~+MsGpqhtN0b2!eD!E~o8>N5CBVOIK)7YFN7(@Q;booHDV%#+Hu z2ZukiOw6p80y_0Z9#1qs+|24T3eiA$+-G3^lem%RHGYr%NmJIzvjRsIyv^pY_Hs?< z<43@&Dy(PrzOVgY$~<0$$YNAGx_7E#$yivJm4xtnhvv}__BAqg&G`{Pfgb0O;3*)} zdsDddnsMCS{>4-QcKQNTs!-)Z)XLSO$)-0np9)h**XOETZmokSx&*{0U{i5_;d?TK zX524)+HI+(Y~+V3Lt&ivZl1QV<@+}KS&^l4Ou0U`z~zw2gcTG~$$#$^Fts1cXFT1^*_`j>x%C z5r4L$`kBXg<$e4N-p#pp>U2HmvAiB$MV&p0-qPVL00Z8(%Up+$Z@Hhx(A3bDHWKI%$wiNvSuldZ$!akUYW38}z+2Ivf$ z^QrzPMmqC76U}NrJ8XVhleDk+4Wap=RPg7Hy6<=)Q#F5sTV`?r&)5EP{*a|Ul+AbuxEI4yYSqST;MXF_1>LxxL#YG}$TOlmZ zG#SGLwc=xzdeHfuMIIZ;!|nrr#()EcLk@g>*D3{;4dX426w~>@o!@R8*cgL+mY<8u zGWFb8i;H(kV~E!(C|w|_iOoomKHS58S~>W-VVgv;+AokQ9zW{UecK(r^FQin73MEX z32)kpv1a|3-LaJ^18FK)ZZL?rvX3^CN}zMijU_G6ZutS$w5upWp1k6mLPF?hJQ9K5ETQrW zc|&-_hQAm0jK*Bihj(9&KT}1E{g&n#N3N+ys+DTQcnTuKf~K~0qO{Wh1H3Kz4WwS9@S^&8AZslF0LYKYg1-JR z*X4<-5}~3+HB*c?#59ZYpZ>_1+Iatk9g_A1p`Mx1g`Xv+%}#nj0@eYlKqpN-F`b?= zZZO6L9ahA~fT?W{y5{%0zt#h;3BMMr)l_d;7I`i;+g!LKD@Xz+0_(!+%+k2jOKe;egHMso{)Xx_hWeCRW&8~K*fGB{o22^5QT`VEoR`Z z{Xb0cM$m$9pxQKwU5F=uJV*vpB3cwBk2>gzm!IE0L%_XUE;Y^Pe2535tgLJTg-RWT z3YWb{_#zITN-~qo+Qa7|l}rk$)#4y6O?C8_m@H+}!x$03e4P!CbJ#r*Vv9{coQBc! zMdS;zqsNl!H&9y)2JF<-0PcQgb-M_Rrm=f~2$1Oj0bUMxx~$nLLnUW3rty&`ErZ5Y zVvfV*h+)ZK)xm97H2{J9QM$Fg z{beze*ziug9NHjTnSn;Op*e?dzXKhJ^-HW1Q46t%?|-#? z1INE6uP#Ov2*SphJ32-ni9k!c08^VXE7cIs`glwURGnUryaqQOX!|c6 zvAMa8LCzPI$Sj;Cy9?j2;qB~%vcT7zWFCf=?@Jn5K8M+1_Bx+h_j7Uz!_xhL#uw8+ zJobGelGn*fHZ+R?o%)>&i&_fqzFjpKx3amr<)y}Mce{tSeI#x^tO$h96(bE44@Kdg8|30=-KM8S zp6A;{2FxoUN4wIYHcCb;Do8A*aSX*}SIrzoM#dh1haxaY-xd!q|5l#@?2nPLmKcQV zeCL~Bu>6$iC3dxEUlefJOo!e0JZJ=sN}y!xV~JD9(|(%@G3DgryHytNQw$pQ1-hw& zz8YhT-_hd8x!pA#PGpw1!o7GYv20?(V{5u{Wmi~*k8e#v9NKmv1Z4Hn%>q*0!9Z2M zz%UCa0@ z12s2U@kd0o{BB2vs5ORO#`h>?>PnyYSb4phzcvo#*4CV5`Vb9xiK$&=^adS0zh*hdkPmPUQsQx=^ODzuD33Y;IT;*j-RRmfd1&k`%r^a zbKVuDoi93%yjHXe8aS(GV)Q$I-TLVd?yioa83%y&r8s+=YW6q0z~J?D-I*BnJhj)! zS2M_UNmULqsy4pqIzXE!_WYbpsL+|qm-LcQdgm3^_OnP!!QIPUqA?Zz`!S^8o%Xx8 zKq>Z>uxrYv6w2~7vB1iI&5T}K4Ty(~r$ORw7ZW2}DIC)PYG7T@?2xT-Is3eT zgM)*Sy5a6Vxr+-%pwe(zuaueoA|%Esyz4vbuzC_w$&S0KGHOhpWv89;(n5n_TzB2}6^&p6jo4D!vYES595!iuV+H5*z-PGV~uiORC$#7=A{*AG7<@By9e5sey^r) z`!)RK(1UE;rX{ajZ*%piX#0iKR z#BN3>p@=fd?KiBmZm?A3N8;=bOc2P$#)y$#FdzUuaidiZkee_Eo|kuKZymhq-#CLlPo7tob@R0-eKW;7;qpvS}>9 z$EX6~4GtWg40#PUU8uKfX=-W`B#-5>e7L{uZF)u%7IBodTxSRHc^MAIa{g~KWJlQM za3#B;m;06wm!@vQjno%Za%cpsKEnoQMajCH!GF3Jq1)5I!dUqh%8-GgMHT#C9+qQF zU9x+{p(LZ5aD_HbmV6f@3W%_QUNiMCz?~j|(~Yv6QkS2vE|gVNY{8_GJif(1p-Ms6 z|Mh0@@WqQ47b`+Q}Wif}LqOHz-oU+FQJyEU>E#i|sKY;%JD)_ZuWcqlZ{pqsQ zjyHqV?NVI~fW(E5+B~+il%v*l@1mt~>s@xot(}`PQxcZK0PjAlclnG1q}6Sg01)G! zJ`?>dV~loH*$ISFieVC1*lx9&1HLaFQX4D9Tu z+(Dyggl25weg62Y1~(gn=Zm0lenz-)kVuY}m zIzA3Sq*ICNk^O6_x2<<(AQqNs!^V)&3P2slZ$UEe-i_O!P-%xto_#BFWnlq`zb6h{ z#BPOx-6?r+xp*1-!ux1g(u-Un_7>ol*(J=sAjXI483JMxZ=lk~kd+m4fZwzs=_{kf#*3#P*C>y)mlUxlkih1e>f6Dsb zGzd@DDE(#734jBBs+Kfb4kKw2;Ct#%a0QH3w~&QD$K=|Br~}JfBHSpz#lca;r%k-V zlnl;8w5#!ZXsrG9=N`f9to%}#u=RVh&?)Xd*GEqU;DrjykCFJO!^S9ueFN8Z`3{8H zGnwgl%_LM8I6XfiY`prG^dy8!^&5`xLrjc#+`Ug}=H>=a6tsw~LkEukRnW*Ym`BuK zdaA}Dn?03L!ni+z8{5WMVXK){S}sbgU7cAa3));i<}HBbF^l*00+*up3XeOzNFW$% zJ#~-cdxIf@57=3YliMp@_|t5J=d?~4=p+EG{c*9h<>Uzb0t{~MbGK_gqc7q;yng0r zxFGMnA2itb+9@z8ehD||D<&;YzxM@%&TL*qUOpuN3tAyb-RLG;#(sHWu54-H^$I&5 z^F}K*`LQgEDo46}Z#qz4$pq0n`oFy{^55%Syj1QxO_$rX32AAh@+fj~va}}KlMT5T z0386CQ#KSXaoxe4j+W8U#^-p;(o@|skPIF#C1tbm2xr$#s}ZtF=bB%yeu)J#7_Vi~ z?@lVeNwly?zRa?>R_T#~_JtyQ+mBn<9W(1z=T3iz0*-q*=qnRWc-KMlV07lb*q z>hoL;w$g?+Tgi;N!Ht*M8Ha$Gc67`F6)y^yD1sh|`r;1sb!!z7Y0<3fa372wo@hj%ew`9NLcd;f0O-skU zHNN}JRWLI(Gi_u_A+iiCCI9S!;xRj5O9pSD+sy@V1$CcbjVR#W-HP!0Kim&&SL)PQ zM2C&+4AA0)_oYFh{6$1_XxQ|eu=)XujEd<7t+cZ5ntJODlXZrFZI&od0gYKlPN>qGgWG$&G811TF?30*A$rl#{t=0c@p9PFHC zN$>~@^R(l@=>pMoPEbqtyp2+f{9zGLRnJi{zusOsYN)4woNH}`?Tq`#`;5xzYvtf} zi=oXx6A}t?^xqm=bn4fE6sd~`wvsaEcTQN3=sj;SW#U--ro`5c_fDY24aN@@c_`n$ zeZ!N_8(*57s1>O9W@Z{N4jmO#9K{R3QhGd-L`iN%1BcMfTO?>{vS{<{a5L_ad?(J! z^9_d9EBrP7XHUl8Iv{xtykbGG+pKUQlb4_0V|9DBl`c%`7OVnz^#De9?%N>Ob=-84 z-__-a*enAldHhkSbw3z3$`c;-J5gQ(Z+&r=GubYHm9Rkdyo^f_To7T(2ZZxD~R1bPEW3XlD1^JwNhqTI0Tc{glV#Q@}Ch z=H_O9zCBc9?S&02l5i-)2KUJW0fF`D5Q3(pxUftGMvTo$w$ zspo?b#brZ@Uc)9dt(1DMa3q7Par00*K zO7Z*grIZ^;#T-h=R3p~ls|S1>&N?}JB!Vbw1j%5vA6cpnbf4oaB$c+=P_o^3DZ(Yi z9~ZWsRC*-uAIt?Z6mAkKc#7&#p#M~4czAdW;f8#;(?003Y%eSKsSW~D&(RXDaVAZ*B zQH%SQO40{$iKPk1r;IXX?<5cUs(ii6gZD`6d*5KRP(ZPs87W$WO(G6HU)$$|*9+0k zvp@tvp6mZ{%NyW?73JrLwENsTO@DKnA1-=7CK&bTs4P`L|FTC!s6f0-eY$UIi0|du zbKZi^Z(~)krYB3H`RgT3aJ6{V^d+#2QX0$*ztIr_E@_gBiz^1WJKCu>JF?POZv*<} zo%c!9kDZhhZf{ez8O{D&O}`Zk3WCo@+c9xvGtYnsgaVXg0bHE&>gU%ZJOS0>}fJHJnl0iGB*RKIz zG}XiU6xK*dWU8wZaRRiG)n_L8llB48*Hy?&@FnNJ!a%1l9DBmT<`1W7fhAnHjcGg> z>b4a`M9?J9MWRsKG=Ga;zDj7Cj&MGCZ~k&JtwD@O5evIaWQkeqH|}?vHx+9X(Jq;V zuS|8_I)UUNVrcgwuCx>>h;kTXqd5-qUwtN^?VA^_w*UCRf7)qAC7pe9451w&R?yf4 z;h&meNFCY@70{j7?{Q@ebaa~UqbQVQWqCh*NU-UCH}3q5D7!rOP$)G)*!yg+obzH` zockl|1fJT{vaw1U0i6QHDljvIUb#y%&d&nnoJqs}r@N$vhOQFLj?`DaP(~ z%Gp(W$q3VX`VMw7zpPt>BzG#hTfDebRDtBjJ;mlaJVHF`6b*pY0!mx{Z#X6-!alta z>$7e~e$X2Isz#%&>w2fJ-YDuh@d7~k>2vMY{~&;rJ|Sn;!luf;g_Lsapv0|1Spz%e zRF_Prs8er%B%O>ZoxzqqPMs)kbgkaoN+@8=Yu&R0N$3a&Qx6Mj?F>?`=jKp@S<1q* z9}jUczXD4q9q#jbVRli~SY@l+nkMZz74Br!$mg0J)s;bG(|6WN(E*EP*q*f$Nh zWp>Qxz=29Y0OL0Oz)x=MwZxOWbmTI_KZ+|QWo ztSs7P{p_Z6TL1USz!Z9WPgbx!4oFT;E|W5d7{H6Dfx>RDKGAaA5d`$5=TFz*02QF%JbN6iWrB$*7^G%_fr0YiM>kQs8mAzOK7D->hmFkWgEHw>K zt>iLOkilx+vfe^^S~QW$=L|lotQuVO33&oj5?@wDp74mSuC8Rljb0$G^sleVYPpe9 z(RO<9r+ue=>aKA#eGxT_{uCk5|6lVy=XoVX#fxsjovF#mpRC4h1~w7VlTnIXowL@r zn_esR24(UShHPwecspgPi7Gk_Qv_`9j|{`$-#l+;;8%0JA>AO}H-YsvMg?|{Vv)E_SzVgP-% zD&%Z4UL~d0f{BZ%85?`u`tbCIsssvtH_!>2m|tzK6ax0}3+bPXI9sj6v!Gc*gL3kF zGtJnL0VxpjfF@Lbz~LJwo6>M`MA}Q(_^QRJCFGk`)Xa|I?KEdG`&O=2X-M94k%(bw z?GffHNnUi-&@{oR70`PF)w-Q8I(BizAeet~SWn>xl2hh?uMz%**z z0T{l5Ev_t2ixcn0t}rwR?(E+~E&wuo(s-dVpno4j8vO}L*$oEKfyKLasG?(}EQFc# zX&He$vj9h2I9`_anWC6=d7JWAZ{YMsVTE?3&-r97sj%t?yZFWPF?B9Y` zsXs(@%uq+#4C>j!Q580TwhcRj*M|hAHiTly7#vPDLi^HcRrX6wr-U0rb#--d`K14c ztGA4c>J7U_2c$t5gn^L`sR5*%yUFr*4~16Wdt05mXtT&d@G11-PbIVRN~sVDrlIn$Nxw*Z zsP6o{Z@PH4-;%Vn^pYP-IS>e4$CFO;r?(#^B1;<_zy2juN>7+7oZY?OG{yxJgcj2e zE4V(Jf3U3HJ7@(!7Xw?&$eG0Me%0h=!_y5I9t!e(qdU?2@-m|Jjs5pZMT_f5Z$(|K zvX|Q_!s~o8h=pCOniB-T2YZ|QFuah9*E94VhFgR1G~}d~SyA%P(JnqH2+QSQMUraU zovc%E;32D>*~w%ZRz`(MW+}gqg|X|n+p#B9)eWO+M09+cy@j@cm!pjUMOUE}aFcpu z0kuF-eIr`_>*NKkKq2^0IMp>fwtFF%Ty^(&XRNF$|82&SJ(+cbq~;h9G=#s+N>@Pw zE_eemJKHe?7>6W&%YS){*6`=_p#8R~)x%2v4=@&;=EY=Jh?Bn7Os=helIx6)X7giy zK9oQPEe((r(4Ld>Wlw9*8+|9eBuzP0#57IvIia-eO-iAJ9h2aOA0qHwY}|^x+hmbq z6+p5Ph!0D~r6#twsVY=&`jVHX&X8}Wk}LHtW*_sDwQ{&HsCX?@lu4L3?@CE@sqqGxj`B4)Q;Y6BKrRFxuh4SHv zVLiU3iprBS(i7p)d*GFSkdksU8UyoPAta;Ug}-Q-MHW_M&4ZaGzVDz-Yh2y!oldOc zvT&Vg3pdY=?!k=ij7m)0lMBr~z*-&YuEBwn6Z!}J9gN>Y#VNZtqT*)awTlzjmn^Lv z_VD?!TWrWVOygjq^fXB!*xiy76#aUYZvqB956vYCh5(d_f8iC*W}CTn>)Uge)I_Jt>c# zV$?6`gU=3Kh6=)jGSbr7a@S7%e%`uTmHNVW5viHke(hdguKtO5D?EbroR0b)oJ$^e z`tTX4to!kS@ITfEG&*2e6<$3z{d}LKh+^fguk#R z+=)Y1%QIF#8hY50?b*YB7;uFaAsf3q`Rk7*4X)h??ZkN{PACZp7}|DaEzINf%}TKl zGEULnC|;&CC7kVyLa}@Okn9)UY&wk>oGjL6g?_E9AgqqZ?dDF=;r;ldQ~J#Ad!c;; z4jO65*@+p`pYL&+s^>ZqZVAeHDuUnx(ybHPuh~}dilO_V(^k2!!z2T+5@76TOdeS| zp;SwZi85@v;k|8-kKNtc#J^`4N^qEyuFVu|4D9eB7xL2NC8#&|Vu!4+w;kxSn>Cat zOH#($0T$hkrC&B6dL94@U9Tk6_#qIUGCW>4*9XY6VGhlayto6)QmZ?}-Fd6H{=S%w z6c9~L?!Ps85qHRv!Je=b78y23b(=gpqZgwfg<6_7iQaebtw$er*j{9PT~mTyLHs-& znbedkO%Gp^?*|9)w=94?zq6D4onj0Y@N)cg^rfrZ+H={S3%+COV8uy zqPAX_IZjzQu^(H=_B;$D3)Ok(Fp0-1EOFjku-Pf&T1J;lP9*LM&vHIZIz#`jJZMxa z(>{$FNM4Ckq>%74xCE1qo%7rKor#R+iVGxQ>W=ybp8VgzJQlZyi}&$bOBh~u3u&6; zXED#mJ(|Jg3DT9zLCT=!yQmXJ2*h{XaNa-AIgtGQl`Qu06-kNgP659l?8^eD1!DXd zTHd4onZf(nGT2zrue&9hAjz9&`#Og6Z89t$UV)5fQ3;DlZTB4i)(LGEmHV#ze(M}cJ=)i9lNi@~9+-F>c7=Xjh0jey zTgsUJW*aj4CZN4VGoeo3-25T`B8Gm$kN-hiT;yz9rcXm4lHx4qm7k#?Z@i=zQSnS= zbKLsU`dJr=FNHu<2X6_5i)OA|VI=@tpL@fWK{P^|bYPPgD#=oqxH)_*&(t;l=aZ{VSzAn4`G% zUtIRmFOR!hah>A$S?%&4vlDNjxGu%5Rihe%IQ?$i9?uHuN|PyoL}vH*-ngvh=!YV= z?&|m4lKn_xfdck8I5_xIiP9)pMkrY)wVFrmR5A${fk5P-AI z|5x>6M?2~m!^sgs&EQ3OzNwZWDG||8H(aAyxCH7qez)-a398 z)I3~NXpeg)uBXQ^o>_!35xI|FN7*LC?r0xiE~Dvflq0>&WoDnGr&0pUleZSXfpNr4 z;OnFk977I)SozgdWm_gF5Odtl+9vaW5}v3}R+&$^mNrFH=TJLl9A77Y{1-4PILS1> z`++aKvh5pM`)pX%U2s{#zeD|$uML*k{Js5)QKAvh_dKq^7bnM$?Xmw_qOTi^!0JPkP{>kPVz6t`yK;27 zSV&MvX9tEN+_g-_O^ZH}XYevJYnGE+7D<;yesQs%9^n3r#iy=3O>YKsML|U@r3T@s ze!@3w&|~Yn%`+0s_Per~&i`zfr^p=z7O@-00gE6)H?&1i9t|v8p3iR{ww&_UGtNlA zJ!IceI{6PFYbfC?on5M#AJ@oWXV_iDv|5b;?JM71^9rCW#tZ_9^*xhs7d#!$0!o?4 z4j)^($NB%GmN5*hRj>!7#aUgH{i^6MU#Db6e{eXF-WCCvL2m8R zh6@4#=xNyKRF4w(>8j-LMVYd$z)8$iPyZnAs#eO?y$4h8fp}k28DV!TrBU7r6)c@# z8Vk~ZgN?e8v#gl)YlHwpLgW4?8hO+$3OO*P(@bpipaFEIB}lKK8sDBeYinyU^r6(a zMxXThe%T<1LpK`AU9H8TIVBNhRdXTXp2 z2bIy^Khf@@?R{$X5Td&L_!H4w8B8~0s;V%T%j57SNWi$#W~ccrBAW1PC195N%5HM5BdX9U!-#BuDJO9MFETN@oLVi6@LNVc$aj65cZ-E zp{DWmjHFs4)rZH2!`%npL!XXi$6c<@zt2o4Tem4DXv}6S%PaiQS^E{OsIA7rG1y~P z*-(QOf)?97nA;6B#y!mac5g)bDFQGJ!_Tq%D*%PbOkr9q8yd+6l(WF@_uqYF#1Ng$ zt)pAyYJ+2gOVssUnlv?u4-HQ!)>&E!nv!jQEMMK$6xLg>W@f^rypONf!Er=FxKi7d zT0Vo?8fK}J?u^)mLjRdL*eKYg6oJ8MiSh-gGt8})?3Bz8K?Aww&9VlBfE0`WcfCzY zWqG+R8Tq@?$H$C;osLBXgqD} zxO~ab)c<8@Rh9Pw*GEAi4l#)}AEddNwraLM^5Ye3*8L%~nl!IhaXfV~ z+?SV2QuCeBs?Fnm;{m-B=~_}|B8mbYyygENT@9aaXQ_YQ=tmy{$adiR!_&a3Tc@Og zjnBjHpDSbe*Xhv#?=B({E9HCtr9YxBpu?CJHN=Fy>aRWdJeZQw5Puk|6=xUH_GMlW zpbSxyL!?e@YD~7D1UcV4VZT~rF>Wc^q%MPSsbhXCp;iq~$f@Fuk1K0%xjvH9@uEP&3^)zwCHZ`~ zoQ{g@a`>&*EFH0C2*Hm35qH$*7Se*XzxWEmfcJ>2j$vF0?gSM+2`~tUzrIj0KBONe zAviv9aaMHw#p{8F6~lD*)1)rX&AIHe#l{=St-1QSD+EXe3IC6dKfmItQe=u{s;x8$ zkKdB;HqIKd#~Oax@kfgh-~Y>kN;xFmyF$5++>l(h%^svAKK-W02r2j`XcsHN7^iUZ zh>3@fo1B4~YJt=BtScsmGhc!V6XWW2zP!PK4xJZonk;9qK@vvz8P1C1ZLI&2nW(s! z;+p^(>ZXe)7bF-8QK}_-oi$?-9nJEo$PCQcKvZjEQof@S3oDT%;!NrOH^&E4W}nQ> z)8A*`jV6LZb5zFa<_jcp875#OnDTUSo2l|XOHaM}Qz_QY@SWk)7KTSn5Pm3ZoIU(_ zIiq8V<6H zq;|qpqrpTqmSViXs%megdZqf$kggtrU|kohz`u#F6#{<>4!9#Dq=b*X)@8{Vn2&5a zYG>_**$&)19UzdJ`G@49uUNhPm@8S`Oz#jVVwHrB=6_bz4TKrLV(8%A$~2=!t`B1}i_Sl3h|J&HWTLirsiM z<7@1dF8poqZOBQKTKsApL3}j9I$;nTGpIYLd9K+}xKHKdUzQw7U_TvJtmrSmiX0AO zlKu?R>M;pcw|##|xAxg@SIjbo0_5+j0UNq9Mhi~#xeh8xjCW5%msS=wd%mIlnqSnl zd!ZHMj1wI;_M>EV@N}clQW#Q|j{KR%)%Vn5RV8GdqRRVvheChd3Lmi1gI>TSBSFNr zybC4pOF6j^vSVU-Gk!JSy;xDd1ahFP42n!`sJcFwSu4y+290nz`GgRg^HZ5J?I6F# z%)(sdxV*x}P2SMPgizn$jj%+RIThK%X;Q#nU&}lK=B9f%yJH&UI+bj8>FXI0YN$^NlhM%xBN@*XK9resMIpdKV^yd zS!BzfsbTXb6GEiz^s4Tqef2q5{1!)}d!{$n5a3au(U6F79z5u)Md~eLT*EHEZwO(C zbTj+o@koj#*>&~9Bb@I>M~hpZYVS^i84-`Yz5Oom5$Sna02$~Jin7xpbqOYQNskG) z`{+~d^qwj+#&qtKIZ2H(##Jq)yfCYaSbi>OQO5Q_Jk+PCwe@iPZp!4@x=_Drx1`e$ zRAe}&KUGj;i_pUn7Gi@3a{qKIrHUz)pMqC&ISS{b7cXK^k7l?-5~cf|%0H=5h%}?R z|B6G>O70!f?Tt#^S7?N4mE$_9t1BI}e%AU(JD-9j##*_p?-!}=buSx)C+*lUVA2-U z7_ia!%Ix4%rr$$3TiF-w*0Je7hmR*1%F$#)UL;2cTRJnw)_duzT*GolHh5xLtLDd- z>6EAl$-E2+g!TtZ_#_^qLIPX!HbevBDe@*`V=2lukP10Z0MA^ zN-}pY3jnuGl`o7I62oHqi=oWL9Y>Pomm0`S5V3iBpGGub!n3!*v?8cgBM~AkYjF6H zidGyWV@uhXT=RYBbeqf8L2mkd zaesDha1&Q`>xl8-kQ*IRjdbvLTnd{vkXB4xo$4cw)Ltj7o*>`cW>c z+s376gh&ZEm?j$JO~|eRHQ#Gk2p><{``6@7`~wc}!eVpPOv`=wrj(^EXON7nBIESw zCB`V=P=iV(GBF98r>IFvzZD1v>Q;0R8l{dq{D$nrFtW`HVR9_1HOcsKXUhL=4MAhL zqZgM+MJebLLAror7;h6uRih2aYVooJ;=)qF6QV7Oh0*$kw8~Os*}*@7A4m4) zj8AWrc~oa_Z?7dcZWQo13)wAl#YExZDtWDAmCjdLh6S{t6_#~NC$!3q*Q?Ppy#0gd z=vAe(0qW|A8fm-yW9hkYsXfp@v=kK}&ete=<&y`Zq2`B*1R_wlC!uy(o4S;(F-u%k zf-fg)SG0xNd`6%CY{@?_1P1$HX zPbV82Wv`8)L@QUyGaGTr>t^YLWP@|NMM^=1mr=8*_BY@ZBka@yHN5~dQQcSizcpr* z#=}GcQ!Pg}fIkR4FOOXe>%-Z7aoq-J<2>%kL3k31hCa8iIBs(5l)TtOG!Xc4kDraE z0Ulgk7Emk}Sq4SVATHr!_`z-2FN%B0TzCUD@{})`ZTAsytKT7zW})+=*`U$~3-YU; z6)-5XHlM_nLlsZ8D|@TR?oxiN=f)dM%p{#9!Ci_M4zlCIcMAPv@1?Jy#~eP4ZFa1J z$A!HEC;j(uGQYnf^dT^{wu!&qr0%>%v~uE1m&5$Bi%TAtHDx|0L$zGd)TD(?mY7$1 zL^mFUDYM)#VD(xt!guKm1Cb9AP|Bx~iWHXTl@QvcnQ+IxXv^*dW*0~Fqpe7BRIF)Ypg$STPJia)J@`8R$_$;b!`_L9o6xnjV_3*I!HGiM*a<55D z|2cRTbttAuU)&D9)YaBwYfrC~QYA;u0N4zrWgTx`%<+6`>n+OAdF{Tr z&2rJJ__27!KG`GJNcePk2;aoKL3prLoo32$jh>?;sqi&vX^z11%0{CFDgHAL$^wPfYr)<_R84^KJb zH>(~bj7BO}?!F0)l$`@P-|qPR=Cyhnp+MP!mQ;hJYj%P$R}b8wQ5HTllvPAfB9%Fp zrq3%Tpd|U9cLXeJdS_M#!uN4g_si5u)ToElQ`G++rL~3^@z`G2vbm>K2J6&sZI7FP zejGKFmN@aK&a1Xp_`%neTsSxA0MB&v<>tjM>~W4FKJO2AXHVuYX+B5Jan$M8@!V#G zee9bz`j(^z#Z%q%iZ_^7B23@;2*;;5d2kXbRWN_Rge`ui88BG~-C#k<`V6Z4n5Sq% zz+>@79oroQZboB{KGMsIyxHA1!mg_8vpy=cWNX;ugdPy=CeWB|9-@0i(3{Hgn`Lox zBXyoXut7KM%T!xBb$xzHMh#HT-GL-rc|a7`9ZEmvMk(+#$NZ|!pDOH1?3gw75(-GD z1G};t63ruCf%!Zr4D_a-)67r2cIb{8Hn;j<%UFa0~T5nPi*vjTXHh%k4e)WCr0n5}7I4oAAS zUx3CpVb=+*n6a!oco*Vds+oHJl+k8+AR$Dn2rr0ViW+Yo0fdi!zlB&+35At{z)txV z!?~G*y9?+ciucvNO$Yop8MTHZlwc0$n*Uq?^x^^w9iJMBU?JK-j!RUY2L^ojx0~k= zE{$4LDM9*gG`^DwV)Q(url;$Y#c$TA*-`EYy^k3tshb{v2vu73g%?FNI^y!Al`Ce+ z1AF>p9B(;tkX7wQgg`jIxmVlwQ~I)_s?QG*LN*TrK!p<(>tx@&M$BYqFJ`%`IBn4& zSFpK`WgzhDd(#1l&hVL)99{X8?-{k9tA@TMLboCcEPnRSwgfxBd^TiwcsK+9y|%e? z;3!tvkf(fab}pn{2b-pjE(#vyG<%D!z>6ZPp~HP@k0(shcG|M;>`O1R$5{P6oWB;i zbfkmyk$-BMe8?OvTMn0n0WQ1ZvP&X=ICICB{@ShMe@qQ}Xpk@T$BR!u%4HUO3H?<* zKcmrMB%&xkYOs;P`wYMH;6eX#?P6ywAKg}4-Kuf%+;76he)z?#EOg{YNA?RNmSSAp z-B)YGj;G))3NLdwPwzQB3!#i{a~-#ezq4UA70tPyv%yqBIh4T2tjxMaToZ#^NX-4- z2U2Cr;iIFNvHK+*%cP7q=lNLh+*ogC_qTfEeV)8QusXhw5^!0cSYLeWP>)(02~wh3 zrU+2bPQ;b%Z^^|lf0Tp1WdI?d{#uoLL4{SYlH>gSyU?$sq0TCNGvyw*LLqKOx8Xx2 zzc(JSD%{(i1ffRk0}c~Ikby&$Wm{wfx#6vfiaUkx2~eOuiY}AI>y0snJnnZxJ8Hhn z)iT}9X1c${2n0YMOp+Kdt!L|%f8K+8H*PaR}% z6_VW;xxrOXJuSt~ja9z-m9q%teLTNq!3nLW z#aHXTObq?waM zG@xa|(J&JzD79Y-O2F^B=?cjf6I|0z0#L$PhUPYX?xHUzR7;$vUvxMvn-s{3jCdnd zQT$iXBBaBsgY-H<@si3rr0_E;6f)FT3vp?~N50dbL&Z!sLTLYIP$LTTE0$5U=kt`# zbjcy>dUiihF@F=uN{UTL_&O>6e%#{fLba0+`;QE0Qb>q4x;0}fvM2Vz?faZMB3}1s zNNSq?0UsTQnV~Q!0-6aWuT{f6bD=l;eB{B-o{Ig)2{1dr3!^>(r`KnF@q+B&lwI9| z?wPq`lREX(MZwR%l)lat34uDu*feiGZBMWJrJr%F~g^6}f!) z_sy@~ON6GI9pR_u+5#}b59?+4l6vW5+vW25yW7Ex>y5BWH zwIq#BEp-M zL^232J2C3E-cTsux+WK-;~%bAxW+Ms93hZWy@FOuD9bAc6+>#qdU| zuk-Wr>O7RceMr)UETkuLl7`)+=@LpWko`}=Mh(w;u`h}Cf2|KWnXB@wz@UFlbus;S zYQmp;KX#s!u&+O0OPgfx1|0rbPyOq3%O+PqY{vcL_QW3UkfU1S6;ZsdiI~8swQa}x z6XnyVE~sD@aI21Gl9nqfFSqKAg`#r;yXRlD;Xv(oMx3q2HIH}H#&3S9!hXZO1ly@s zpC8&SkGP_FiQffv`_(n$dTdVaIpGD0U`u6ymvRVfmPsMN7aD;Uh8>7*ncB2-g(M{U z84^s^5WZcC24T1v?#~pd;x}cRn#hx}&C8>JUYXd>t|03E)FJm+GW$8;+SQZ;Tx;C_ z^cigANn?lQmxTR;BzS&7ezVPBkB5JJdfnBBDi#(Nn^>=2%(fIB$hklaESt6TY1bFG z|Jx~ex0?g5S^V^?H|8k8*m<1>zd0x0M3HPddL9HF(N)@|7oGi!SwcJb;nThZ(#vI% z{TH+^m~m8VJ~nwgy5#%@s~U9?=v4B1yQQx=-`Q_sdfZLbEBij>gC@>{f#^oY&(B}d z5iz#1F?De1ViZ2~wP1oP(&N|4nf&uFy6B%)WE#!zc{S!KRA`X;y_rN!z)Jz-^US~9nPmwscDH{eJS2H1)Z@MsXs zq3x-(mrTi@jsV%N=cq5s|3%NmvRH&c)GOijF{@(M&=8(tBRp%!f9Wv3nCH6CN8U4A zVGG!juvVW_rE77_T-~09z1?4JXeVjCL?~)^1R+DJ%mxpJ7=qwOQ2?OhZT*mWRqbL6 z07<=VH1d3-Tn8neQG0E2Syq`-*xUdf_g=AmY57q_b~7b%Gz=@)meOI98Gu!;YU}76 z)!6?PX&%t?`@ZGoeYH0#8^#^!AqyWn6Mzgm?HSi8Ywzl6zY6%8U5HZebxlmGEZr#6 zvp9YEN$daj-L-T03y>;zQyby|7ZtS@Y?)7avd&uj!G;)oX@Bnfet-?A5?r>kyHW>1C^cU}zP*Afpn$Qb-;?Ek z6#7*2Es2fHlqF@6|7&_tqs0v9RJHo_($`SF3d3FvGcdjdJ#)(Zn6dP@f)^gbWEeiC zS#~AvLG+)QOgRl#l@`D#wUno#x*}=Y!0wdZgp^T8`_3)o77G(P}p*nwQEXswFEsr%2e%e0Bh} z|4!3c$XYu^pM?zp7V2V+O262~|AqxaHkG*vfJoz-_0}HOD(jalPvYq2)1@14{xwq` z2$D{!dv`N2QEp&5!Jy4^l+3_a}0@~uKG%du_W2#_;x{P|E$eWD)C z!@R(EVb_puT~VUqd@W-*p?R<2S5-AmZ+WwD_ji7RR+1qMqJCjk1?|))2N{%7&|@P| zly-hF3UK$#-a}F5V|Ak?;!;57m8*~)ZL$Uv(U$o8)9fEMjT{D{#iZ!r_89~9Pa%J# zxmK}|kD~ri4Aqco$t8Z7D!mI{%F{bapd^+9xdMYk2@*NCdL0Br#Gj(jz=hya)lE_Y zv?+fif5o!;k42xY=0$W=r~rItrkR=GB`Tz^yoPLAv@Mz|zmrSXjXz&Wb_KwS@U%<$ zp}B@9wl9iH8%RM0%y5BL=^m6N`G1mpy5>l8XvTl)MYrswn1jVW+%%`qM|w5z%yDv! zZsHJ_!d9CY|9v@{c3a7#TWDpeuFF>>{yaRs`^?SVWbe#e zXj(gsAC7#*D3Eza^<^<^RSmbhX~MzbUJ% z#(6i$?jZu3X-N6AOli{A{BDQ2kv{mF2KdYuJE+cJ$KGAM}pbgDQ81cKG3N4xYBpFKhJ4uUi zABDo*&spdv&VZ+kHnn6K9%xNqk-F@NiVIhv_T$`t4Tv)%MWLpLl+8kP>jK@p8RNHB zP3~R9bRT~c25S`$&$^|wN2J9)iM8ujG0(b5K5CV~X0{};0s}BV*w|kHOqxnjPsqt{f;ml{A_l*I_pjQgd^gcBF)?V5S8@L-vHDdG zRU%yHK1zxqQmC($u18r!yqC0HG^~va#I_tUjxDQqXip+_|hy#Zq;TN&?V$G~VZ22Wekk zlxSE!e`C|~XI=BKFh5KRJ5bLPIrIzN9#-0KqZg3kCxm@{?`;KEq!rIwlIf%fYF_v2 zEXnY?94r#`@Ndp2A|rF!E!lciAn?>NUIQ_1QI&DdYba{^_?F$!TJ+)O`)hS@bY5FT z86(~4*y^eC`nNEq5=Hl-z}VocAUU6l#n3eR+s40Yx_vhR0h*lcmwxVp7lf8#*eN0W z9fO6DyVx7aL_ZBBGl7@N`DfM=ikX)a{c3{14vf7j$en`GsQh)gT3+?vpao1eJuM7G z$D@JNmr5u>LMU`B{V@+eD4xI~zR(TXv2X~E<07`z>Dc4TIEH}IeSb;WvBI7m0SYY<)DVq5UE^Vv(6SP3y zU_-|Tj{T*!G;V>wK>E)+GBF~tiduuQk3A)VB>I*%iv3Y3>T0d$^C2T2I~+e?#CFur27ua)N@gNPSzA3cTe?_zu!rGW_SOUdW&@Ohk2x3?&1})_7{za zqP&lb>Y9hV+gFPwR4w&^9BK(3u?1AC0#D|>?3_taw%UZcYMQyp`EIRy4RQ&EG1Rg} z7=*0V>8bc{y_VakHY;zcPSgepU%@jDsp%?h4B`S+2u@75fvXcU!}3oogg3w5lVZrY zZ2C|A@}M9vs~2R{Y5p)|SoP5Dkg5~kNIbRW=|!TM;+9Aoik@39b94!Z2z~>X)u8s9 zVk-l@0P`RrGdq$eR@fBd-P ze6_K!GAS>LWho;_=`~OB(oT-A0KA)kN!c@lLT%Dpre{!CVnv6^;SpBC!&O&_=nElS zohJ3agm7#{W3%bO@-wk;dq`}!EL95|OA3xT}*-mQkZgV zXyP=`@Q#hY8}AUUcd|}rGv3uIr~SJ`kFvI_C{e&E9DH=px%lqiLTMhQ^lHuN1Q!}}X_*~q}Jre#u_7@89+?~s7&#iEHZ!s#LHsba7cfa|JroR@Ih^Y4v z`fwk+665BH{8CW!7Sa$3s^voTa$s1R?dp zn1}xK7AsT0p;wPd?QPIIeH7W3M)CXRDcbW~{rq%TpBt5zlcrMaHGa{cqRF6+{e7C| z-S1KT!@N!rGXFkMRt~>V)|CY|w0;q-aM7?T38CgEd8W{~CP3{EL7VTXjI1gu6mEmW zlLuj8IRLRgwG~#%lT`Y3WO5ehKgfvP((y}5N+7@-_94qwMGnuxFD9>*NR%4=)sTsn z`#C(B+RqtkAm2djwsJiVE5#F!r*|X_6Xz4Lj`>6bk7|a~kNv5-6?!2o-bA4EO@O=X zcnc*CQFB* z+oy991t3KPO2A%lF}yHu20VCNC^A{6E&`dDellXvgWBpRfi}qlb!iQ)!==gosrb+w zkUi&sgQWE-xkc=vRsACZRH|6XT>()_HgFgKl~>6caQP-GjG?Ah?(WTpCGWmO&Eok0 z5Gs-aE~@Jqx(O}7Qg=y@5Gt(s zDyG-$tylMzNdNH0!cGz?EUQw#Z2Wkpl5gUS}*XMo;02H-C#q*^&sDJC& zH}nMb(oGWHXB5{*NEJ-4$bN%2Y8Bw)dl=HFG5x5z`KunqyrjKQ$h15Q3_=ej=B9j28%t*l1KpM?Po_*fdRi_Ej?O+^mySQJpm zzsP%C?D;PU>X{Qvp7E3mnaUnte*@EH!j@;P--I8a6+0R`N)Zobzc5$E?a`TjfK-#L z%dm>==ztWtRH0^&HW@*P_|4!R3pLu+aa0BD{r6}#G7RSD8-f*&tGk(lOL`EQQqELq zZ9_%P(Tl`E|9Su9eId{)bg*EY*GlC4@IuezHH*f5a)$z24jo`U;}ZJ2lbz z`J7cKP|&<$9A_0i6UFy}6AJA-Awe)eBO!A_@NeE-mV|VPk@=;DRg%peGqt{vI^@6+ z53V*GK1a_sK?PBM?pneKMpN9oyqgzSCt?)rclVi7NdX1R`qsHr-d%A+F70+@@o0xmK@ZZFcm1z=OheEzk>mQ24L zw-~&0%gBvTK0T^sO2Gb=nEQ>jj8H**D{K8`EpKY`Xkg49m-TvZof9}lIV?l}BL}!P zE)-H%{^5v?#(+c-a|K~xOj}Nt61VD|q(OQ!>VrjX9E=tNheZCtccYQJ{Ozx%GJr|d za+tWdVU`Q&SpW89mghmgL2E+r&oJ$0)#|L0Cgq zkhNdHj~GC_BZbWakDdD!!M}3^?cEmr@;kEnj|kv*P*!#aZ$#kx+H`$5`)_z6H;&^y zzN7}CIcm{cS=t&uW*d&7G?mZk%k+JWAD+-V{fAY%$FG0H%-SEs6KLle5C|BKUGuix zEjicUn2}_gy0sL3Iz79xB4yQ`og0i+>*SGxfkteYtY+C9DzI6BmoD$?ab@28fgNQD z4oa3DbN_@r(fprCu0pwDAv?gWUI2oF{{VspfUSprR^ZKc)WSh}Ko-k1r8i8Wf>N*> zWWZOyz_%%Ipa!eDrJq-U`<_;2Srk@dG}y=;y4XGgk_XkTul&o#C1+{^A#4Sar0z#! z@rmQ!xt<#xJNcNc55;!|^AludTJEi(-pfRBO}ks09UV8`wwuukM>}Ek9zA=NA4 zCz{$jQYtI!hXbq3mxfm_PG{!j@T)v<$i+ezu#+0~OZ+|diKZH#N`X-8F6pH9;xyO( zynuSr%24=%CU6(ZaA(+?Bxh%3`376mQBa1tLN>`BSveZ^+YuPj_$=FdBtI{J48h`e zhn=_Kzd;JmnE7xzTtb)@h*q6^HY;crp3Z##BPPq|S#pJ`f{*`nGmF0qHBnb%-ej4V zcCbudc%AEJtGdvLa9(Uo^WjnfP(GxnS`jso|3-nZ10>l8qX!-l z^B(}_*3hz%^;863Pb-wwjTiqumE%Q1V$}qsio=mmKf&oHn6Hdd@hF&6Vskxj7Eaq#8TumF#l#$Ar#W3%M+ z*UjJ)UteKjRwZj`E%t}v=zdSso)TM%opLHu{^WX7rDW{m? zp)OAZ#@3edy-_KXMEr)=^J|!4nowX--p|M5y^AbB{knX)Wb*9U>N+{gIpcGADkuRU zIm>*vQ_pcv5C4>2$q}y-dfvydYkb}^(G`5O>x$l!>qzbJSVVrMX$6}_W2)ME}a$yks)jv~@rGE-YQw06c7qVs6{h4#Q)% zK)Top3+?m4l^!kF$m~13E<<54tbcYVnPA6_A;pYxs8%sdd5u3-Ag)&7_EziT!#tzs z1Q-{`?ruM$A>#PotjYDj^SB(jzEjUgv!~h$jcq_Eb;&G&pxtV#K+Tp?!E_r4gboIh z=rnS9GLB^;@Uj_z6>F4UY_~`h5yv{OXXNDk0k`elc>@z-o>}A@GZn7oNC}KA{_5!H z?O#=1)bnNB@C$}M6(!meL;ustuXYa2xAnja&uiE(Bd&iQ$^&93YVrVGAaSBKQB~u^ zWJ!J>J&%-3U?e{*_(altPWs*Y=&y!^d$d3xk!c8EGucsg%eX8`&$HNTf0z%jp1nTw z8Csj!xp_1h+-IvHDQ^;CHXgOfeGzE8wlf;y8cOt3a?J5d9csLuCdDe#WA-TQ9+7#t zM?cviOxcGV>+>=%~+xSrEPtRU`8H?>x$HlIa z9Cy}sl5-b#oTXFQJ09%>oR;H8ygzB){Dk0`5YOTcI0!L~e3rZ$Drallk2Pfn>AJr~ zKA1Ety4)vCtkt1aR*Uy(EO^%UEHkGgEwXg5wlKSlb2X`Um|Dt(*VB;0*oR! z(zf~Ej{=z%Rraq8ZoK8Y4Pyq^-dB`G0!J|;5%N<@b8~pNz}A8KCS(0K1Y2%T?jYCK zfSy2}HXRWD(8o^lv5Q0O)qOKw2SFkISkV`wD3i>J&nO_G@k|5k%DO&^)N-Y%7fAsZ zAG=pJWngGcJ{=q9H7e*LpWckAB>!?Vt2lv8PnKsw^1)%U8Rs2Bz!E|)2TFK$x~bKd ztxt`k^}LzufL0lqXyCK`V&S;Kf^Ol${da-81(y=T<6Gkm^1Ozqg~!aRe0&l)a=mst zFBg;d4ld@i!-D`07nxGEJDsC~$Su&}b!y4V-6GU}L-RRV(TatDHw>)F!vpqr^ zbDG(RumK=*s$%sZ>>H@tH1QVxN{Xt3Kw;zVF}De&T~o<+?^D`Sik^?{B>O~Lx|yYg zDi~##fa7-kn3(9Uz<(21G*qDvE-V}!LTkM6KKjWNIz>59KZm<{2lklnxDmFUPhj{m z{&({)zpt}6Vw&5k=o`f)TW_l(U!g!BSLK1ai4Gm9Y9p_w&IqIC%x%D6fN%5oI(cEH zJ0{p_Y4XX&Ae~gBiR^J`_>=yp)-yZwwGkS5mgB2M8i|RY04|= z@>5UdnOr$R+j$(pgt)h*^EEw7ch|L`cf> zM@t@+?P+HcgMsyi^?wc4;qO2cNuNg(v7U`SXuyR4@6fiGoavagaXYwG{`Z_?*Vf`W zV{@(C0uM7B(EcSh zCH@|W&zHT|>X~5T|H+_U8qP28;Pi;Epc0e=r^bJ42xquB?nq*sM@`F7<#<26C@*}$ zuu{W+ad=L0HFk5W)q)LU5Dmt>Oy_Yf9$^jP&QX$(2m*+7H8_0-XXncfK$^Du!-0oQ zVyWQ-R=J`tH2}T%5>8f74>T<%|F>yz&^-C%PmanwsQLZUL)6VHN4zx0LT{^W&*XF) zvk>ab@|3#K$acSL0yQf@_sH@iV$dC1;f4YHX3$L-H3x}q9cw~r3E6T6TD>&}_vu#k z&0o%O7|jm+mCuubr_iU?ssjuVcZa;5`|s=O+JUgxiqzGcp%ou%|K>9lFIn|ra1MQ@ zUv6C4(8L)P9Z<7lbU18h{F+?y$j?THeeqGpmsZt&-=wBg{0|H4y`x7erTX^i?1_e( zze4%9qvda6ES0Z%Mdq~hiljH5d*8^_*3=;Yk03Mt|Iqc8VO0iQ+b|#~A)&C54nblA z0*ZokBfaU8?(R-WC8bMZ6Vf2vAxM`r(jnd5@D6(4&-Wb1`+of8xUN0d%&ax*JlDC_ zV4G7dF(-{Ca9-2}rlv0i-StUA7>!mtCh*s4H*akKjyZ8-<>5&YK|N7d_^G77*If)W zspo7`J`|{f_mDl}>unzMeK2e>(2uEv2yH{~mI#>D;4{|x4+a%}t;9){@#r)gHiQDH zt;In6<-PJXQ{QoC(ptWvi0472LQkWo zWes<*>y9!V)u7tmAGxLZQfujbXPzwj1y)MAd+3(RzIQSHmRVe+kW~Z{H+3r~Yf)X% zZg$_345T-)AilMJl)nygc4Q}J)!!|`U2{0A1vQ<`S8|j03UAe4n~x^$$UbtqwD#IL zKFz68ehUIr1#4+J@L>|7V<^t)Tc1MkpZIlBQkibP(Gl(YR3Uvy+S?Ggq13wI)ZLXhs0)FOFQSB)3Re- zlKfX(YDvOet&~RCPH6cub&Jjh%PXjMv;BA)#dKe|$C06wccB94B`2sPEG&%CX{&`L z1^=Vzz&X2vun!e9!RR>W^Q@&v`?Cb|Bg^>@(<4qs@qaNr!6UEklFV~O5a4CGUQ=k@ z=qDmpV`+B3dpFW9?GgdbY6m^y6-4A_x@>1C;=?vc0)YyxcG)4jIdk6QiI+=%PHA;h z^Y9V_M@#-|qKp2m3iy!E|M#Vx&T{{@@G^bBOmo z76o4W1p{7i+PiSB=%TKsFQnGe@Fnb>$9&eP;z=B}-MxIj49D_GQ(nl!zJH_WG+uy= z45|st$W0rc*>@%eXG_M5sx!v*lXQl~n30@L0lvW%!R3}ss=>(G8z^TMUjAbXZNJRi zHosCN-TfX+cIHZ7jdjya9)OMxx!LeKjVbNA_v^e*^c%vKYp82QKp0)Ul)5uW3OiU$ zw!Q>^%Jw8{4Aq>3goNy`A0NFET>nHDJP6S0vRxn>=K1In1Q{h2D{@dL=Qu}^g2D++Zb6erowg7D;0Fl?%mlkv@j3Ii zgMNt~$O5^MxKNi=+G!E3hdxhG;cGzL?lzc8NJOfXZj3?_5R8>sdUS=|>lBAkc9j9s ztu`Q=|0vkLL4RpFsI^UsqjTi1)@O7sUlKI=Q#cpOhw|VN_D8glZ@*`n3*fI|k$BtF zYAgjc@S-vNPPC6rO^Zzudp9d#mHJeEg6e(vy$69+_!^g~v-d@m{0KOfCp(`acxS|% za#gD=)TG43I(dtfi5aS`@SuN`XUcDCA3*=`Du8e`RS31wpOuCIm)Y$!^w)YW(wfRb zP)fbJr=Opt)=C>eTYSigO<68#pV4cn<_r9wraM3ncstVs1drJF9C3$BhzI;ScS$z7 zxMFVhsfxp|xk)okvCf~s?+X&s_CP}dui0cqQJmprdrOFuUScnEQa3|JzOeJ!Ty^`` z%?f5tLu{el`&{oy*?=*Tz`8h^dL-W2^IN$GfvPBS*VmKX9%7egN4$Tzh7dti(j|_U z>QDG{l7yvCBlUgjp^Z_t zFTY4lT6|itF6RUpw(?u0Yjt&ngY_5P`n8Gw6x_Gw6`ntWss-j*vR8XYdcN8#Lxjt93-JE%f(Dqabzes7&PnXS zbrE&521}<_H>Cr{XzSCLs&O52tfayu@WC|?63S!0bWOEWmEz3fQEy60ffqCx%CHF# zv<+RZ8Mwr<(*pZIar(&fMC_g!76JmLjmPiqmN|Bb2h-4qD3w~?qM$0GDl;5nWA0qv zW-1m~ZlNNqWM_XrY;;~sbe==;|I&Z+UI-oH)ICN^r2QQxaJm2t8ptCyP~lwS=q<&B zRQv*Ss>mz@j*ToT80@q5dxW1D&ntI;J?Juk& zwwZ^;oz6_f)fGH#!;P4z9uGlqQBCl!fmdaNPHp-tH zg$at>)w!mShH<6q4P}UEp$BAqUgnr?#{A9l%W}Gk-p<}0O^Vx>^)?NNP}>5nD$tbD zW$AyRK&VYb;XVlheiSUPdcLt<@1Ll&l%dx+bv#azggQklvi!4{u4H{1+w^=-!btG}w{o$ptwP`XaC)NFoB-br#WhPMt% zE>>>am>MG{b}~zo-6;*^&2R;FVgfOS1krR-2^m4;`R!b5TQyd=%%K8(j5#JGVCMWM zYXGL@2~r2gxa^MglTy{Wsi7!>b4WujriDs)0ltBN#;4sXNRkG(SLD{1 z!W=fa+{2w$lfAa1{*-D+noEQ$zG0tyA$(`X$fekDwOcQsrKQyla(mTxGDx$3D=GM1 zEn?-WR+`1;S5+wwFFAwspTr~v;sRH;{KeAOclI);nWh;+wJmsEU0tY#1T^@R!c|?O zpE3vp-x^c+j}{6ZJXXtFe<}Xnf>AgJ3yEWJQ^;PQs!;9p$;{chemZPYyDt^2O+6a3 zYA%IB-o(}#LJKUE^*!cMSDEmQ=I?N1sp)@c*p8^TPTzZ-)`u zu&!6X`_vfjtNY~0@U+`kCO6^BtKF@y3W3u>?WrGwk8M9w^(Jv8x%mcLW>?bg5#V!G zRCK%0IP<6t?JGfJhP=$0U#fmSK9bjdLXMBSRf47Sgk^7!iPK@Q>-@(bDHJuJiG(@y zfLSAd&ibWDWm>{qf?iQ7#cU#M!C=|2H|`=?>YD+Q7NRee8X9#eLap(e-XBKTQA2`| zkLbgFZEg$+jvov}*Hhft!+szdj+8y2J+JILhOW(ggJadOWwnp(z(~v#5Pa)=r1c9n z(;_>(@vs|O()iS_f<8PWU2k}5!oNt@t}k`J*ph`WToVEa8f1a z4dV>o`exRCmh&kd*#{fbo|?Y0so{pY@oyEjpEK>uHO$?8gJmO9yR^aoCi`EEz4-m6 z2=nZ51nG=fX_7c=(#u>5epYkUnT7VNkO-X?WTFmF$8Ce%W}sfJ@#? z9-LC%IBrC8;^RZ>(SZ#F&%%|FA0L4VPW*S9`askuA%HW*5zcj|TXV#r+Te1)0y3yl zq0~X8;NV^h?-06@L-_++@WbXM$bivx=!A+PBG6xRJk=)&#o?5QLPOwxE4ZG}uJ`UO zAeWNt+ebaG6jYM;e^P&X&*}U-bF7!ww-lFFP+00Q!Spoc+5%;QTN|bmX0l*_rrpWs zj{C?;0VvEcFavV`;O!ssI0wFw!_z$xlN8ulevm=Yk{+3zIkMUHE}!39yR`l4dUPFAVZzxFqVa64aq zMhg!;JUP@zRT{4?3NCayhpNT;2w0S>_Df>Nl5v?|;cDicAN2u%Y#>`JpJy>@!uGP? zYh(md29(x%O`j!Vy+UXwWWwo)_*1g-n&gQw2-t%^eL|(`w3TqbiavS|iWr(v;g4_x zna$aV+^kx)o|wAFGk}r~a%$Gcuj6zRYzdYJ$o;=S5U?oxPxV93G>XP=*8Co6q=WkV z|0*!P>QDW*B)-w>za{ZN1^u6r_zYsjFHACj`h`!QPPs)cIYXJ5>&wX;euJX@It%2y zSg63yns$pyhnoSFY*<2(@B4xG$8YifSNXYJRYuNfR)eM_Q`0!*gt@?31vxGra(r?6e;<=KtiM4#Cg2|~Vb=*!{C(GX9t&>6B z(7Q0!aS%-=iDpu22(AN~sQ`&HWgtQ~Aw*cN0hQ9>3Bni8F@uO9tx(%FY=rGZE@!J0 zypK__=yEtX7q|N6>Ynu1AeSU4G6+<9OUE7_O-@WS*14&tSao(iSw8409b%STS@*yN zAPbu3&s%{GNk3bflxUS4h}=0SQy)1q&3LmEXMCrVAIEueU7%CBEA8$%g#oJP!-Y_J zFc36E*!J;mxG5ku{Mw_?N_~94`55xb*m@iNugbI zCvJ@isi_0c{S6x9=@n~M$n0xJ{P=FUD;jIn=Bx<`-a-n;G>!KbECS3xW{bJwoDhMo zg`gRf*mze@JOjYaMi~*b_IL;qGU}0OpAq<9vF=dwp~B~Z1!5U{PLA+_=sc>D!)a=Y zOw7148@A~0LN*mEh!TK~-T3CpLDlLb$k-N*jg4&vU_6WRtSZyQgBnDuD~oZB7ZQh{ zL`II#BhmG1XHxw(->zfncwaJsLDG3bV0~Yz5vY3`fMfQPpt;|6CXL;HdL``bH}uJz z7J#&9^+IVQ$q^{{ijc{K<*q@)plOiZJlZLzvouGC3~#zpYGlH|(g`-*X})oC7HEf` zpP%EBh&xivkIv0lqIy{vD`m zAVh`JvUGqO80Lmd*tTX_Xf_X#6ey^u{0ezLbh7lhAk>iPe+a~xlJUYr7g+@-a%8@+N0_2#ak9=jVh1?*Q03omn7 zR8&;1e#N3E8rPH8fvi{sq;Tls-E;cxg-+WK#)!;deI9kVAR;7yiVr@Jkq@JKYf7H) z!*pNE)63GKg46=}^N2Dgf|aIHMfp2pJrk(T=*H*THH%I(r{mV_6s*E|@6;1f&cGS6 zI$UrEGE+;(AB>0&s~&Xxc_2_#FkoVOQ~dp{?AxHx$Pef>7*IxCUENI}$Uw8hj5&uh zKkirdu0hK=$*$ z>6$71N=wKUG+EqG((Qy9Wd;Q@{{1^k2?h$ZZ^zO?!!ba`MlV=;y74bQd%rWDhJ?P&d*C;iWxZSEJ+Va^b|PUP6nTOf z#=;&4aSx)wHY=|znb{%vi2kCtg>*SOJ-;0l-eg8sU>!gz;sm~q82Ua8KhBU`05!5u zj<{P81*o2yk2BCYiV(UPl~q(GYLSL4-}r8`Ov>>4UW0-%sKVKAb9b#d55^_uKP3EK zLhdI63evQHj>SD|wLtP&6Q;{TjTrcRLh|;GZ2Z}%0efO0%{xzd?J~NBx4F5+#mY<{ zYQ9fQQOoBq6vqbFEg{Wc_Y(ufz3X-j)AGB9%Vk7m`$x%~D|?W7UN`5i1i~|j2qyW+ zjK+L}_FG}4HN!^%Igc%05l=&aP#h61p4Sg@2@}P9pA6l-F-$q+fNXH3E}sYJf>Ta^ zV#wsM^3>fP)zpAXO8g!@u0ShvBQ~Gd0xE3j%!fYJQ2`~`cz(f#KJ|8Vg)^E6VWRaC z)02Jp$DG8;3aDJyfxlr?_7oh-@9uUsQXPX^bQMQS=_evrO*D^ z*}T^v&)M;1?U1u5#&=qF_KF8M7u?ZBE}PgQC-25~X!Ny*KX**k-;+nC$L8US;{N<` zX8B@f>at{oW(T=#>W%X+D+0pqcPg^8N1h$6B8l3WTE_5n=hPf5hm6Hb@8rvtRZ$mE zC|mse@}&QXUtsk;r#2docll7XlQ_cT$}mG>N8fO4PSD)3R`$NWCQs$2XtS$saCs{j z1IbShSG}XJrbG(l&Soo*8)MRI5G|RMAafr}4|Z0^@!PvJ_GsL*xJrtwdH6im9jm{F zlCc(d?;lmm-B*yD9b$j~E6-g(?B1#Dw7&tw%cmU^Gnfb#;cxy+(3c50G~DY*L{Q8= z8tV2lp-!&)dU3gnJ*`v8fE)`mRN92p@rabxL$Iy?kMkSXPT$dwKUU%1^(O}InqZKZ zgOA)UE|N<;{?vW|Y1HJ(({f~e{S=ka{nC@Rk~Fz+)p7W7D_A(H=%Ch*xQ^eCjyHdP z?S1&;V;LuhOKb7vhqZuviU?eANl?@W+TJ;?U`uNJ`XA?1Rl z*|tIE*Qu)DMu+%7@Qp^!=n&)n5E31MkFBrgA3qgcd6|m?94(4Mj;{yh{LPTNkm$UV zbtETCSJ_=Tw!$|?)r6Froo5HEnasrzgzuU*M&UdHV}aW(LqMuJeMZm60%&edWz1(G2QKH`8SDD$W!E`*Q0>O#oZ+kWNQ~I!D^hP9QwVFK6f#*C zb~k~jvU9awXf;yH+ahI+4O@X;9GHY~el-N`zM}n$$xbB50 zy2Y=!ss$IX5Lri9I@-SWql=VrS0;dr>|1+DEg^T(*~3xiIf`)MU>q|oUVZcn{TD!v z*x*u^Q6(gsLy9?`!T?b-=ab%^60Nv9!p5Zv3bn}Z=||@zhIY(dz&4s9Ewqxo&C<%s$%qg(&*<<-W6x1T zqM_P+MFm^^U_FQ1-iVi{&_~cL7ZJ_>m(R%9Xf-`va1p3g4Qyh4Iw5vZ z{{x2#p-+_Ho4(H?0>3gcX%nNj#~rIuWwHi3QK;hyX&hEi*ibmxy%vi&=M$a^r^?8q z35)5+J_aSCruyp@iGAo4$h2{T32p^_R&aL->35#>xX{D5p2S@AH=hSuE^58d*0Lt%M zw$1T+30blkTs=??5%~E1yK)f|VFc4SKwk3T-3KdEYkkl)%%hy$BZXsOsW(4H z%WUxv+*9{nZvK3@;-r5~3^U2;CXq=UIi~BBQEV6G|F=#B#qYKgREd9n8fO@hot+)& z5Z?$WJGa<%Uo-yUhTx3%2)^74iJ_pV=rfLp?R|XetO?WOcsF_EeRmN%>h;-v7-eV9 z8m~nfG$E<)i4L+KU_MHHdhBOj<>}8FdJyAcLSm(i0N-ISlA?TfXxR8tICt{wGjFVg zs~!RVUFyN+FY%3tHA1gBoE>5kBZ(9*Pl#FyEVsemUO?oOUArUCPq2?(p}6Sf;M6n4 zR8P9~jQYFZwKsXRxj2k8G~P!YUBUW6LNt7rAFN_2r|(98@Z3$zdHRSct$07+TN{vi zwZTIf^M#*|^8FJCa-`mDrLyS2qOzn z;2=?EeGz<58Fp;Y!?S1qe34v@QXz_Khifp}*tP53n)ATghZzrhjnNlpS@Di<+0B~V zJx^*9C0_+sHzqg^ov1NjCvZ+FT?gHS?0KaBnSuQn{O)nvr>|hltf@tS^TcxQD$rJ{ z)zE&^eM+5;8&$eqU)=DbdOAbhyx;-qi=TWHldleF`3k!47E&UmA)P{(g6)&TSI9)N8zbNck^_J-t~-v=gvRb21+LuglO@f5Dty}Hxj z46aUSk%#9&t8+}jd(=DWs3DVz;0!uCwfG6UmBio&dqt#eYdWlninhxN$*wLYj7;d9 z$BWaS`}DHCe*9QX?@HJ`3J4xg!kuc6wx&*UcT@Zp?$n>{ob&8RtT7dEj7^so!fECP z!{>3M#8xHfVdO*o%(6Y6&X#%_mX10q=H+)k&8>?`xc2JYyu5|PmhYF9h2+p zM$zK?imi*G*b=E{-m>1%`9_|6gK63}Lp6M))>ikI-XkA8(zM>REDgyPptW=E9PmDm5F?U6_ru`3$~|Kb zR4mf7ANKMLop;#nI#_t0i$nJ!*E~zi5KGX)$Mv{ z8dVmAskv)i-`rKn{eG|%YJXaYe}iVc`+3rBHHzj#bxBJqZ;k5}v!R;ub-W2WBjyW| zCpi8pli2+V(R%htqby>qfj=_#!?OHMIFz=H1!lnXxj)j+yB=vS`Qk0{iwg z4~f^uJ9aW`7UgL11%Z!uiSt|nN@hm8yNae29~&JnR^(HpPrL+%Y)_b z=W4-ZA#How!nrmMBMlAn;NGq4&8@Agm&QxRR8g*ycR-iKYC&F##Easc_W$JL& z#MVXHf$f8jkKTHE66=rC&geiBd@)dvKQ=X-R$W-v*`U9TJ^cjxq2jBfJL2VLNF|XQ z`}DB7GGx`-p&jW$Lz|e0$W2&|q)ZGk)mpQdS78y|+PY)|4$mmBujevr4~DqFjuCC|L2f%Msa z4F3<6byj!=yQ;@=zl~Ap-1|fiLVZRw*#Nt13dgn7>rzwysFBcL%Sdo{gT!0&nmEiG-I zUMXlm_@RC9Jxhn+dB_?n<<>>Ev|Hm`arLH&HpaL}U8)u_We_%yX_pcaJ66kYF^-=p3RO2nP60(yb&Sfy-7E$a&l<6!1j&vQ>OuLnJ~N6s*_2o#nhPC|n=; zNk<70Nq+n}ybu;eJ)^LQI)if-No|URjT19G_xfqfuwKU`z8B4N8XBWs;3Y|$3cNq% zgfCJeATs0e=kB*kw?{oxp`fJ|)2~$L!ht@V7>gI{z4>z#GcZ2RFM>&MQRq^>=q6^i zwBj6|i|Lg%q2R1=8S5o%4+a$Jn2Mzuhdpbl%q1c^=@oXQAQEH@b0#i7B9o%1)f_oflH_|xHX?Y# zF$lssE<#yvi+$-jCLO%q;bP-}>xw1S)zzDpsWNGiDG)yXfbi!Me2@)Y4M6(+`}eI` zWgP_Giorf1B57uAhQ)E-9w*)tn?n;K8Vft!?R7jIcUYl{-AO56uh4FEbA&d>fSzP0 zv&6RkIPzljo@zNG2i2;}4-irLTbNLApfh$FEcDJ#IdGxs!g7k&D8d{Hi!x%Z3j^8Q zdoT|r-J$&-q$izXnK6d=mNCj)^1ZR~ckfo7Pj{!OI z7Px5H#=arP61s|kNDfB6KNQwkX8EkEr)RjMqa#%`_xtQ)CQDqp!Cp|8!u>YphagQT zBlDa^SCysc-L%eKrTcZulV7ORv<)+HT? z-~(K;z^)OqBBm+IY5^DTR%&W$_7|VS(T$-oGo}-xo7}S*MNAAK7J1f>H%zT3)ccH# zwaZjxQJE!TmB2e&hRXWJTu# zTMSJ0rLT=|NrVm21!t5+AiVIWP^_6KUD*8n6%Aq^`?Yg(tRNFvfbOXXt3-EQsv-lh z@Lv{hnemWy5wXEdsK^o<$`Yn2?Rwn-<=cGo z`gOUR4TB!r{dA@>f$98x74(~dV!wmf`o4wTMBUN`J1PX-;`^gm8Shv;;rtvD&hi_l2m$BBtGI&AMGh&)QiBh&kM%X!g4c< zmRs#^_b+;!jUd<#+tjlt!8za3z9Rzno!iOdwZpQX`NQB9HHRmh8tT{P5%D6J!|u>? zDnsIjM?4Vo@xofsxRq*QxljcyV;hF1!yblZCVa{H6{%}+>FcN8=8_B0D5sCzJg*j% zf12D+uZI`{yw&-Xh`|x2volpm3EK3aLa;93(-$b*i(ymX*b0!Zlf!H8POXYJPW@1s zKJWR&>zdJ@v3L6V`nu|+X5DDsvj=WTkAN+s^6St6cM&N6Oy50#A6&ngt6s!Q8LXEu zjM18ip4}c>ki(zOQBTmLYBXeIT1i!)QEt?)s1~RFOvJX1>LzyEepTEuf~BMN{Drjt zm(Se7`{hsYLku;HjEtJ1js%$QSFMQ}teRwfSS2SlaHfiNOJS{Gyq1a6&SutD<7C$! zlKFPH*)$>Iz|$Svdpb6P$MNzKDxWhrdgq#iW>e?)eiGD2$#cegKM_19Ig^**t5h$V z2JN(($Tr{Uc-;R6&bbx>97zlb`5{hMcQ;zOdJzPysp3P)bO-I-uB74Rp1Dl^ZvA#* zOyccR%;KUz+{#=D@SP>)Wn~7&Tj_j%e}jV=%vA%W z=)T>@cr7>jnZdylsgemQMVAXLhRTMN`UPRL`6iRRVvUQPMcGAx&c z;PG=xYNe8it(_th76Ky$i8YpvRUE0@TZB65nS9qNLgxU_B!cDG?~V(=e!YP0#>`EdLpR}c%z&ukj!dv0rC ztX;a=Gt3|M_7@Qe@qF7|@s&e#$LMS}dT{WYlwwAVPefcz`dzfEI*4L|0irLya2Zoa z)>XZH3dwpAE4^c|cA#)N&@u!&NT5KK1N)@<88jg}I$Gy#vT=c8zFKH$FB;{wTm?7x z_G0{NwW9Go(A!MeY%gnw4C&qza0`Lyczudi?f?h2Th**yWCal!(%vww(a)W{oZyop zvpwhwM4OmVEbtf8Hb${(V_7S`w(Wp*XF6 zGg`Op1k*WVW@kL-3x1ZTQaG0POU&P54;&J=^B#+R0CHJb*=T8Lsb&V986MQNDzrWz z*!RwYOsmS=+~a3%R#nzJj7=E`#J_4R_3>Ainwdy=%Ec5d$VZgSTuZl~WSI=0w=R$T@Qhm-1HL_lyy z*;4v7_B`S2?9|dTK3DbS7>&LBrSCz!9_|MHi+*ytRHD_gwJQU-ALUqSZk-){avFFH^$w~C;ULBo@NvG`OH}qSF?Q+hp^D#QQDQsd^t0=_wz|Fq^ ze3p15-*t-{W-yUhjw`tqN_)jXEWZ0$)E!G4h!cP4sJ0PgLSyrzSe?2PorU&&QY7j7 zV+}75?n_Q1re70Q1b`zS0dems2;_=yewqdH``qyxvJn+!&_ORzVNH0>7?5kmAJ4om zW@9d}?-slAGN>po$Q$Eh+(woTYd%M7R5xEsZEjbHVW0@;%oAw8uRT2*TvOV;p*ieo zW~Ui&TaRqbe^5_VaJm=1;$6(Zfj2%fmyzgn!Tp>fiE=SSN%g} zDH{4xnwp!XN5#bq=M&%Lpx%7u+PRaJtJcf3ADnx;ldflMDwWMsTy~f$`S77ltlaFB zUOl1Ta(~+HxF*j_NHrc*;gqc<5iX%vJTXzlLk)JkPh` zSM)_~S_sA7MAO!ln2Bl6n-+2Ihp2Qk9MYeTW4A!g2dnZ`V+u-sy&}yzamPiPg*p_@WQ~`ksAy;Cs@htQg1T5XGYk zb7WG6>25NZzyi$djnJw{)vr2xzjHWjab9#3J8ENY+`F2GRj1`2Skv*~&nRn-|9Hd&Fw1$Tr9>jbu;p~>d3mR+|CZg^BvoW&kkLGS)RA}OkBNCHzkxjFC&#y z|NTrpzh}>>Jv6aAz1Zc-_~6;y(vRguDpBW@$@~GNY%a*zIfM(Cj{aW}^@bNs!)#gf$yzBSH<+zt)%!Td8_wzrq*Vsm;vcLi;tDawFhlb^KX}GX}^W1 zx*A%ZfASw_IGZOLc?O-@GDD)7zYKwb&cT)fTIZqKFPZi*AXGWpc2Z4!M}6JQoo_ckU_u5(=esje)fDg&hB-K}TZ6hOZifzLa_B~G z$-rgE8(qP`91%TE5SV$ni(_63wufP${){ zXr^EC=Ka2SQaW+Hd*L?*8arvzDfXSW`>kk~xX~Ei9u`t5igY`d5O+#7tbW@ZPSNfV zc@bv5Y>bCxbuEU}tZ24+lbEfMcDMW|#QOqfdY=39Wz(Z;GHiR!voZFgDf zh2nV!uYRly`unI+xO|=-DD{7MBF_Inx_3uNM9KBnXxhBJ?_Gy?XMS^*3DN_`>!(x& zzn}k1}H> zdtf_OQHvY;e<`q`s%o4u`5UNKBjZ3l%$rNqAE8i-o9TzPZ=GB^JqohPP38&=K6>fT zIy^R9h=v-$b|e{6X!Kgiyt0f5gWcIVpK*2;X>WQWHDYLXJY)CHxhiz58M9oSE=@tl zpbtB>(QI=Yc7gIx?P}`qilLAuy2TIa?sc=XZ~kcLU`R8zU-k0QhDH7vaAaGQqX%~m zoKK;btKEb0$EpJ|(^^-}mzfCzF$ z!w1d9*JsG2P^n-{A^xSNdd?q@C(xKt1)M_fpTOC!(CFZ{m& zsD~_g{Opv3!HJ(gD$A^3%uU?LXtl+f*k0%Q$Wh?$poz@>OY;#=(f_0QPFcVNky9Fc zqzgWq9>M-k+;?`r+}4AodXJC+TY<*M*W3%n;&zH+g7sM6`I$d@eK)sGPBzAWwE!7H zyR>OJ4pmi$>>3Pbx_`=-`XAO0aJ-K?M$Tqa1cVs7?O#F+tPV#Bf*=YO7V0Dgh4^qz z8Doy2fq~-WFOOeI6pD|DvNbRj>zJJlq&E&YL}*3+0}~ZSOxTL`LLr|sYI;(=OzyEV zz_PRe)402bL%6`3v7Rf;Vbpf?(f|NoJ95CCcak#|nBxYXjqk3vh? zL5HfVo_Qqo;Bbq&&R#=E3tr2aZttaZwEdHeC;BP-5)(@ zlKY#2tCp9C(qbw6G5#xE1J?s1p(-l6DC##X9W=nA)Wt3{vHu-~;ovCT+kT_G>F+}= z{s>v11_;7<20!a=?*_wk*%Lb**Z*(wtr9mx$N$Si&|rXaTapH&B)*}!2OflBU~C)& zsA~y1ytb4C>^i}}CK7S){klZ;69>@VM^%X7AbYyGUGlDpmX)vz26$@C%_Th@uCyBR zt(7QLh{^&;oJ0A#-LDiIla|AMZbT%&8(6)H8HVP0Up(8hy!-3)1A6R zAbRGI%QOA$oD90TmD^Vdl>c_QI@qRTTt1g%lwkewJ0?c}>y#XYE1Cq16C}~h1J900;tV>k+&}*J2K8@<;!*j4H){Z_zWiDIkH`N|&losC zi{}tW&rpE{&t=DWWr5o@6zl+1B4JkV&6NE=hJTYm*HPb$ZiM;|WK)1aV%7V+t7!yl zwndk%4a9{Lv0oVl1EQvOwI%a_5RAY}hQ3i2uU%tC8|AhC-_YL~2atzBnk^(VS}i7Q zL?7MjPR@xK@|TX2U%Qz94biL zJT#x{un^qRpbCb`n-Bi{ZE zH4qSA`he^N0@7PlFft9n_x^Oj5!3(6lt<@g3VF^i;uKeCM5OVfq44eH_^pTerYr_*btV(du?IDYa$Jj2w}rT523U1TxH*m zUA|^SXZ$H$3JZMpFrQw0xHGiWd-LS7`jJ`4-e2#JaPNK}^S59D*X_cmZ_#w`*@pTz zzM(>7aO+kOYSTPYhks8I<*xtvmyEc?81vYvoOmuxqwq$bQN3iMnt_uK@1BZ9K#ag| zNkosB$mrU6sobi{r|@Z?=%w2mvoD{-6X1-C^}S z^_Pz!r0vO%f2?WbP>Zv_?jQqKca+DL@ss|;IAj3h?ERK3G(bfG!vK&7^em&r)J?o2 zBm%7d{YYNJTeXXx8x=?ybdV%&^TYKX>04l0{c`fh_x$TC0lC+SfNX&S&ag~W%6i~O zQHhhV)p4~^A^j^aJ|?wLnA=!*45t6k)Jea`;lIwG%o16qD^;nQ2$|~IOy?0<^1rWn z_lmw&h!|g&tj85ZaBR?zGw-NAk5)QH=29@_S(wpsMWmHEC#_*ZL^I{YP-~@gMl>z= z(*Fh{z<(_O3+2F~(DC~ZPg)E*Gd09VOtOT|N;mK*ex0ml$he-iv{kTfuI6U*Qmmfk z$8tD79c!kQZP;BkyIX+u-d5Xpm>>x;KFNGK%|*O*lg!X7NTcN}Iks;apUOM`Yn~uA znMLeO6$m4OWS)UBTBSzuBe6jb2X732%D%uk=)pU@+|{$I>otgIi3kitN=HWuigq+qS?QD%Mri0^4rsnLw1w+pYe@j%G3@m!i* z>tF`S)%CJ2{D7*CNFpLYad(#RSqk^!ao>wx3DVy>VuB*84R~dD!c@NZ4*BJ7iu6N-GKdU!_D6!3hY(Y{B1I`I;fRw z4AcB-wb~E&?S94d`%>IO*1f=JI4nfQ%5xDr+D~t(Uf#>Dw>y7^C-NtB1Z`qo-u{m^ zu^6(5@L6d6WnkT4nyZD`_W9`QPqm{>=VDjg;eGnoL>)}$;ydge&*WE)xaDB(9PEV` z!fN|K6_Lk#y3)LS(LFhujIZKZ`O5t8xc!Wjy|TIh+w)vz7?3LwWRv@D@|&0;&}I3T zW?c1hp^alVz&-1LB|s@0nJ{}d1ktf;kLN-TY>Ya7->phU#fYQ2 zM&djNZM~*^9{dL(^DiLX?|g0wolJ1VfbzdIz%}=Eyp&--T7~_vJty=}9arwpBDN~H zJ!Fp1cIa-bi`svZSzl;WZnLTC_1;}GtcvrF-(WPswkX=VX_*=u55+#GD_a-@+ey{od%-5H3wstxDo#SRv>4;s&uJmge)7Ffsm6wmXN25|&C zSUQTo#q8>Z^1KLMx@Q<|dX+gN35#fI`G7lR1j%=OO|Fte{42a67W~M*v66Ck% zjZgX^*_3TLABHD^c38>udZh`*dKY=;oRG#ddAf8b*?63K{M5_OSv$9DdS6t&?>uH? z>erri75+8bt4PDv&IGsVM%wdv%e$))dIhiB-r&~3yEoh%(7LOPv{|LGYPmNTS8YHI z6MsFDqrBpEI$Dx*8W8Mhy+++mBWq@>lLNeHEWBR)b<&+)QA=sWr&IL~2A4zg z&Wcga9ow{y1L6K#9b>k87!T;zNszJBrNT=R0P%bTDy6xI+_fq_rZy(v1AqQW-pdUY zmodHLy!!oFPCrV6cHYByFEJP+AULVv=E>CldxgX6Eg7Y?9n2D54+@WKCHB!>cLw9_ z4+qr&*Qp_v%to3&nY}kH%=Wns)1)(vdCvDsf9X=y0WwI!Qc|S1P6TWm=*h~&HWh*~5Q#*hqUS6rIq()~Uax478dv4!$^zcZNJ zANY1S{Hyk|6T=C(V24|ntwyY9LFKBY8`aRvNaicY3iFqZT#X#SzQg^9?;>FuU!KwD zj!Es5R7z=kc&h<2dZ3k=mrS|t=I99`{0Wa{QU7gQ&VWgR({y93Vz$xByca~N;-s0% z)g3Tg`bNx!D{$X52xw;19nY*OXR!=F@-qteNB<~aw!S1htRMNAAB~=OOyaO0d56jS z$C=_J7s0=H9|8Fi#K8+LK0aZ9YvBzUlJiw`Z~} z1+hKK7(CTQMfUd8ipOF7_qf->h{IU|6;fsObV}fFC_f7fz$qH;SAq_t4q}A*ZJ_W- zk^aHGkcW^#vlAp`{(N`>{faF758HAy0{|8d02rMP8_`~*;RPp1CRN}2+d$YN8+;lQ zM6pg9zG#16-a-Lz!egZ8f%};E;ZzD^Z!@@oM1`SJ&mTQIE4BbcL0{iM|Bb^AjH5>_ zGwLtmkOla4?^8xX{-`{NaH5op!~Y9k?HEK}{EJ0ifP+zc%Cc~b{^R!cHUa1>Obs%5 z3J-n{5yD%s7_rUj>_@If5|!{{zP@^qm0=Q1Dc7C!pKz)Pgj0)L?qRW5zQ7Y&&d$!3 zGAI|W6ZtPbBte4f@js8S_;S^~MxRnt^f6c_HF7YRow!(~f+qOiSO@RnPoJ_r+>a8> zLIkR>jRsJJEb4@^{~|zzJV0|@J(E0J2`{AQAyIlzpV%@Ua6(N#1w8Zl0eTC9&BLVTz7P=6R#WmhWHYtX-^7O!J?) zV!j88!&dr5G8pfpsGkUif66eiabqEV$e;Tiv0ErPW{ots1j4Dl6-XyX^Rqdg@fv zZlTP@N+pVFO5u->)7oTEw(r(`RgnLc09*5KFbYC{@F9~w{Y636mx7DSJxaak7WC3L zcp-KF#?!Av|706|CtnHmzy0GU8NfDaDjQKMt0W*@|$SGD*DliNHGi0ma9a-;Ki}V2f&30l)9@;r@U3pCjx(B!AU02_Q$i z03nVsG%#t%yhAK^KdI=a;Jqt$NdXH!VM&kAHj4DnZxLMpM{9WF|Fn1I|4?szoIy>N zqA^I8EZIURR3we;$ubm4jUh^d5{4%0weL&HlI9LsM%EZa$q-pWp5iiyLev<|ObXea zGoyR|f#;X!hdV!hU+0|pe9rmo=Y7ucf3Q11?IBUj%XL5;P*D4mua=dPO^M1a017uEQiI*VPV$FGuAQt&xeG2GX}b_8PL;3+TGp5^ z$b5XRWXx-zRnNi_R<6*yaWCx&)HM?-Gx&4qR71t6iu1+3;l-vvq%-47W#?y~+o?yU z2~{{?iyD_VQGx6soxqR}u+lfMjv(wbu!5$8YeMlD$r);-TkpQBhrGSNnKiG+q-3sv z!@iPV5)Bqv+ufVED0b>hcVMaJL~!|-as)_bF3I)!-B(JujoCL(ZEG_XlRG^6pW#s* zs7OC=lW!Q8DOR}iAyYnrE85vz6 zAEos38*MrxrroMhxQFl}VD20gzW7`(dp}FLCPi!(VkIU$I={YP`HA&RyI(}51nS|s z78+0VOT~Ni-Xh^OVV%I?h05#1^W_J4m1V^qN<}{~+wK;yzE)i5R@Oo;6gI%9GQx4h|?#1LXUQUL@`qz=t^+K~u z&MLryeLDP@bfk4=bsRMB*Rr;sg8g{97Fv}MwOKpm9g52E@070z`ib=B=e7P6=SDDu&ZTn+jM z-*!a^VE~-?=w{*+AyU%>QRrs2zQQ;|`xZvlHrUF$k{PT!ZsyUCpB(F7dGl_D`J__e zok!o(-p)}QA=rZSf+AGq^3jI+q8NO1(8|-Acbm6LpHBHVjQV?ijk`sXEdFUr-Xz>2 zQ&6=I_lHyf7C2g})SF1ee8Fs8_Zt^Wwh$CQVU_<)qVj}}qKwzb2)#89b&51uSyo(T zJ}5J&Z@+MCFo;=vtG%-)sm3t5r|KCvcA#FxEOp`g8PN%LeyY12Wm$T(hXoCMo7`SE zVGYojiexX64=PDgE3Yr??o7Jr*E>e!92@c$crLfAngKIH4h(&zY3K3iSH^~c1K z!f+9FzOw-PWH8XzPI6eHE}zujjx$B15EQf0umW%$3g{VWwXxxF*`g zx(B)@rF5o1CzEZPtAXb2^pz@J42A61!PsaYJ*saFbs~$ch1=b^XZK4lw76hP(QC#` z3p2hV?b2G?D=l+j!jC$71YV`TEUFdwA9+7;rN;;f1G!tAwUuk7g0tY%gzRo{CM0twXzu12u`65iZTwsy!&|Fl)Ocu^!H~kJcSm6!- z0We&r#{EFye{JR>!7a9_+;j-{XvcoM8ofF=Oo1s~p=vaLgVFqaPZT4zaD`ueu$1-yz1tnGO3on8UrUhnBW;&S%K zd}1H5&9Fut%P3P52W9Ag;8Y^zp1vyf?|k_?FR>koQ_(|4DT%rCgylD51Q%<^|&};Zxb; z?2kyd_83O|k+!b9RmGG`I{LCcj%i`^rsq8$ddqGWx3zd1msSt(Rj@-O!{fk}&X(JD zoARvW@LDLxTb@%$mouT1w_XXIoBL)Rbj6efvv0Yxz5zR*Q=^mFF}{pF9qL8uMrW;_ z+{@KxDQDyA?ubIoe(B#G>f2#RV{GuTvJNOK+~MHF!f!5=z_Bg@pLsZSg@bOqQ=nGY zbVr&zaqtiPLr6t9Un4;Ptd!;fA@OYwnF!p?CGOOxEppWx*9h@~%=YFQxT66g8q&r4 zz_8RtOk$R89$P&C;d#Wjf{+y8u8w_)a54=M-?$;-8p&#S7o7ZR z^K6jf!$!B>kBl5tDQimI>j#&??3IzH1KB)BeCTW2~$(ev0zg706y zjQKv_X*;87%Hl_mt_J3KlHyxF+|DgEQb$8}KID^h9GCaH) zEM((Y3d%rmUa{JJx?Vdf%`zMUA{L7lm$0?Sv)9-X!ofXm1t^;cg>wgoV3odB{l?ro|e4PAl-&F3GUE*BpP3x{wbh)!u6K90>n zfv}@&VFD1uzkRLYltjduE@tas5tFxdrJkdx?K{;6-#~7FSKndNdGi9`2s^Rw4Ig9! zu+&IXH|g^GbLA00YroWHbdVB7p3mW)yiV9Iha&+A`d3Rdtns3aYkk(!8<09(txomA zD0xjpTZmK#AE#1LlEyFss&|fiNa|GC=3lw^f#b8$mK_<}V$RZs=hu$Z2yagkTdAOp z2rvWiucf=#Lc?BGaKM2D(kkeCW%rvU_U9>HK<$OnLWS)qVP)hT+|SKG_e33-<+hIg zp8i8D%_F4b{vM9~l`adqAEumD}8nKXc=AXDSh>$o~Q&P*e;6 diff --git a/Svc/Framer/docs/img/top/event.json b/Svc/Framer/docs/img/top/event.json new file mode 100644 index 0000000000..5267fe8c9f --- /dev/null +++ b/Svc/Framer/docs/img/top/event.json @@ -0,0 +1,48 @@ +{ + "columns" : [ + [ + { + "instanceName" : "eventLogger", + "inputPorts" : [], + "outputPorts" : [ + { + "name" : "PktSend", + "portNumbers" : [ + 0 + ] + } + ] + } + ], + [ + { + "instanceName" : "framer", + "inputPorts" : [ + { + "name" : "comIn", + "portNumbers" : [ + 0 + ] + } + ], + "outputPorts" : [] + } + ] + ], + "connections" : [ + [ + [ + 0, + 0, + 0, + 0 + ], + [ + 1, + 0, + 0, + 0 + ] + ] + ] +} diff --git a/Svc/Framer/docs/img/top/event.png b/Svc/Framer/docs/img/top/event.png new file mode 100644 index 0000000000000000000000000000000000000000..f5852898789bedd74cd7495f0bb1c675074058ea GIT binary patch literal 33543 zcmeFZby!?Yvp9&8Ab|u89v~3h-8}?%3-0dj4nY%wy9IZ53lQ7~86;S6*8l^1CVB7u zzWsf7|KHu`&NDNo=k)2S?y|0`E{If=mqJG&K!JgQL6?3nt_%Z%NCmW4pCJL?WM!)< zFfeE~mSSRx(qdv{ica=smNup^Fz+K1HIOw`hH$fVzQo5*!o7@t<%K2g_4$=(6d9RX z^~*29qLFXj6fcbA1zF=MmG72D(0Sf*;p@E9 zWj_8;w4CaF0+X{ilK8$>i2=sxyXW*mHQBG*Eo`bi8ZtOJVc5#<#E}GPO%|5VFvA8< z?w@`DbtH=op8ZsA^Iz?hJKxAb|ZHMRYr|8*nk1wV)I`YtYmQm<`J3wKA-Vn#$ICH zUxa)V{QhY{YHLeY?Wb~tZEgpG5kAK0hx=HzP5TE+v4@X#1DNW+ILNGe$WtlP`8J>E z$DWchY<}lpST7WdT6&a|`)l@rwNxmuQ&1d}xfy7+m8>JYC45X*V1;Q!Jw1Y^NjNr! z7OMRMU~Aa235j59UVhKrI4pjjD9E6TJsgN%iR;q(E)EN$M)11~LTx;E;uz=NtY#up zJ+JPtS;-|{^E7N1iay4+)^mECC&Ju-{Eb0&l#nxNOck=mQM|X3BIU3(3G{S~qNZ%E z!argO>OT(~8C&ih<)F}6EL%ifPm*3E*xmIxDHHkZ! zUkWOS9<%Nhk|#p#+2`PvQ^cM(!^<^0aE_uGpNcfT;9-|#M5$0Nve0@je~c&oHkmGV zNHr3tGS-iE@pD7@-N8syi3d7!Fk;BHLkD(Ia;{^B=Kd~05=@E7$kZ8&>{DLf5iJw=5y} zvS`#{uZ|qVmPv2=Db_hKIq{ZJZ%9Tr(*@RPazjs39D*k$o7p7lh3~|^8jBEaVW`cK zAKh#J1jWw~WAsAE_)G>~H@|WCzLG?$%34AF0N+ijs7ybD?w5h55E-mVsB6(PmB22ebDQ zuY38aQ2mGzWMfly*n{>q4maQeHgxiRd^=3he8eyZ3hi4%9pdgI@9*yqy7tHgVI97s z**!Jd^QNocrUjhrp_X|#S#~Oi(=j64CQXL$jlrbApcW6@r+nD zN2%tZzB7c3@SP3kQ`1{X9}K;i?4GLixKq0axvP%5BuKwNk>v{!z0e z)(PgevFOp>u`M(3SlZ~_sO>1$C|(LFv%i5z&1voXCQa)piz!=6D;|(jl4;?#E?sS6 za^j>_$DC&w28a_R4T`F;F3$$iZ0$ZK6Abkmrkw^=CdhEsFHIrUYkZIz0NewEyo|6(OokSv=8o<#(Ly_HufJi z@~!xm-y7XX-Y}75ktoN}#>p$lOsG!CWi_?CbQrZKdFq~0c_4dETvgsY?ryFp>^T3} zVbYgcqhIUjoR9)X<3_LYw607n#~n1SRE=ftW$$;5buo0)2M{WfoN`Z+$CEbGoxUE4 zO&nSp^upO9qD1ELU6|lrxMUjRRxsSq0kB3ulb<*C0&! zXK~N;ar~l;N7o%`xmS$&2S-Vqse%Yz;?=NhI2QO8u-Dqr^SX^La2TIRX-P!pTjhzc zQ+vr>2IHrvET^muyd3P0rX##zcT+tqU$}6*Y^HJa-dr6-?yrjIN;XI*Q?QVomCZ=e z{CxX{hTGCr8GQSB(>$&#!zP9PL#5oCLdtK4ANEo)Sq)c0Vk3{SP^nilOxP^%3ZfFw zsm&Dx1tpwO+=tgyMXi+gS7#@dE$n!jsACcuX)4kOe^u;sY$2b|pYtL51VO z&19S3nwAgkVk1413DG5Qw8-CeHS_od8pY6>(rT-_t4pZG*ec#G_(gui7c+>H&y?obEC07{}U!}WG|MTHU3FArZcy^b} zVeYwA?!vRxy|bdK?APw!_H4c{qV9-JWC~93`kx1_h2BL8;>GEnx2ifXZaQ7z+|Wt+ zyFWoJ5~NhF)F#Rr##YB%8S-`H>yhfST5)}jmR-lMM!53q>X&7kJ?}x^b!?k{H)XF4 zbza=rJ+5?mUmRl{;|WZ9DV|U68vZ7A^Cz;nu;6=qcRQ6h=ooj>aIvH>_*vlha?LKy zk>wEEj5*GPZq~eem>XwT%4yza;g+es#(MUWznz!q{r(UAK!4pmlC_mH?Yq{evDzji zd-pD9@A(C+nTu23@%v5;i4LR=Z$U3#{wJEfnYvEPZ0T&7t_9zcdxEnoKYw}ut`NHI z7Y`@~)wz3nFzt)zFbuC@c=?-@sNPKk!3VvYsDgj?KwZwy^dbToMy*=qVW5r>hWlCi z75@+P^bI^gLCl=WN-?>&wJsWXZ}D)lLY{R%Aoek^WOJ~m5=(1qO)XtdBl7r%#4rR- ziROx-nCq#AI@NG1T5Ogiw<2G6W=@9>BFtT3kfc1NLym-GOK)b>|E(G6JFJ*%yOx9=dpJnoq+$ z((>N&*4{_ptD~d|_w9<-va+_;`lscU)k@z3-JR-28yRb!cUqsxC8P^doMEt1oZ+5h zzP@=Nsiuklt_Xu{W5m2x`3h!SR>9rhOZDQqD*MKl?GBv)M5Ku+3!2QS9PdJ1GAI$$82ZcrE1{*ZAFtkYapTnS_FlEnQ|34sIKm>47n+N{~ zx<6A8W*##CA14coV1!4O5}lcWPX0g5H2|iEGW&m8BycZ6H^6|^&51MOe^?^`3s@x5 z|1R?X@0<)|#FI5MF$swtEssx~yX!indm8^Sisprm`d5N=C2|(s3R+5N*f}`w{KsO@ zH6E`A(+D8HD{H$Bk)h9YBctxNQm`FB4&svz5^kQxIEIi3&rzU?73hJOmY!bK`J%-~ zciQJSZ(&Kx5aUOet7+FHMl4xL{maFcmN!+^@3yWEan8MQ!6zH>`pa}%I1LZSpY<_o zYwOx#$-IN0;u(JpHzqfh+u2C?3xaDSsX2%T&A+{CYv$g;r&Rz^hiTQrGks=MqFVLj#Lbk z3X>d&dDgFVt?N5UA|G{Kk7c=Q+%>oxt-Xu+9S?`C?RKV?K?baCQgMo`)%0lDj#9ge z_5p}rLf_C8N&TqL`GWYz5(FNT=SYeeiv?@Qsb})w#2zjX$g3VU@}(xOY-94gfKI9q z@zdQkswvjDFh2^((4dV~k&fow!o=yKubEO%Gh`tq+$TFX5Au@O-V4TAp9IC^o^PFT z>b+hQYhp-Iy*Zp_*{t~Bl(rIch=;ArDlg+hoyG75YM_=$0tfEy6m>lrGZvcoh*oOe zX7IUfT^~Nvk$?g|J&1dx7z}xnP!zrz9Of~>fX>qYM*sqZ-EkF#wcJa1GlcxuiI!^x zGnShMQE2we1g%|&0)pHnN(fM5KeY_Xy_KzIa zw<0HJXBR*tc8kU}$O#=tXlN8Wqv*kd3NKs|noV~Sxg?>Z-opl(r9VFjQj@XMzt-k% z@XtmUT;VVqkb&iOdkO9TK-QGQj7G%8BCCB_t(#yn6HG@Vr~Y@WD{M@7*TIVE`swu; zXVlGaO$=&4bm;h~qdT4T@Oe$mCh-&K|H^YgTR^K!2Cw2v&W`g8g;=bytmI=xA|XH? z9m)_`S?kJoK$Fa8tH@%~dp~s=Ua#T-xB=b&`f8Grd;5g(N~?_n$@HU4d5=jX`a1!` zo{dTSg&)naaYui5*U4?feQT@Uu;eF9dC~y(U)ac-HakO~+JvKY^^g=54@OuK>r^4Sna7;29CrG65WXJGro6 zpxZ*%n>4TgESYxmi1)MlBoRH(YXAo?8BLvrPR8=zkQqTjz5KD*!9TJ( z`5TVM)6;OFe$g;P&Z{qkEAwQ8@6YyJ&=@d~R<7AKOx5d2J*!(9yKP|foQjQ=wO2U( z$gbUWlW~8AD+%71;vdSVb;oYoFVL@~i;jg3tAbsxp|pMfJWvlFIs9|oF^U+KoJ=Id zl=`puMd!bm8wYF*8%-I(~yy6uR8otN9{2=I=t|t>C2GkDj%u z)1xMWLWBO;g`5jSB!v{4o~@PDsIrT-O!vQ{Np^)eo9X=&Hn-mW&9#O|mL7nquHL+9 zoc$b7n6Sf)jQ<;0yorn#>3Y7a$MVMt4Z7z3z{~=_V&Zd{+u`$gSH^g*vAw-c&in_o zUEoq_se{2qYxTv^+Zr3*MgynyY(ECfP1hmiU#>f%0-IHsm=2d$k2n!HmLcWi!(3H(JGt3r>}EkN z`XA|>#nFVc>4$E553Ah3EI0%Aa!^qLJyBGgqx@&q;@;N66Y}fZ zz@(zSx&MODk|t|it*E+uT>R(HQv-GUAy9!n6#Ul{Pz!XJ7ZvpZZ&EhvO*yww1t-(vK%D3binn*Vk8GOYhYANS+{$Yj5Oqhppb<7n-J6@h0rK- zh0s!Gb1`{4yVN8Lf(FqGD{!?f&q7 zq0Y^eyVg01!%03QthF^hH5KRF3pYH_cpzNFm@3Rr#mq~rsEm~G9ty@q0^9cRDT?cu!y+- zws9tc+D~)9vbuevI&qzW8>VzEYG`Sp+4_a|@k$UU9TZkEqW7Gd?%KoHeD<)dFJn;1 zanAboPf#N~2!!K&b^`=Z7~Y7}Z&Fm>EdtJ8(!(WRZqL%W%CR>)S|&dQ(OMl_x!+@| zqVJ=P=0jl@itljP)JRDODbXKF6r=+CL|W!)rB`#Z4SiaNI`QJdB<8o3rvh*@5zV)MY(JI*B-tUMQAp)MoYq$9BY*z_7CXj?DPbZyWxu z^27ghcZsUPkV3?6r))9pkuZnXF{q++(y7NY)O>mb**fI~I7ilj@QiBaz{hEBP+f#gYzdbTJGCl?}niYn`^KB%dhEi8PIRa;zDK(B&sbJGeyf}ww+ zrB!f#el}!jzcfBGozQCwC#3w)Mu?UJfnD8LZmz#9mX(dIuT^;~ETf&@p5EecAjxi) zp-z8i;g*T#TCjq;4diV}xL=w(WahPS=#^@VW>7J|*Rjv2hP*;Nmv__Uvfe(HlZoYo z>K#T;Xe}Al2%1$Sy{`0T`r37)-t4e%g3sbBp8~lZgm@kqSNjTBWBn}m|9ztoG(;0c z^1}Ey<)o@5m2_#4moG^hEQLP2($^X*Wfr-rkZ?8&uCe|m@)~;qEm!~r#bRU^Kyut#2g+wTWG>S{ z)Uxxh#yCaHIvPSb{0f&kXg!MCT!#GS!ymFb7&WXK%W-szX2Fe+wC{RrcV0V7H|p~) zM{%)YY|+$d4l4Jh2f=7<15<(r5Lbwr=JX)=ETp!=^f%N2Y1RucIQL5U>LIS*y`wqJ12zlKH@#yzMC1qg#Y-hbmu>W3hO1m+L?)?`8%zZAS9 zQ_U7K*MDfqb@?hsZ|u&?aqpTCYB_k51U_6q?tSa6r{9j!fgOZiy+6MwaF zvo!KeFArNDdF6s;UIXFUv(ip}SBLEI&=^qvcWp_MpNVKhM0e=Ko^NGsA#aLnHw8`W z(6V@(e)P^Jk!i-{^P_5Uyi~9=RQgc^8EdF+Jc(b|P_N*3B?qEbx{ut>!-RIL1~o?| zpTAaJoui5+apa*?^vqdz3u9QNr>Bj17kO)dZNfggE1d}b5@_rPuZp2(MO}CDy0dCf z$fEbar_YDgNnxb=tK+j8mS#(#^NvF!hx)g|%!^4VaZo2SlVUP6cnGkx;4MyY#h4d! zM)3miI58j5dDJH{q4ce9#R~fNq&EzN$F|!SgK>8kDErv#v>vlwDC8U@rhCOTA|l(7 z9c{f@-lPJR2ly+?^U9olpPB+)XLJos@^#}r))SsRcDiN8Ys}76`i6ySTOS;xiHeDH z=vb5Gs&~)_Y=|O>PqvK#VRu1-IErywk544IZQ~b0cCgmQV4RfRN}} zbqpsA_72SJSBsR6Kv3P=W7fDmmbWG?blGB$R}FQ`HJaEl4=eK;E9MVmT1SJJI^qU= zRq-4BFL>9eLrpzF%u31DW0USfy-FN<`=w=KRnsDd%PTia{-_-?gX4+zp}{&JZ_VOQ z;=Z|MFZ22Gv3{-Ld1*(KN=nuCm?R?BS@9FsJJRA*TM4cLyfH6dyH@WM{I=~ z{qJAAqZ6U4GKR)}jx`;A)m%;=q++im6G()t^!8umPpYD`s%5KZ@!K7!hxLHoB{a3x zW%INP5iK{e5Y=5!WZPV%weBjV_xpqrPZ-`4u`m7HjJx&7tRU2xay)}7Z9Fsq3=f#{ zpP=V1I|j;JKj&}-j74%PWoAM1V|RkV;q|IKrAt#@C?yPK@d`&O4QDvAw6`j8@6_;P zJDf#QT5pxS$C9cKI=1~-kzz7UxQ=DoV>MN9aXkn(PkA(KKJkzzUDA4^wD zohWE`FJ7T?Ahyd&@4^1-ajy1ao9 zS}a$0wp0VK{Z zE84GZeU4hH&9B;49h7gu_6zS(;|CX4X3z8>x8pNHj`pq^8rx+A>fScWISlrXQ{&RX z$m27l57o#mIE3oqo7Y;CJHk84bH%0Ys>X6Si6})JxYRub*{}QnXNeF{aNC?yOsLZ$ z4Y$IR5*;yXZ9V7Q^#Yl*;;M0Xwm)vMVTkesuA*CceOu2Ok1l7l#<0liiWDEEB0PC% z$CYEwaKVHQErpe$-0wKmVf53pfw2y*QJ>pSg{P}p1`N){cl*s@j+GNH*!;R!h24_=Z2vB!_M zJAJ1mb?p$}>xJBE?>X@5ruAJgDUeW+zalYdJ6tMS{zRinTtYj-Cv;Bj#@|2^eXR48 zg

Osb`Ux_qH(jNIQ2iSP2KGn4$8T=TFAqpU7SJJk{&|)!M^A6bUOW+Dx)p{jQ8Q zY*wq@4Gp2$oGZpcvf+qkH1#2>$J~j(=?WojxzV|NS%LR*XY&ZZiOSEbUkY8DbD#20 zQp{num{0sZb~<@3SQ+lLEBN)4F{$+zOC*M;>-n!9laSP$k=ONMt=&%OnHKXEp_~mf zu+Mq0)R8`g_)pOp%<9fwF+KGJ&A9snrF&-I2HESM6d5>;Olv&I_#Wz__GVBE=7v|% z4SFf(MJD@7uz@R<22Mfi_pZl$`+HrD z(2mVx?Ok;>T!($eGbB|0owS(o3R=U4cM+=wJvBrwTsNP)9xy=F1jp-J*G+mD_nhUm zNE%E}fJZpCB%{Wlt6E;xLSO_i_-YX<|c(lD^3+75j(T~QL``D;0b1h`vCj3_<0 z{#OT&h^{hRF6pZex1B2_vZc!Mx)F14d9>M+h9eAvv5*#n!);>;&wn%Vb18iW#rOH^eOeibyr_(m`kc%cG_fo(MCX2Q=GE`zUhcQr9rCr#ceexYOYdO6-9nOd$MT> z)iO)@O0@~bj?k^&(fG{XvUtg>#Z8?rKSAtQB}|K5F*N!MvSxTD8?)}gPy5DxrGW(( zWN`@~bpPK>{<|xUa{}VV^WsqirmTv|9t=0WXG|S3GHTn4)hh(jyp2X}_Yb%8PYD>K zwoPsj*SoVveGQTgD0zQ=g6Y}9L3xB`>v@6W&uJ>l`rP=Whb_`W$$Psly-7udsTe+l1;}t_ByW%d5+-lE2x(T6LTGdj8t_W-OtErjxbmCgDns%HaYv=S{5S#_ z$Buo4nCEJOde5nzMuVj9zg!zk>oq+Vu4zkb)8T%5(OCK(m5ND&RF7DevEHE8RNcmEim|SuG1Gp6??Q|JF=v>G|mK zXLp`m+Y&`JH?>w{aefzFU|wG1 zKX&6Dh=;*D-^-xq6X`F>Qf!`6B|{#(1sU%Q2*;(5jO2P3y_DKob1MhHJ!#uI0`1xZ zcKj9zRwOsCJEX=^4-!8?%J~|TKs^Pm7G*}Pt;b4uwz@*?CW&cQJ8SnXLN|_Y@9LU^ho{SDJOY(F7(LM<;{QaIWBa4#>_MM6(p|t5O3{5 z@hrFN_M1D6!mh1aCT~+3P8Af?VxE1NAXPfURJpXN#%x zWK-%zqn>0dOI0Lkl`gxw>4*tydPj1CUcTK7LGOpTPZad0D*Xit0mgJ|?^09)JU~=6 zp6e%1Qt3bdK54DzF+erBxbR9=+cB&)!5R%>l}@Rm_I0zuBWJAt6O4=RY<^BR_{dtX znjDGFVb?Mg2@6k~*>ZEZ?$42mi)?^Ft+8GcWG=1SbmvnciH+w^Q+U}XfKfqa%jyQj zpClN(M%y^Rccoscct_A|*W82<@h|^78P3IFi*)g~gUI=-_VAiaPjeWMsGGnlKZ?sH zG8NtSDqR;mWwij5VfN=TtUV@kEi)t=V}A542Fiv7r92AYfO!HNZLE8Xhk=I;JrW-) z#bfJaF)&y7n2g@JBO!sy5oh*A+V3#$2UzO#|+#p?fT4PKRtB zDdDaA`@}p49dpf#rorac>Ow1-bGmA33RVN>6r619%-*DOU-OS|OP%JPB1#qK$WNv} zZ?@C52u<#X$5!Naf(EWfYaIC$UdlGst}6iPx@LewgJYV|B$7oH(7q3nR^u*RDR-RV z$jx5@6WHq-E0DXsThL$v5~3~g6= zM-~rB1cdNP?i@JPZ?R-)EoMxZhty>`7bw|K-rj)e*9oNRdPm(VHGkc6jSl$Ce&;KF zXWLO6^&ojLT;bpvf!OGr{g5$%WWkez9Jvj``N-x$7jU@f9)PissiC?BYZU34Zzs^# zvZ?`_X9mA)TUP+2#%?{hfA_x?gpD0fE@g^3WULM{_AH~j`9k^>ETF%Wux+tHj+k13 zhd4qIrL2~`gdz7$tlz}?&7&kh1Za9wHF_R;?sEhb0@>&@m#~1jIv<1L8Y->&rQMD` zn;Y|#>fF?3`*S53D2pkV7@hA{60eTyou*bTaHvPdQM}G{Z0Kjo;CUUJWPig57C1-k zTT1o=P#}D_hwhnFK)%ZU)v;TJ+x}0%^q2P%2VT{0uyr_cS}`%QIl*njWkw2fQRcR8 z$MCqrG~LshvHM?$7*Jj|>CA80a=wW+>zjcYN8#cib74oV*DD)xRe!w36I^gnNH6gk z=p#LQu5szbpslgK3o5J%TMZ5mnX3D>lt0GMv&AQ)P1R+|F;D=~^7f1#dPQigoG|ir zk(*7Mmb3D?&Z^I1DQ28!{}wUs7fIt53s#CTlM1bpxfM~}Bx)uv?qWi3ov2>rmAz$? zxww7FihUV18mm$K&|(O~q>7l>Ca)w;td+@OJ*~1UheiYt+fn!K@?5lg)dQ)el@8q_ z-9~S4Bl3d5a--1?CfY_8I+=3idZ~0{-cqnnOK9%7dZ?*=`U=yG8S~8*J*GPIlJek^ z6Lt~(d*2&Idg&((S80ug!X!Fl*|d^47E5G@qrR%nyZCwEAl9_Ic?J|VsM!?GU0GW@H0(2l9vS!mEQi1m~XcPSq8AzoO zki`@@RPN7~FNNcf`@r@q)^q;IBGh$8y=l9S^Id)E6Up6$zx_%^RVT%6&(d%cy@$_Y zTR`%XIA6Z`gl($L;4rM(iigP#Co1zu--Ckh5b6A=C(1bcRCMVxJm2-T5WPl!ly&UK z3g11gDv&BOPaje-iQQb3_KTC{4Rlm=&Wd#l8;TH;TtwkWRxpY(92 z&7BqNgdzG<1EsmF$Lv-$O+>?nF;(A%QV}jNeq1Y<*Kn15Ev#3QgWbvLf-#P*<(&z* z9E?I;HlEo4sZDKTc&~cuF;UcYxYBvGyn0pEPOB7HXm+TgxN9t=ZA~*1D`S}7n!4*5 zT0E6U<`Rxr4=<%~im8-a1)A|5rkJ69>wHvW111HsQ#cy<1g!u zfTEIlLeB`S%gTEBI2k)iN#+K!uYY2#mdSYSdlndlars?7*(j%W2{{M;{*e%jVWVqx7#glf;{Q@*V?Q1D@+}zUWQC#!@k*Z0w)T8m|QwY;|fK(^ZTz;p*0;1X~zu956PUY#NvyYrDT8 zB@nNovG07%D_75E@EsqOYDWh%W%Er|t58{4c#u+PI&iRbn@fK;QxzJ>8Dxnelo@~H-2n+6)x7Z0mU%xM}^4hD_#^ZB`g)t{Bb zs~{ET4=kZ=CP138S*^6pf_+F=YZeKOQ5aq2^RBRsXrHM|6ts3*AIiL~+4t(2Z7l;T zoLJcxYDR>?GmVV8+~znHp=MUAxVu(-ytttyQo|KGooe>ueh&$&WGZ5`OL4p0x6tyk z|HwW|qe~QUdL+u>)?J#f)wmr-#;?^ah;|P8I?1oJYp`qC*6DWLDLjFrs8GDFt_dOg zm6@i-^JNufrfUOps}!T)JJ2dayZ+k{dh zRd7=wa!SMJI@XGnkCsRGF(d?~F%{Pk3serA3@astx4N6EI)(vW9Aov?Nr2nraZ;h{ z)~7GVLbI&8XqJ0a_X%a++Pa;gD!1NDCyrfB)2cVi-49}nVd`x2N*4I(=AgT_dwcXM z=5Lh?F;uXG_pO+waz^e%)ozSebfbHveZ8+qS(eN*NsRQ<^a|$(#_3#USNd)3J8;dk zGO%x_w^D zfYw=UV1J=rzZ6F8CW+6s+RoLph+(TJ2-vzD;DJqm@aHKu;Eu-^2)n$TPSrGt$rks(VvHF zT^F=Cq^!y+?@%>8S~VA&Tbx-PC+4|eJa7f_`1IcW17FwXoqP?z42^mQ1fNPY_Q>p; z%B)*x85)W)bGvXjqw9mv8b&xmzV^!N3KyeS7=ED|)wc=U&&VOMY*hy=iE`J#^qrMT zvSvVuu$sUR_Pw1zxdWSLWyu}Y!t+L6iJ$QAzM`Y5lus+qvsQSk?D_t!6JG+#d~Cpl zBSNKZA^W_!foV8qG~%-+oCL@c?&xY`?rIUB{Rr%h61dYm-yXX73&&UB_cfQiu5=*I z%j{Nu>!}sR&{zTu3H@$u)shm(6kZ*u?!*HFbIw6AUpxk7MeSg&v7kumGN`WIeO10wA|dSmViA%IW&Ql zqWe|^=1ImLw-47%fmAdSv2fZt&NzYN({i1A`X);|tIKMo9jR5Tt&+eZq%;ldC1TBn zSgS*y;+I8jbJ`CnN8#gzRP$%4aFEwP`WFT+67UwWz^7JU`6=jg2nyWdo zd5)N+4ZvBR|Jd57tn)DxXDJM~;iv(_3Vd)U8CB^&i*#d+!Z#p3Z^TgbiyD~eKXq0G zKka>y_eZovQfU!!O7~=11oVSY>gy{z+rf3aBRatv)>C+P-t*QI-cnUc3-ikhTZ5Cl ziqTmo(Q6fB*k5Vcua0ql{an{8i?NU$$plIt9mzNrWuMmb+s~#=V^RLjKSc9g4#()55HJac6O7$Zw;2hcH9)b6owrkz)$OJL2qRQN5ERVCD z#2Vr;xY}V{rS7deuensTyF^`S>u#gq$pPii9bgSh{9o_{=}=a0EN1K6d~Fbn%5F8e ztks&V(w#NnF<>jO4mb(~5lbYjv|r6)l!LuIQ@oyx4M#J6=T6dU0nur)YqFeMep}!E zc%GvzR9OO>0U6lDHTMP($O8!WTpD@Qp~=m_bf8YHU5f{Fa1Doo&(T;gQ2LtF^Ba1s zu9>dPd58C>*2-eSh=HCd|FlubO^^ksbKd{*W_@%$*l@C0TJX96>GXQB$(H%J)vCh1 zr_It@Af`vf3=08A)7=&q>H*mSmZ-UZkp%8pK>`qU@@Cq`;s9={@J};n45J=<)!GqY zwgnt67LFnLeQ)z=ioRHw87!JwNG5QW+}uU0PHm8q%|2p-lms~qek#m0>a!v&xQ~v@ zFS%kTiEZt&wvmp>%xB!{vytq1lkn}g?A8iN0#L&n$Vda6+`d&nIiG`n)%=xv0YseFz*g;iIg0E@1zJ2 z-Um>8J8m(acqyE704?`{IDaSkQ*gTM2T%m;|6(B+8*{Q8%%P?R!nw~I`%;1OLzFP( zKDa1f3DHzlw`8%w8CBctTqaP=4DY2d89KCXBfbehK@EZUgHm}y< z{t;HS=zAS@tfnz+3pTi=IJdDczDHi8zufP~-{=65=>b6TDz5dH0QGa~01$jKUvB~GZi&sz<{x8J; zH_=fzqi5?083yL*X>E#a1qMc75&CCbN12u`A9p<0o-~o~JDCuK9oD|9eSJ6l#a2s? zaxuwxP@2eGC4<{8VX4S617l3OtDeWU>vAjOIwRwnQf`ye4eU{3tJT;LmG@m@`T48w zofvMTXlDA8JDxqTB53aoiI-Dy1g{%} zMC3)LsInth5@4Rk18-p?tme~T|L+#_ncqneDyU&!k-dmn%R zeRmTeAb~5_hew1WqF5}ksWy94soy}Ke)awpoU^lYg!nIJyhww`2L2K2I$L@DsuRDp zBep7IFAsyG`tO}Q#)Iv;5g{i_r6*SnOHG1=^L9jWl)(7FaIE(V3R3FoxWJ#Yd}fH- zb#}XcXdE4tEhsD$Xio_DS#r5WuyQ~0{y~EA^uE(@?8f(f=S|<;vxzaGHD4irhM(?- zeKhAP(3z0ImSN>ETVB1+^Q9Dq1KuTeP)EF38uL26{*VxQj)HZSX&o4ADMa${RZvk z_|Mw^PUnC^*wD%M!Grw|>0zGR;KMo!i@(DUu^tF4sd?_POfvfRrxDwJ7uL1+&vcS- zb0d7%`TDcFWoFI82q+iSrG+J=(<8n}$rB9@3SH4(AFnZO821F}-#|J)-*oA0mvCC% z>^2?v+>o?raq#a64^HBTQ4u}Fu2AkDCjH@~f%9|4l;w||hnatV0x-pe1>R)NypUCp z?LE1YR;>>aEmQV<;&qYm)iR}S&=+g%+u(WaFlGQ+jrv(W6XLJaFS#TFM;T9m@aa>O z7;y~TfIiA>~~ zVv1~hWM1lDx(vy5A2|_^fZUNy`t0aDhhd}-inf8fwYz}K(cb9*g>26Uv`eslXE>f6`ni`q(eyh&o z`u9YR>HW1hv!|F1QKG|fx-Z2pai)n<2Kt*}`M<>DOn?a;8Y>v-l>V!iKVcErT>-Mi zU1ErKP+{>TZ^4J%c8@tbzf7>7wj~vwN+`>X7t~|W^Q4IO4f9;lo-|6xhD{EtA z>$TTFb&@f~7w=lIVBmp3Uy8#ipBn?3C)!`@@BpkQn$$Wg@*gUq!B$vey$ENXT#V8x zLj8j+%J}r;sI|MLlg-(LA|++**3Y`s;`((Pp=*NN zVb&{RU;MxHJG?TQwxEP!DR>8ql0d_IM#T9CXE*5OGwaVmuaS}3?hA}uEe_BYH`u(X z!ermOcONYq$#{4HC`>4F^uBc6Ncl(n!bVxw;|=diU~68Oikq^WpN_lD`e(NEVgbDc zrr(0Xpq36mgc4{#R{fKK2X89pc-Cg0W3TZ>nk6G^7NJ`SFo!lT0_)j*E+!ta2T6q@ zdwcW7c%Evrj%~;q z2jY$ap3jW2jxEZB0-%-%2<%N;dqr7a9=1IrX$|2o_3gVW(HXyfZF_mHwjA{2Bn}p!@yS z`{xa-i&oLQS17%Frh}?G98u%=W8}adLJ7B>h;uvAb=OpEZzF7GrcR#PNz-U0aXj@J zPp@SX3H`{7;?Hga*!Y)#jc<6JEAUs7rRBP}9rAA6sL7R6)8&+HK4eK}8^dAQ;za~Q z#Q-FiQ~Hg-AF}p{#KY6_K7pLOWR=|qyneQxJ^nFu!a8GLnA`8~<}m^V+(MHp@{d)L z?dI7OR?v}R#c-T6zTlx|@!N!`kq*K`714kuFl|ZuVa)x}Z|~Pvzmx0xvlT8Tr4-q{ zF1QzeCxL)N6{O#q3?V*owYw8N${PW`{i`|6-5-|lZk zl4v3KIz+ldbP8XyV}D8I-zJxPX1>=7E2z;)4UWZ&pu@vVyQaoN4O0xcS%%cL~J@ zXQB}R5HX`r1ne7R2xFEk;3Qf20Ya6U0A~ve`!9e!4Q$wKkskCB8PG=}q27PU{`wQ< zAl7C7ITdg)z0gO&3OfT&S^s7Sk6}d6r~N~=9tn&O^8lgur-I3J2iWssF zKmIh7si)2}9SO4|(NF|#rxV|7c3fBf80eEUNcUZlpg45Ix->xxe!o#bM3na9$B(ee z$BIL;=59!sUuf@DtqK<)H8~xfSn7ejyYLN4sfqQ?Y-6=tW9m9_A2hs57zEdkzWqX? zBt$34bz{EJOr1yG7N$p{p$|NYaJyMIy|dTi=cg8;C-~(?O((hv&GZc&dd{*`xIe2O z6&;m&ZUy8MjLcFkVc=h{e;LAML7>TIn+gwZMMpjW0!5Z^<$q95>={HjLt3ScpIoCx z`avI}@nk<{x_GH4+DkckJS(#Hv!zIr9WJq;4r$sJWl*XhCc*%`G3Zg?*ckRrzu4t7 zhi0#m`3AILDr9SGD>1W!=s8lhkz{s_JZG&1A=QkqnK&J zsmP;827e0ZGJc?GRRs{veEe|`Ojf_m;E3u;59wa;~4*8$Yrm+Xn-_25h4Z z17Qi~5Wh}gt8u!uRg(Bki(z7oG?sG`$7DQju6093Rv(>tf7ERa#m9Y)i%R^sdh^H& z3w1}WWAh`T8(#kz*1}eLI_Bfy7$yBSZQg?>RWq%?H|3T6Gi&aG1%Dn<)m)5qnaEn> z*U(5;e5@l~M;k1eYd3|gH_%D5zDVvGt{n#xI(57TIS7GJCs~E!)7me|xg#AxBRfqf z;2QKL9rYloIZM}U8>yuNluen`lTe6tyosqvz!S9f5~jY+k6{TmLLn)0aD_8Jz>JgzW%{e=Brs*k-5+im$T^U5s&pUkj#EhPmT|I zVN#OpGct0*@0Xs7_^wA!>h>2uY<@YR#Z6B9&Rd=VfnHf(9k#Oy%osTzaWk4yI5$^pGzxHv?Yx5^b$H)2N|mrU zTBZ8)pKhzDQ;(0QGmO-k)>dUk*<@e+xYqH$Unm5^;zfzczFQ`8U6$x%19~>l@cD- zFTAA_eJlM4zo}W~#zy;(>Zvm{vmOL*vjv02$Z;e-p0s4VUQUV>ieFddgXL`PIXs1I!=jb-Bna@@SQe$Aj8(eoipn5A-h&s!ziGrk{PL1dNWc9YP z$4_tkj{B7K$W$#xf4;5*^%pw}KU6XS-{!SpDM#r$i!`?n{8HqBW-~L5b?jg6ui4mP zw6MT-pAE!)O~%q=QL-yJiNPtRMfH-463G>R)VSnlEKGCo1MZVS8#RSYDb&X|j)N#X zNM__Dg1%t-W@@-*osx4=jPMB z^cD^y9KW9*mXKl(_uZ^&WM1r6J~zhqQm4Q*<|xrEUfRKDSHyx8yhd!vmZCUDk>r%a z$2C9X8YN9;>b91Te;*c9hwz{KD7Y`rXyEGo#b_7X#dmHG ziMFl5eMsHdwV-QOLwt<>i7L;@9!<4Q@ymuPv z8!FD`KEc(jlD-I%rb0@fSFZj>CGlG=`c}S&l$aV4x#wu*V!dO5mW+VsjQDx0~Ls6H}mh`5}e?R)*3l(vAP~8w-FWTvo=;E zD2JlJ!iKyNklWyR?%N6iSu{4b9-uu^2LkW9gAC_rXq1l`ba?C8n3c-JOR|$ZusDkg zIaHEar$J(NxtZa2CQW3TMXz4FzRg0q)nOmxL_(slZM8$>-xUh#Zjb#Ak}8`KcrN3r z^;IkP@auREUtZpJh(VZKXM1tTGa5Oo6vn=Ms#hki;aF<@#OX?Rig;9=HI?20XQmxN zMp*K^&V{-fHzszhksapB>gUqKh&9j$p?*!?onQ?{<&^Z}wz7=!&>ISPkSZ|nOKZ_r~&Dmz)4{p%;RmgViA5Hr7w_RKfQnULaS;HRxTMOzCA z(u*A)h?us3Kdl+A6!rRUbnbLEr_Qo!W2G+YCOwbZy9s9FcT#*z(n0E@b;W{b$OSwb zGz=s_n`69B3`weZJf3og2k7$6o(;K_w!-5US-L2OpIX}1LA_h1L#ds?=T4^|=R}{A zC%VEo4~o7XIJnpbvK;~s0uf}ArS8az$7 zyB@vCQBxDa`_5#{u*G>~8mRSW(fx|ZB0nO>V7X|s?c5+$sFbCR9Ic8-3awWGECk*z9W8~jl9WAF*D&t?PCYy6=8Y)l`jXU4V+1;)?Ueph0xoK zsOd+TzS~Z{RLfR&NtF$B!vG)kLVX+Md8^RK7GetyUrPK+ER`*p}0p`h?;_sTS@?|Ra z>kgj<+K)%asrWW}5Wz%Li0Bavg7a*vSx{9wkt>0+h6C(MsSGT51Sb=T^Y!yCa5b)+ z=&9FXW}QO)9_d>6jQhHYRC+gZRo63mzrc!V|Rb<@|yU-H5uGXe>P#RYMd7IJ$RIR z|9fkrMQ|@N(uyc$m#fEABC&JAv=gcs$QwUbxsSV9D;2fZcW9_3<&N=C1jeQE^Z@TQ zJiG;F;&XGdtvm193O!-^ewmL02|LSnKbsquAogOH)mT+^ROgWz^K^ASQ1$ zozzgNRhj1eiZP%RI#QAy$1d!Fh_>F<-FcV{5;xf+;_{+Gp@qL*3-u&%mLF8~+E<}q zdyD?DrfFH!yv7fN>KW1I_f4Z+)lo>$jC-IDttZ0Q( zHh7XKG6gItz<-*W7@ia|Gdep+YD=oju^j)F zPo=hRfJrCC#kZi-as8-HqshA#L~C??wIjwWX;BLbnK}@pG@nyBeAI3x-CtHjHsgN+ z1z zHcC*B?Tu$d7^-`lVUZXg5t}1WGY8U)5wt$Mn)HZL5sKDb7saAgJy>!&(lyy5hs+u- z(7|7K2KBz~4fj(1KDI-Z=PeyJ;Yyl>dAi1hK4^bAb&9?=_&VOiHYdmJF?}<%k*ZF1$Zi%$qvVD z-^RjB`^WN=)_#M6ISC#{{+oa!`8WN2NtzknSegy zVgyr6*=Bf%F2=$aC+UgpJt6f*`*$aAHoUwo)q*-3T7%!75wj1K^b~AlPDl!AuRbmF zd#zc0G?g|j^Lv*k7^D@Jg*U3{?!Xi)qUwu^H)rs@)lF0^)hUB`TW-3mcGdVr+7SdA zPBuAXsLK{vA$Src=xR+AtANwT3bC|*TMbP`T|*#fSw49gqY(XPF{nW+H8VByds^)# z--^<10#KBlM1-!dugu1ZwQrk$5=f)&(c$OMm(PPcxqbPw@O%m9o2zJ|&*q}v1w{89 zGhd>QhGg@Smz-qtJ9FfY+bRA#A_I@@w@!{;th%qJSN+Oql$^lAQ9Yh~=EaB+=!`ta zS^Ps8RGjLgD#sE!Dfnq{d`w5$OK8_aNmYBE&K{8*v(C~3TNiJxQ&cEqKI7*7YEWI3 zl*?%@#mA##SE%@bvZ_!jV_R20rL)RSf0p*@#Ww5ZP_#;K=`MH99`@)_?~~6Ai9g~E zk7hHb_vPy(wxmSpT4_R|T|n8EEQ{xM>wsX8|8jR!q^N0lj=$9<*LW}D^Mxb&ve^IZ z9TaZkO%_KSBEGRSa4DB5T3c-r4x3J`i>HRt|H)-JKZgtMSC+eT#(c{5=TvsD z=aa{-uH(1byQqrmj%ZR#?%Nh9cT)k#~t*4MW zuWuSG=gFI^B3a8D3l(egSe&2?~!(mUL_Cn2=h)WT(cln#1XM!%T~GLdyGOF9(sTz%A6ST!U>rIg(wp73!xg0+|B1}sWtDY-h0F(HzlK(pRAuD|ThB?%kP znlpO}LV|?odobgq@8~KEK+YbF}%OeNE^z^Rb%G0!`CW*j+Qxd_lizaPZA>vR|XQZjo z0r+?Q;PI~BHs|czbZm#!VMdoGWEwb~Jxvv{Iaj)Ajrey+o?CAg%k;;R#=DoQOJ1#L zHYR>}?OCgnOCteGw`=bL9eSPHnxbdreh;zx2QqIC=a$yv<=obr%4vVbO^np6P2gxQ zuI@$zYp)`enos>Xjz&3GmnXa`f0U&Y%B@_{z22ySNQ_cVWBVM5lip@t2FTPY0W$^ zhd@PQd-D3cFvd0ESbD$8G<{1ER$0iRO6Ajfq6;kX`5=IBNKQYZ7xAE@amI>&SFcwWjNM(YCdn`JTy2ULWCJO-@sdxOG62w^ag#R>dOEKl#Js3DY``vja9$g(Oz@Xui_fIwwBn1qmhfZW$LGk(Yr8~HZo za&YP9hbsFtG?}qg~lHmsOc7N zMv{d>1+N;0MVJ?}ROLl`{RrFMEdEqfgV>gyylkMR_Oqzme$i+bP`q2I8GrRnH%{S?deOV`* zw9cf?LC*))Q;@GJO3nJuNoqloJxvvA%Z<$$rPKy*=@QJ(?CC|Xtt=yY!Xm;JG)BF*rg$|Ux7EBB@^~rV9P*ak$%!!}pCJCr4uyON zpYT!mW^`O>p2fjrF{KxA_u@UG0nIRh1yJ`yCrH z#0w`gf4*veEKlQEMX}^}oZx$~bj&j!=080aiX0VcNaEtX`C} zKn{L6)%yL@*soJXlWx%{dC=K0J%;?`o^X_)Q8)LY>_MFC)o{JlS}+(vo&A!OH)3t~ zGda@wK3Gzq3zu%1OHeoj7Ni=&fXtK?Zg?Elv;OJ^&u5UT^_Yt#*rjOigRRdFL3geC zvAA8Z)8`_Q34cvtluZ!~X6XQyN@w6+^~9e-Yev&q(fG%DsgrKSA2Q`_nM78G0<^`){guSKq! zu;lXv>2z`XfO5Wpnq21(z?GWsGA6l~coyq$>Pl!0ubsCj+nVfDYr>i)$j=sXj_n2S z4rewpT|X9orY0{o5Rj_~vTf8!A*@swTzXsTiQ2xV(&?n@$apr9^s;_L(C8P5-1L@` z5_(^74BxM(!M)0G{Z0y$Pmx&YmA29NKQ|d`Xj(`%@<#cH7WR6}^m=_2tt43R{CU`S z{s-ymYIgV?xeq$IWJRWCSD&ZJEp1VE_wNCeoUXfkxvmT@L-hGn_e#r%&ooNgMm)MH zYZHt3C748sCv4-jChoN?a>8WC?v_rLIp2^F{5=kf7%h)S^g5faIXU=(pCRGcFr2@<<7&cyU7z$m0DW8gfhV5tl%?SHq;+kKU ztkwk6vJi!zq~sj(a^fmq{sP&Ne#)VwmUCZJl+rH%(c@dV-3WRybA+PQb#NtuQ1B8I ze%LT^{JN*aMn4(=)|*-|1;`)<1ii$b12%IuKMJ z1q#y9+F0cyf`hG+UV$}-TuE;E*)rnxSy=ffBZ-V1%J_@$p=m^9c|8Sj)4^u`D)_{- z!%!zIDsHZ^Wt0Je#!)rr&)*lgH{!|`R4xvj_;K)y-vJ$IBpy{MI7V?ZpyoRLZ1B0h zmU_5Rb8~V%Qr_~s5j=S#Njn)?(UFI|)5z;=g?4f;5hobEOtQ^WQRX18 zjgj5AH zx5rOSA9|QLBOJ`JLGt$1>2I(eN7DXzWukrSj35lLWTmYZye12%6K6*gDwEx|q)I!n_Kmv&Lz9g)^0o|7La4XAb%afU zGQMtlCs#*-5jk!ft78%ZoK{2;dp};t94|A1RwlSL8CTFwK}ex#nSbEqmqTy_}l;-e!t*soL!cJO4CpOX+84 zar48zicJ#7{K+5%vK-|$icg9t>Wq-=5YJC3mhu(nwb&35w#m;uv<^a))AWu^CrJbf z5+aN)`I4p;Mjdbb>#rI%N+*O9aWp`5Egfgm28QNmzX&j1hW0S?Yi)MUpvcTwG@ZIjZ=(inoi+tFE71-enB=`>P&J=38#~#WwXTCtr^}DMf1iQS#6`ij zSu1x_f?dVL;gVt9JP*5nfGq%Ar=;|A*OKq%!L)}<0=bMimjZoqCxCUL45R^2I9v*J z37z+@7F!+_V6??%`2Ssq41m+gvit|xW9A4D-|d$F5AX+w+T}2?+}n-!$uLs~vcgCA zcqOHOI+Xv9;FSXGyTkYA$iyw#p2}XYNM&{c;8umGCE@cGA$JUzJTEZeChK`G*nuad z#K)%v@?5e{X889EdEZ_vIh)GTU@N>OB^84mFfQOJa2cyxE*PPC&;uwf$Bs*GWj;!- zID;2Lb40uhmH9jlBlRfEH1M&Z0$j8?-^4N z{v5RL;L>T@E(&VF)&h_=z~M_sx(7VG@-;W|FcQPGt+Knxf1^@3-y?Pp-Kp!at14F&u?!0x{j zzkGhlDJmSHaIJTQ?uJK=(v+1-_AA)O!R+6NmoR@Udd+P5^_bnC{POA3{)0qGL!0$< z_jXT0ejhoYygbt8UIJ6+IC+?Ik2#F$Jn$xn9uqxyCEfMofr=+2){6SsauSD=+>#@_ zNJaEkj2}#21Om%^B6YhHb2xy2cwk!rJgbJl+EWY3>9EDEUJ&v*$_!y-lq>bM&6dR!3a+EZY zUE%SZQL#}}ROE@JKYe46aJu)hh?TYBN%?_1l@1HE-!;7Ajy+~gvqsDfO+9O1S z8({iFm=$Q_)?fqB;V#9cix=o*f|&^>;BD4f$DHqlDvS*q>z)oZcUkU6_gqJXalMnp z4HfnqP~egikIauji#Bt6L;6kpk$mo}Qg<%BrIRL*Vg!c}cf5*3mXLFwAJ6GEH1k zQt*>dif_eY*Kp(_r+Q8te$yu?NkR1hT3D1Q*~KuFSy=&y zPfV=uZazb0Nn9qlcTI$7G(%Klc_T(^X`dqFednGGL-5!Ky$jXYq6chfIShu0C%($| zAa<=UW&wZ@Qd5w~?JREqkgwUrv`8*%KEi3HIOWs-1nO zx|;)t(I0MhcDAIX?0bxHE6hZ8#oj!se|uWB4xR6?fNLM`o8zXE{8^k?rC6Pz04VLn zhgHU25-}v6Xr3e(_cgKsDiZ(TP(FGP*(Xf3W;Sf}PIkCLUHHBL_JArD;m%wRNX`XYj=rx`ZZ|(a!MDsA9Hf3pz1@k;=D4=x_k37h=m@@u;l-9;_psR&a-y72qU-x; z#?b*$u+jpLG!FlH7Z2BG$P zmg83)_P-U+d2&SRx0jTm3p|5`v6&`|ykn;KV1_k=B|G(Ah0O*5!>J%5!+_Z+Oyq;K zACp?7sE&fIILlTRpL=~dzpBt3crlfW^Q8TEbEZA{_jx0|Ao+SmO34D@ebJ0_2`t7g z4?On!35Bl_@Dq_5G76s;jkS#4oL?^P%(od?T9zB9vXoUwNqBXohgJwueV~%IOL8=& z2myk#l{=zu{2whKTgwu#T{7anM5pUT<@ar z$FNxNEC;@9@*de%Kv{KOs%mz9*aK$DvC>dNMF7Su05t@l5C){~C40mbH@l&()r_C> zJmy~9ywI_>Xqlh%U1jcwg&e)yvj0bkDFgN39#W_K7wqWk+DFz(+pkgoQf&KFy2aW-g3${4J-RE z*47G1DHb(%FItyFL^!nuRlo(t@EIjI<Yr5@oa>$UT zDrbWI+F^~{gG$2FFS`%tZGJc(^|=&=d^0nW#o;&CkgMGrQRkr$WHbS5yAqMAJ|MZp z;eeqKT+|<3f8GbVb|7^0WC7!bviJPZgQKlSn*ksoZ+*__cL{9;?iC8i&z}X3RtV8W z`Q%mlaJQH?3^yTziC^R<{RW!764oAPHP2kB|1K@S4wM%_Js-g3iJIdT4Urc}eA&6F zcONzP;cML8)meAqMN~zf7@C;O4-ex!OdiAq;33(*C>?S?Fe}+JFv_A`Wda_98gd&O zHVs9>)ty$@?&V<~dg=&EaA6kMgqfQ0{nxMAV-3HsN~|dBKZ7NCeX^ zXjfrk55H1DAMB!?u>B6}AuTK53l!8(jq<3^-??c`B`1$!jskG1vx3cZvu}Xf2JN(^ ziV;FT_@4=eB*Y-8=eCorpH^8*FO5FF{0CG~gfn6U?&3WaID-(xXQilyhAYz#;XG)( zUQ$4XI9!6t_7%JTdsn0tbj9>iPy_HOZi?8ny!Ey(eBq)I(0km=g$e$0OfTZ=zz@t9 z!#RQNwOM%uh1Mb6z*Yrtfh?}6B}+b-t*Y-5(Q!&SR!ARs{Iv#t!m#FcU}wZ`{)_%} z&9%cuH!CLH<94Z1h2jjFf>w`Blf~Tm0V3N|40xESu0Xhrh2Yc_^*BYSC zz_$&9u_1#GwE9d;wokg7YyI=NiVPU8}LWQ4PZ zy3hbA7<~rQX}y=?Q#4Gn_&QTzo0e!t5sLd2a&L^O>=S}ddvAQ+)|mY>pu&vBVV_{; zVot`@A&NxFvIG8DuGq$gkZIv@JTl_QjJs49#L*1G9_QwYPXa$_w=cyzN*1-Jb-qK? zQ;Mp5a6}F10mxt`X**sav`KW3_4=&EB0}5o9OURp-~%*_k`ob_kR;*c5;C2lZtgEv zq~W)c)zNu{8lv-Humz}rE(~D-)2+6~dGZIs^p8tca z?~~1c`L=)jF)1t=?Gbjv{jY!d*YY?u*pi7iqk8u?|6uw5`6`bNG(;P%Td($fcOhC8|P|H08=YRXlzxaeC11ynLCW!uP zEC0!od-n*14fhCc#OK3)`yYP-gQ$QdxkZuPe;x3@@#CM!?FO3;BR&41{@+>l&k{)h zJD;XDE@SaG!2KsnU}vWk1m+Z!V!WUX|IUg3cu$!NTT=2XuliqS{I74~{{K{$uYV9m YpiP$&cz{dO2>l zm<`?LEhKv!LS@YMf03?GW`=U;bQ_x~qu9FIz@gh=pn#DVfi7wN(jPCQ&d&Y`>X-h5 zi<=KNMfm;KZ2!IV^@k51uV4t#p^T|IEj$TX5!Vo)j^qWxUZF!}iP^FTqAHa6rwtf+*7GMnHG3DA$;-b8b*+umA;-)h@*W2kO%QCPN7CDWwvuRkyi zJ|ujz{*!@jHIpx9;aWuHquw#E@s1iN3B^9~HS5nt~x-sY$6g~7!4P++V2jWcM?6sa(D1pZ^81E=*2JmU$h!#PY$1^dqh?#KK zi}XelRekzpgnO(dM#6{@0?+WL{Pv@TdC{+CdMWNC)*5;GHHjZbnF0o$brnK0gk&xh z-btuaOc<3|2ySo{$Daaz9>KR!{#q#ChOrm>7M`aThmTYEE#e)`Ec;831?^bU+>sRV zeY*abcY|Hnrz>mkPu6$h8k1a2zPXChxyVIwka^OE!dYXWC5b%OB1%Hx@XP;En2Wl^ zASDKkFD;6I0VVat)b7n#Ybb&4x(M_YHWhU2vq4lM0$g9u{0ENjA9P7YuUpOUTO*l{ zaMnmLpet6JJoOV?d$p)sVYsqInL0D0X*LYs@CxQUcAUG|2- zhDZfChLdZbYav7(r~1BG=$HC<@a`ZP(VtP_n}*#}1M=f++8Q|i$kZMM1N?ILA_TVb zcy(rHc>a=B@xr~n)?K1AJbnyCyba8|4sx~4cgix!jyaBbr)Hb#Y5MMIhU?{dZ%w5o z3EKteP`ydv?XSW3u4!d^dNrA#d5U9n=h)T<*~Q$1-Q3*lwd_y{LECkr z**w(P@};O=ef2%uK`nH3uxM5ZVPt{3N*D>`AB0MRLe)n-wTC8a#fS69U_+1yaE(Qy z>v)N}%9rSGp^uk@jv~sgjy&ZTrO!A6ec^kzf{_n>zJl`_ktM*?4t61+Fb}p7ZgEBM zw>U;%;0Okvp>GnEYAEcQzboavG!j-=Csm*H%Q(MKOkNIDjZhrw!cS4X&fj7F;PM84 z6Jw!b?j_y891Cj{70M)dE9s5D&SYmdLId46B@f*d= z#8F~%;%h8$8&qyII~(T!=4tzk`l|&093vI$=c<8U^f%RURT0xqxr(0cwF|9De2eC^ zm#XvcIEMQcvc2YbWODV!6J0kdy{&XL=E&xj(eDi#)oTn-B$9SlF$4pm%vdF{8Ohgg zU!z{CAg&62k~YQwg{IlD(qVIkafbDWri3AeKI_CYj+OXX>Lm?` z0!*DsQys@A-DJ6InQO^nnQ6&jX;=+!No(mbsgPe?Aoy;N+Uiqruh51$N4h{jqkm(( zwp8=m1By%KDh6&G;kN>`@f_(YZ+~Qc%UQ^4{Gg`BqjsrEp2wn+o~K*jt#s#qO?@8o zp0q&li+rl|mv@QpT;37qyX4ziy!y(;9Gf84pUs^2VMJk^Y|NeOH<1Dn$+PBe?I?~Y z%P7?-wXeqVjPeOv#)B|}Sc4s3)wmj}dNrpst(i-vNQya%jWlbk+^crxva7PI9jg*8 z4kw%Q@3cd{8x><`bxdn~uN2>|Qs5`e)*6}pNajW9_2Q1HNjx#%D!YGlaDsViv2_0X zd~sg(c5Y%mk4~xFVVy29tdTnB>qzTvly1sy`R+V}?hf@1xQ>M9g+x<)`vLcMcOqVX z-k}2 z45Lhmz-;w~6GqmCB&JO4OZuL3b^U<`SmtpS6;m65GI!;4X@1W+A#di&u zCU6Y1H4H`$v=45W&JTVaxE=rvU=QFYk+b>eiW({lY2Nm@8x=~dm z$s7)oy{FVId=30&{D&W#dES~$Bq^i5nT&E@H#}^2WN`d>@YeB}Q|g}P-u2vIoBT>m z7r2Ih(W~gj@bb+iD_I(uO3cd`1x4B6_rvmOwT&N}3>y>NbdKm;5#5H*OD^w!udl{$ zJN9m~>Pam#EjKj}OU*~(MK1ByFAgun?A0!o4yNy<@3suKFt;-K5-X7%y&j>8C9h*V zBJ7X;(l^)Rj=MoZ^Nf$^%n#g=HfV#??cd=a;h!S*Q4C9rJ6HgX3w;o&7!CZ~5j}-) z3PS-Y21yUsJHlvS)&Aw{MI(Wp0WwEAe&o~F^o{(@?^`6;d!dz` zX1QPGQiZA|*C-f1S8ZNzl=OoW-blOjVa(EKfYMlQf3#55etDqr`FxnJm$1ywY(KZU zGdJEfUOG^gUjDJW(tpHX&vcE`jg#0cdGM?7-l+A|KG-pq*TRu#TXR6?RjrZkOrzi_ z!)fK#LvyQJ+b;Ye9vyR$mT{x`Qr1O!yLSQ81pQ~cCC&W?*F7xHFmsu4mFXPf1aIaw ze4UrhEG!K7jghtcW5e0rEO$SB+^$b@amg5KifBr3N*jN^)Spb7oGV0Ctt};N$aQCS z1dYzQ?By0UsIRG3I0>3Gd3tGC7+Zi5`kyiKcrMW|xMnlu@3+!r%gge3%?vCr)YIC@ zPO7dKcWDWOut5z?g4P~RKb_qAp07pUk}A5;9SA%`Ota!Ppt;~4URP)}Hh>iO(>QU{ zaB)4NE=uwx7&pJ9-q0ObEs;02)ch*9yn*iaTMJmpxLt|Rd*{>SM!%-CZcy6sL8>U) zn(wW!=KHAk!}$j#m{V1gbkj8?#EwPfL$wFLZ53L;B|L?!{3R})UC6(}Bwt)B;(gn< zh<)`j_1EjkrPn#fOFPGTrRjt&xjWXKv#8r*!>K~Ud_E`s%R$!>LijN{C-v_gXV)Fh zaW5IAd|V#x%;TlroqrfEtR7q%bYjldQm8_xN~_271TQ!Zo%i!(*;Fma)w$hFb!vfX z|J0^0_cfnh+uScUdz>C%AK(j)xGSBE{5JSQ?(9QiernEtPk%M~rN=(zu=;dPPw122 zpM~<@3}A~s&T%u`VV$&Tmtbe^mZYPs^_&e8J+;;JIUgH$lbhXMJwG3v9kS)cW6kUO zhrx1N^=-axgKmaWuF6xcl5E2zY>O zC#~TK1%*co`9jO6&>R8%Pg}fK|EMl6$7f^=(9}Os6 zLDn{oe6E62k8kh+*O14oR1}Y|e6$jzQkPev5Vv(Oq2Oj=V_~BbLZP6b5O6RyU7B<#@ z^$mauK%Vj`S-6^5Ye-mt0Ga_~2ywD;3p~F6zqS0&i2nwu{y&iHoUi{E(0^8aZEowL~xrK^IP+?La$5OO? z<7`MtZJ0H1cR!J)o*h$9P;L8gk>Ct2U_Mj@^?lgOs4mu-r!FoMh%*(C;T#_yx8UR9 z=j3vHPVp)9o8!VEKRUW6jR+Rh@yX>O!g7blgWW^RO|Q#=%kbS$c{7dFZJB=a)p_zWD}fdSU$6j()+>OuYFC`_T;(1NuLHVwDPqeUU={^G71t zH*k*L#g~N@hKk}pey}Xh3IEF|7=HBFu}Z|7&qp>T|I6G(#EOMr|H~*;7$z`Sme~u? z^^N}xW$FA$v;Q^LZ0IJ|V*)kb8$15ky1^|NL{=T6lem2gsEzG}bK_7xN;Ag9DSJ zXqw5^mIfaA-HYY);o)C3pR1}?4%~5`IO&&0y@<>ZV3z!&_aynxQfC%P}#QJ2ak?{mXSK z34K?)5d`;ocDz;BKqJgZMK(HQA@beB%F$1skgDmLS*SC)zqh>R)KRLRc>8in{XUMP zf1t1W^Thkx@9<=l1J|do8WZA(;&g}|umo}cB1(_BqRrJcH@a#7Cv;1AyiL769D;~g z)Q~evRH9vWQEy4SzZan*>!k67?mSj&5)FS#D_(-yO#3Dyb8VTqrvMfo9Wr6I$iO7s zU-d7SXziiNCW(ktw`0QMd$R*JuT0prno{{-AqZkthkBjnL@djLnNuU34}Udr_OV|_ z-7v?BNArG7rJq4N)Ot=^_CvSzXQ71pqDL(jd5shq6+KH~TIw;cRb2UFiHMO^LrW*> z*~LZRx&vR{<4dh*$VwT^CF&s5#1Aw6Ygoo(TOMz~Xo}g3e+>#nE;1UWU*K%@BD4II z<~x%pH5N_uZu+?u^Y_~I0zXXlBKJucHEY`6PJ>P~_Wo#Sbkn|>`>P6oM4+8tYDuj- zS=D($`!mC2PbEk+>nx@~hVFa?U9!I(E<_itly9;oO%x~dSHeO?sIUpz-inw`bL$mW z?QJV+d3b@ww5VvRl~U4@O}ZFWXTwQ7*sPkwR1v~%YxORl=*JcYrAFXX%dG*PjaPNN zt{b*goReXFGBkl-po*s|PEkRVUg)!HlY3FsY~5DDLFe^+KmQuMP8ev@n6a#4>Fpny5F>JQ}s%aV?X%w9tn0aQP1^X|1MSSUv1D|D{YTUkWjJZd6>=Yd6Vb9wqFF z=*CEF@!ZrdejoJZRLW1iWmANOIq;`G{6mp$q>;Rfm)$gKF{D*XHB;Zui{&*l6TB4* z*{yV%oe~?(jrLjdzEVF*1cnAoHoeHysNJGM}QZQ3@g!ik> zMYDQ7Gm86Id?dRR;NbnU`BIIJ97kO(YQjvKVxBjEiGO0~zDc#`ceKq!JApj*zHy)Vi{UXw@lOPzm}c`;EDzI!q3Gnt5= zlanWf+swl9FU|DTsD>3>bl%t&b{L)mEQh*f+8h<66+d$O zEZ?bEg9BpPF7y*kwpgSKqNfJKpX_<-N92ibysOPhI)hQ;f)Y1R#(coHHI9q8$nX+Y zRa=)mAiJvYuR746`*BYU*14Z$Od49p$!Vz|S2HmDsM+gZX1f;686K9-^`2__r|T-@ zkFTcYf7I$#*31=HkY|%VDM+qjhT$}9jpe0o{}5}^z3AM#za}{@R76iL??dYC0E>5{ zaM-~d)6c-UiT567Jom}?n6jeI#sA0-hF>3C@CxkttgLWNZeb!_%MZ1u$sZ)QUQ1of zzD24oNVXrQcY=AOp&uMA8;5{3S6<9~ACI2G2>-Y1nmC1guM-#VWe)s}*~TAkzd!sV zG43$=45lGI7hZsEqTJCydZbfeKx^)cv>>IMjLg8`|G|O*Nnd)c2C+xi%OKnZ`!eS{ zw&mp=OW@o>V<%X7G5Igi2B7`KS*7z+VI%p1Adlo^e8s>8g6Il=(sci>aL|}Y82Vr| zS ze&_PnL+P zYcXcbClC+>q`_x`4*xLnOQip5WEWGEUi%BNM5>Oue!BKN=kJH-$Za9jEOog*M^ zYvF)1UAN1^_16=53vtnrJ-@RsW^${1cOrd~4%Zhzze^rUV4&Ynh{tR6(`Dj`$$sjT zK%1&Nl^huGr|HW0iXT}b(hg8P#ZISy7@$`uB?Kg&a{}k7yChlw#I(WGhKMfH+2-{w z(-RrP6agoA?Xvtp2_Tp|1d*7g5~e4EE)3juE9wmvFaV5S zd+~0j0+NUo@sHs7$pAwuh-KkJ^hX~;yHw84e4n0RV1PkVT2uSA;+0ZXNQ>s5*qFo# z%y%0tM}Y={d^`jsP~z``8rn(&G`^seDZ;0jpi}kPwRzIZb}3-;S2McwY`IP>rXaDL3j;11}w91=P)T}ID6tsfYSkhZsqfj>wAb%9gOdz!rTYk=z5C9+Q900=u^AwXzO z!CxQOAu5bY2#EFcfP4o)w`WqRl8=^y;uxZ{w?b2-04@?S03yH3r@uT=e=P*Kz1k_% zsD3X7E-Krhcp@VW4KP7uew|uCYBAV>5vhYU@c{(@#4XeaxLvP1%^m-UTs@xo-Rp^p z60LGThzSp&561sukuar6AQwkuiaFoUXXqD3=>~SgcK1W( zhB3*)gdH+cQZspVrj`YO?+|b~cqepPxr+qor!gRu+=T8Lm-GN}m|^S=hMC}g+T@x=}#4GWae5pU0Q_(U>l|P@F z95cqTK*dYc7#-V8h}R>)kZoh8|Ls&;tv+7e-|VA2>!8(al4nM>3=fvKJ=N~Op!S&4 z%AY>j=V=-?k2GAp-6u&&Pu|R;bwLV^^E}*IT)*Q%DKj$4*5}Y?=29!ZALH#G7_6;u zB4+kc-T{_3rD6f^UOu9d^`=3|5$L0akM>D~}0^Zv#o0_vCFnh1*W1F~{$W-3NIIU^0!=Xqg zU3TPiL5@bs@MtIPumR@stV%cP#mVI7{GOg&(9gSUvCwg4`k}s_1zMlsDXVnOicjg6U6Q|jGs5WW|p zy%5S59$UXi&7mx_tqpZ(|5pfB5voNsjgqq6lJhAsq0`HJt!rbeF~z$R%EZ6H7m=H| zS}wEKA?a0dCttj^1~~MgZm!esKAk%`t9M=8Sl(QomYO=xPtFL7O zK6jEP>#dRU0lNtJ(L9^2{wJ1NQ3aI3mNrhm1(1k&RXr=SC7*F1qMMB#_Ua1%^-GYm z=6=jAG?-ii2)FQI$*<;080^R4NgV#b~JN-qUyl zyWUDar;M*@sGj{=_!8XPFYH`i0|WCXS1P?G4!7_&At^{;X4=a3w(B9ndJ6&HVp`~k zpyCiXHGXMD#OjNCKxMmOF!m&LBL`)Z#gYoMwXPe*T5A~^E&zG zA}G2w_(ERG3XOLKW>rI~`Om;p316))`V^bjsc4z;r^I|sR9|okSirNviI$^MnT}U8 zVmK)p1~<)B;BCxO8AI95Ub^AG+{q&zCe}f6ZNbS|{*xkH;~cudSaZ-UnZGGSt?IH` zb$&L zCdRCG#h!9;cX%K4!jG*+uiiVNl+3Ep8CeF!OSRdep>(66+W8G!y-4CyzAzLP=wLk~ z{vao;k7}Z(WBsf>?*@Fbs%Smvg-)G)(Vvj^iPz7@JYzY@o>!Q0eoVRQ<;RAPzp443 z`z68`Z;9pSupS^TKQIpO>(p5Xfm~hFi<=%kjmXvuvq%o?j`x7qGSQ23u3uKTj(Z84 z`m)gLe#S_yhV3PC-JbU`9IO*|e+V|6K=4!2H+jQx=YCinOEBDLy$Q?eIjp%?Kr?|r zxu*=cBAURerGOgm3^DzF8ki84!-rc9rIo?5dM{fUTf3c{ss=~S={NREAmC!BO!i1U zdQBo@5I<){CzVMIB#0uFy7UmtCHfuJSXqdRve#WdP)-)5oLW76BPfR+CHhjZ7+pJG zQs3!CW`gXwn?OWxPL@cr8c1Fy`3%|6zT)zsM^7xj$-EZZG5`@UrE?!}#`*4+SXZX! zcEnEZ^!`X;bAsFM{A13XOjJt{-OOQ|ifwRtq=KcaKN`*JymmyuWX?qQBY{Xl0`JjqfW4Wh&hqEZ_S~!J!7u zBUf8f&v)+Se$OCc8N#j~eMkhq^@|<6D062Cx^&Y&44Sq1(K!{mzXQ;3If5t9bfTgu z-YY<3gxN%;LA=O-Sxy27hwyt?ik$%y&DQQ;_vu>Cq{d!sI3n?%wxJuWSHhG*Vr zQ_INa!qiTZ*vO=NfQ%4#e3EA3_R{L&ibTjMvdF$&? z@aC28cDg08sP-`TfNb)17=5GKT$TxiL2!+28~e=rp4}&Hh2{i;p?iiE{NK&XcV4bJ zTeKUgW9wD5*^8F?l&#itx~`oi3xA*zW)DwVeR-a_J%|3qmOyk)fkAj?Xqd@4>w;~` zK&4{$9ZEJv1EpXmIXNL!&-`Z)sxpCfoBZ0ET%cx6%u+p0cqtiwryl7101-64K0Mc+ z(|_lJK8CS!rqAHxFT10nFNIfuvk zg{Nckv25EH;$ZEa?zK!SW-n^XdL8gt9E6!UG7_08z3_2xwRqIy zUDRYb!!wyLilA#=Ow_D8i!px<^2PLLOz^Q!Um9{oe|u`j>|i3&LuCwWu87{b{|c$Y zGnKf>b_ZTgl*c?#WK@7aU4eGObQ@P)_!_7vnUvJkjl4`lIR2_i*ysWu6|LqIDxw1M z-zOGJQ-Ht*iPKL4&yujRLI}RNw#3u9wM6grI=f?6jUYXV>VXVqq)DzSinSNruRS(kMF59UU-(N2kcP zHQdHUVC1OXg^3R$MPOT6yYjv4WPfAnUOx?&iMyB;J~^~8H5t`rwF6iLNajfd5M+NJ zEG(UTkO&?4XUvjQ`a1;rfmbHZ^zg5@1~`|H$Ba7;?(wb>S)Jyb;O1I?sAEoC`^nIM%{*CNa8NyjQozKII10MMR=G+F9wNnI1lqhAH~pFX8I;3I|!q zvVIT{TT?Uk6exIYrQ^=YDVgWB>b$R6s1Z6BfLSuZ23^GeMhC3zcZi?Q(4fP^40xuL zFkws++}Us7BZxR_HeLPTyOIQdxqdY?d5$vAqSG=7KV;dt9_b}JZ7p)EyLSH4ReSDM zPU~`Iy*nwDopre9^=ltxhPAUG0`&I==PR_eAG97uu+ywtOR`rqef|g-E@oqd4r|JE zy<`kv1-vm>!=3fC-)#f4e?mhbzRGHyB-ym1cB^4O$+R6>x%+TH&3WH8Wh>sFy5Mz+ z@JgK2WXgfMw8Dj81Oz71+48eF6Mpr0BZAWM12_(#i0XeoXcA+RYf zJhoCL6a1Zkg!4VwPbrYe$P|_>-?+g}yk_-No`C)!tH%EHx3~F&eXJ*~fA*ygU29-b z`HOtbSOQdPxaccxkk3K@2X_n$uu4@rrNoeQ3lzjEdCB>!dtn%EttLLSNxmyl&psEO z{TkIwb#UD^F8%Rp2K70oLA#Zi-K}pVVzh?&c=s1SIjYwuzha6n_GMxUYlUx2mJ`pJ zb?6*fE0`vtc z)|;07R8=v@T;RDRq_)UKsrzHw`HE-r`nZYDK2;BvkO;2GkT6BcWq!F)650CWT57V# zGrv^oGp;U|yv{r~%6^~61#=j~IP+RHJ4w6QBoX9ujoKW?3PaALBL*>AYYBjFUk9$= z;Sv}PnxlXZ52`|6IZ0){Nvk~fNVi+X*v%~;A*hr{cI(%$!nX|A+pzZsR{d|1TkKzY zp1X5zmu$Bjw4rs04r!8mtZ$ReDD5xYb~=`6&Fl;&|4{00jjr4(_1;^)si0*sa6d|X z2rHhwi{;X3Fzi{n<&_wFIm~Sm`#DHXDZHRcRDV9Y`2yzEg0ec_LI{ z==gncDI+0Pv_a+=&wk9#wGILv^3nkHs<*6ZW-9w2Mla)kJIDyBcyEdJvbPEmhdg(AYZ!zU?4iaN zzK!Mnf*Df4vZe$Ginzt^$DO?aW+)X>s1W=TAsFgL{Ts|xo_aw=cL)+U>?)TQ&SI>>=HJX3v{b)kftq|IP z6H2&@-u@;E=AdEu9{Zcwz{UNTa5;+cx~buQE8M5&G}WGG9k$eevaqPYMr1L0?JgG! zJ%^OASK{P*MKd)iiN{g?){9-7LeC9gkb|}s^{z~Y)9yBUmhB4z&?b)5Lykx3iau_< zflh$|Whfvay!@L2u#pAwU!YN%ZelFUo*+#){ya*BA&LB)YH0XDma7~*BVHlKS_Nwi zdIlPfj4Y9Q*GQA^>)Ux#6zj1!j8uh}&Gu{3EV4tx(a#7&v(&y?gB=T_j-4Cug;5H%dEaCv z1ohR8nzr>2`JDJPDBTdK&M`|dqiIIi8&OsQrlxgwDAoUW{WO?}prdjN{?61ww!3^J z3MifytwZmc4%%capF6tR z31mvV@Ie=oK6i(d99hzuy)>_2X}(_g95uC^7`gZyC$54TrZ3GtRamLVb+$%8FRw4( z3NlJgSuXw=XX&n)`tWD$rTerHieDn$^QxE?UIufP`MSwrHy||TKU!eDA8oN;o;gPs zdY9H?16HX@7&>1Q#K7;_KN zS;eAsrt`w}UbGl9N?5f{X}Q|{UQ3D!P#Ms(n&`6u@2z&wNDkynU5+mX5P=FqL+T3K z!_#!F`QGJO7E@>sWur*t=WXeizdk7{zss5d5vz_#sXeA5Lt7&ucwv@Y&1;B(_k%Ru z>ndUi;@>cc*oaYZO?GcS00E6n$#B+tKvNpDwDw^JE_qRhKtP(rD0zhQsDS7!*?NxL zcoTOf@nMp@j)LT?a(_W#l_@08vEMT$mB_h&_9e@AE^rOzEZkDcu4b!Q%KENDk;?VD zGf~Q98@IlP1qA*3U6=3S27jqrt5ge9c*nxphkOv}a6YL79t`8u7`H!R3!_pmg?Yp( zPrmSDg8Q)&4d*c&@`U6_6!UYM2qW$}_!GE@lPLRN3zoWKTDRT*iZ~t%*RKcCLx<&C z9sLiR%L-cgpwiN=UyVG)i0}hb`))I!vD|B8yT-PQ>npf*3Op4crHsqa^eB(xz@C`% zbt4T*$VJNxIFID;73!j2{BQ+z zG+HeSq71FqCuOmN`nEb0ou*Iq0w^DBjNULcISu>VM&rX|IEiA)T?LR;3y@dZTb0Z0 z+#MoR*puH&wZQMe;ym{yh2;rv-4Y_*Vh7oW`vKD+T{3atTx zu=0{AQ(Hz(%Yfttd&UXFFamg6gxCS9gZ2uRImVH_8sk52@ux`Ro{WJ#pk3$6k9GmF zF~%>LnQ;6XUUAAI-0S>a=Mg~32*eD zCCfM9-j|+@F}=)*97SZw`F~$w33#<--FGpPW0WZx;G%$RvB0?&gJ$_jM3-2kIAni?mP%+L$RO zrdoAZSzowKIFLIaX_6Ot9NEvmHrfji4nPOuyKzw0#+)X-c`=cb(y+ zov-8ZkX|2ldv6NZOlnsE)}}h8 z8&Y-h41^AF5xTnc6%5K&MaHx#4)OY19vfJ%#hQo12a@#=*&4(7G>_i=J3+?fMx(4c zmY^x|GNF84FOuX2=)Hi|Hfa9SRV{i2=T@~{!868|9WLJA$;2dxZp!QnJq$&?9wg1R zawxnfbBf}Db9o@zIGw+BLj#cPdh&62LsPtDeiI6->UH5oTf;}rf(Vt+?>&q>L>uYi zt3Nnzmdmt}GV~snA24P=GiBq>s7FThL_bHLN0=eDeuGCBG~|~?#(#Z1ynqUb{G|NZ zWkwbQD(I7ytyF_fa1>OR0!rO{+P!~79jSWO*(&<|9AoAZOLoE<9j65#_GF&M=)^>U zr=?X=-siPUh@4x{$DZBI-P`m$u?w~ zPtwHZobL9hPAV<^K8SD*O1#6X3DjH#Fwb-9&inU_W+#LZCzex{AtB>82>Hmevv;19-W`*>FAS}9^t0O}#lStc zNgc$n)Vt1{%sPPIbFlV0;U$l;`zAK(iuSPig{kJIJ6?5+lfz4r5|verOiksFv9P-&O+3D^GM{jVk9hAMB_OdfK8HF z>N2Q|a=}_WIJ#{i_Z}81{x54Ajt^^kS_#ve9{=q+u###j)dUHjeLmwI{8-G{cG7)rds&D4&@}v9nfSxCf4&UIdWVro$f8c&v@L(teNi$Ncql#1?OUy;Ka$2{yJ1JO(j70o1rH0?}_07XN zs{pV6dg@KfwN>aPEW1mF9s8P*dJcP=Vb6B+8oYCWQ6hJwhWbPjG9fLl)xtrsao1a# zZ0#cn{AeC^&!h`fx2}l0KTzEma=jUw(1+}$#$otJCTO}|TLjiKcr!%mE#S`T|IJ)s z>*NC~1g9pBc3TBW_zz&unv7t?&Ib$|LzQIVz<$b?u*pV|6{=BVQ#p+1$X!QR12vf! zqd{CyFeE-XW{p&bgQ5`|;Ws)W(t_%f_}phhBOQl4`A5G9Q>}R>^L*Je*%)VF$BE-I zpefYkEf9^`H4_OZh{{j-d)9IwdApj^iuff}&bUS3HQ+)^zSWJ%GBOW-5x}xU-8CT_ zB2-2>P=s%^4D63aR_-&gwQ3x2d61omFh2vKo=2~7^?k2xT3ou`d)R^|20uHoZ)^!U zNZ6_Buu*M3tmJVJXjU9Y zUWt%UH2b@a2)4npD)o|Gn7=1cZuGF$+~VgvJsWW{=P}LiQZ#S!3L*BM(wLP^ocZ2897&q`<4%N?El#~=EAWSC2!1)OmCW^_7Q3uxo@13W8Kg^^V zUcC^)*&{FvV_eJe@EMw@l9%u`d6`2>Z%`ESUV!_h7Pj6+DqCveIhe=bW47q-1T2dic<&yyxxnCPY)3Pn*lIdzY>PTn&M;BsD5kWd3;p&ZjbUIVg0KipnxXSVuwVcu*GAD1GSKm4vTpenml4 zhlr*OF=)>amL19y+L$FxbYnEyu!-mN-q#ES^e~-;0JUL$8<1kOpEr6gKmi?wE+k3L z(NG0;FP;y#XIimmzyGeDQcZzg?wC1`|0?tKbkxj@_Q=L=Nl^bwx;WZ5!BRy(b}M28 zU0LY(?YMN5Er7xi^r#pfch4e~I^$%sI+aMEH1^wXk?sl4m}=(NO9l=-^h_f#^8!e9 z@YwBkz!tMKo2YB_?$Va=)YB(fA$-(`!Pdw=4qzA#?s z9`BaeMhrV_4?it|kDU*4^}6plP=P@K;{t?Z7c9POcVHmhmAzZX4KJyZ%3Tn1=ffUL#l@; z=781yO#|XbFMvoAbdY@9>+7g$lB9vw8NpZHW`oGXF|8=&(wzq+QfxZ`s;12^*%U%C^@|&c5`TmyvS^)8y{MVAHC`iSUAK=u{i%io(0DvrO zG$hNqSCP!6E(RWOwXl8K@!x=y;v_fEP zXuW2H6a6kp0IO-9XuXS90fjI=(m)RDHnoqs!)tMB*^lPS5=*33aQ5`fF{5mLlskSt z^iy|Kc4jc&!Vbvs%{>}Cidt%?In54fjV^}N&>kAHsgc63JwRm**uo%g-xc#D!p6&3 zc#?b7J(NepcmO;7Z{?s4aP%Y3FVNN1q!Q1a5hXP573{fndFT=&(Jtnd6!E)hz(RDH z`u%Y6<{;omprr2fKS!P{FbGHp&d}zDrhp^cgyFg)Y*AZ7u8HO4m`F8VQ_FMuO~vPA zH0(F3k6AYw$mzSVg@$?_h=rCGfYI)oo*p+NEe3VlBQsBT>wCmX6N5361ja(_`$WtN zQR_zQgn`1|j1sGV4D>4`v<}4|O+P0!iBpP88(fH_IuBX26DH>0n=MY48qO-efN8l( zO^#XCRq6-WN(HI%{Vu)7_e8SGx4wjxP3nu&o=t6hnsW!|AK86wMbuKxU%eMEE558J z`eaiUI46xgeGZ5gZkNh2UY?|64LcdIW=MVDdTo({+XhairHh4q~L{k zibLMhI*=7Xq!Du^DKNQ;`B~J|+z5&7V7ik>vhw@~m#*tMB5IpKpelT7F&Fkp;v^^p z;LOK=ZAyGde7X2tcr*cbF^nkcj=v;T(iy~TT87=fwW@Ggd zjL;=VRv`0=>#uw`b8ndn1NhI8o2+i;Q;NVRGU^m)3l`J7K8iqPEcGPv-?3JfknFbV z4>Y6Z$XmH~Dgb zcveVC_FJ~1VHynS9~RR8NPj)BAp`9G+QPuz!Il{m*4E_WWh;UzKm!G&yE{ONVeMrrGgN<;=b_ofy zRcga}HEqzQ<8O}E*qs>=B+q_;i|Ty|Z+qb+*@Hy}fny2(lp#A=Jq`#32Y7S(U8>-& zD5+xs4IWbf_e=HDS!!;M5#mopn!tRoEylh6R)doOT|3uQYn|s5vQO8TzY0aTKMN$< zKM3vKbdrbA1c?}+kb!t1_7ebbb|kHYtl@cPO zq8JH;F&sRX=MFuVsj$Vd^dKrIuDsx=urf4sfpdtF`lHJZk3Y^RNF8;u&t; zoj+jjHP@WC=6#PbR&Fs4x>QfQR522#VW$3nE+zz7B$ZQ|KU>kAos^}pVld6iVe|(2 zzTkBpYWG3Z6A}Shw&@D%f6_l#A^w41?4EAjPmYcos;9p)q%m)lVpx6)2`PIT>kieZ zkt+V))G60O`mvcP{%+(`%NvG?=8P21sMS*)#tLjx(?;KaBL{YreL&;LP#yq#8SutF z{*R_hk_)H9Wk2xj;la*;dtn+agD3BEnp(eo?gm%CO;L99zY9J#xF!WpXp!;;IPkYj z6iaz;o~zcZ|5i%&0Y8LoFZTTJ>3!sO?~k}AzZFVB0YX0!>Ott8Atzx##)+GE|6e|7 z5DY9p4jKpwEa>e3Vjtz-$AWx`k3ausz;Qri$y{p%I2EkThw4g7%An1Q_YQz7yMEK` z^grw-0OW23)UuT5i3+@_VS2z8h5oPF)*0qM3my7+!nrPhi%(s4 ziH{%l{{Qqt!BhJ|FfewN4=sTI_Wu9Zr~iL_;xrb(qC3#EF>Bf1GIyFQYxSLah7P&% zqKkC(K2(+|Zf7NKrv=V0`{Vq~JO9l8xA%0Ac{FnqtfOh!2fOigb1El;ZUwcrQxXzP zLSZ`;xg3a>&SbK7Q@{ zIm5}tQ4K(5mKh!T0HO^z^=3tL0JRnSc|vM}6*rW)q17N&1?SwRIsX}mgO4q=0r9C` zX?BL5pLMhbi>~TPv-yz>K^xu7d1pEf6#&gcciJ$C;MdmDv)@Vh#t}Y{?soeN;GbVK zqOPU;l1@(AZ5-ihCZ)D^DJdzL%?G>jP~nMyERXqU^c{-&wXEg^C0;9u{ zjpR_=Nzq-!@Rgb6Kk9A9Oul&}d;q*#fLoT(SKzW31!<})3Ry&f5-RVB;_IRXy)zqm zno$)+32q!F7ZU_w940#oV3v^ZPcQ1GEDuEo`tIPE=Y}+A3)#MeicDHt*G#j`CSG7E!&z9yXh)bDrzs{rwt}vk_ z|F8Hd<}W1gS*pu**?~}iPwc)@L$VWO1+ZPKf=6T)lsv~JQ2x?sG!1d^wIK)mD4ov| z1SlX#K1Tp;V&$5iw|52+KDnLnY(WcvGOMav=d`ZkERClpgU4~8gWKm~CM9VrYBuj< zFx)O0i&qhzp41juC3jus0Yr@rfICcv^BGbPQ743C%!N(&!Sf^tc71jEJm8iuv$@bURcqDo9JO)0wlbizpVqQuN)oDpN|0R;teYH=_*V8l;%@b)Bb=*q z+#y2Rdb#Kfo$NeAhk)|P5+p+B)6au{LYa*Q0S#Z58rgUQ??upUFD@;OH-MhtihM|G zjIv7;Lws$LA&zNfyK#M|#GIT9^g8YQ;$O7!{6{`GL z8ptag1mUZmf+D2$z2+f)IdK$L=vZfjo;p)wN} z>J4KFu>Nl}=1=5>4M$hzx@(b%r^;p{YMDHi03W6S{!+8$NBU&&O-D+U?5Ecqe`F8} z>l^ja4}ntoxFnG+DsT-mB1B|lE!02@B7KDx41f87vY&%Cu&2OGbOA=#&Coq4kxrlg z#Bto+d^a!-%koI7^~bWvs%rI6FcYmexbS3Z8WtiExHO&k8vQ;3Nc2apGfDb=xw7g4 z(RPj`&<_&$@u4yxRQJ*5aY6q3JS^*X_2VveSIzyD1dZNh+dKpzaofP*tPeGkTuy^A zUXZ26fkeoN?rN!)!*AX!`)vmbn}YgSF-4~u)QCyPkUncxH>ajKKm3JZK?zw32@{1o z2?xKPIg&C3EWXhq3?L{dh7R-#9E28VjL!cY+;E#-iA||7S|!p35VMZOgKj4?xyby~ zrZ?!59%O?V;A!~@_4A8{k@ipo)k>hJ5$=mYZp(v6IdrMqr0n|FQ$$anL+R0A&a5&vZUVt2+n=)dHrSsfC3&!E(g)ES3=-L z9q6cuZm!s>g@>x5*U*CSJMNBW()?v{;{le%adF&ZS^4A+53)4dox+K`28+gJEqhJ` zb>*k--hH`CkHd)P zJyg>d&IRxv1J|T|Enp*H$g50hsdvuKS}^ejDa}04(@7jC+F7rBfdfj|R$uP8LtS(4 zp9^axWx0)Rlt`$I5>1cNkm5wJ8&1TOijm-}dxq)W_HK)t9y9~xF@Q_$#hC8`OWJ@{6q1SGrF2D;G{5>hCQ0;`+qX)}i7@NQ5 zb;AzT3}H68vAJc&d?o}2+8Qp<0{#Gz&AgUbvYbaew}B|{;j?z?p2(T>qaes1c@E7@ zfSqK@{mx?lE2>L>9^Y!aLp7#BQo7N()gTRs35RXG2>sk)tb=}ZThzHXyS$}nz~{Et zw`o+-10Zb+LGFB9C?Ag*>p7}nfo?- zAJ7c(SIBjl#O^foW=i>eF+*YVZ`ak_{GDSFGfe~oT)rV%YNosd;=n}EcAY%W2$ zY3yG^@R*Zi&@63h9>O?UDb7Kwe~3o%T&g5l;HTmJOyymL5 z!pT?=Z6RfCUi$I99EHIt*Dv1rXMD)3U7ny;y|YMVCee&AYxQfxZMJjtHMh+BV691& zLTv1QH4oit6d_OJOjW~RZeU7$qmnIPwumxTkWXJ4`>74Gc0%Xg`K0|SBF%`N^>bRB zyO10oa;+h*%0jQUHSC*uxL>^HKsQHJ*UtuI?o$t=&%1F9l0E@$+!JC;j zSmuuj0Y+;|P!1}GIs|iYqm_X1Tu?`i>rrRDi=1?N;m%Zco zvawC$fIXU(Lsffs-uPOGc)JBD(7&>>u+!;hRuX`xmseFu?I`!wJ=?(A7zCrE)M$&k zqjV#9v-_D<3&6>^B@7MCSCFds2^b*-*t;O#-&)SLehasiLQ?I^{eJ*3rJ|N6d zWiT%V++lm9NT}vm(w(kGoZtJGV+?|Qiq=xr(?b0GeU#Y_%>5L-4+1^MmD+UwZ6z@5 zK(7uNTU`p&svT*M&}oJzs7Dhy*~bk0yLB{zQhLr;S}MemntgHdYGx(LTN*TFKtwy< zB0mu*M)`r;XJ?F`5;Yp24?w@}I2;BNp@uCdGq1hjlYVKw+-WfutJZiWChmG6!XMH0 zcf|@5c;{331&4=Q!*pI!3pwNusscPNM*Tc*Fc9kBhdxKe$2|%EU!Tw*nBEJ_O&(7` zO#*K%!6DFI!2nv&?-vIGU(zRdsH4J@#-^cRgTM=B$-HU7heErN#b!odoWD#z6PHVG zi|^>Pmyns1lLT~h^!kMk)#4WL+1_DT?HGw(rzR&gk5yamTb4YY-#FKHtytSSM9wI2 za2n)R2c)4ZP*A?`ygC#{cvA~<6OTg&mp6=uBJ3H z$^=dephXOWwX?4gV9$;&=Vn9UF$LiYz|Z)81i(=MBrJF0$i-A92LMd&jy9CWkG##J zJ++||bH8S26#H<)8th*{m1F|950j&JcFMrw; z6$%Yxs?!Ir2v|`qaSt1f$|U}2MKh<=_1I$$1{0J55=LV216q;ji(ITE-8kioFN`E? zj@GQ9MUl;_!W4au;U{&qqY`=W2<_8570+xZzYO%(7$?Wyyk$ctAqJV~-X&VYcWv8E z2qoc-s?BZM1f#_{4f;u5BE*ZA)x!JGjnyI(Q~Y|gD8~%U{?!sz*NFqlLxJ<&@?_c^ zj8+}>51(-&@Ee`(*8{&GiO|!pYW(FwU#<_SU~>aS*_Gb{H3s_o=hnj*7I3nBUx7U#OpkcqD+MMP`ks=)FZ1RctnlxH^II7PqBrV}Id9T9*WBUt~ z*$;yTywojv{4PU5d}cc~KBu_wxUT(b1w27z)oqM=jcK1&G3+rm|*_sn1wHmmrGSqd~5m~i=UPa6= z`w{h^QR~uO3oe2}Y=Ord1}l21A4%;oQpA~DKT zYl=S~3@Ink;N=UI&!CmtUYGw1vo`r9FY(|5atCLJ?Ca=ABF$PcrOSq)@TKsMx1yOq@aUFHZppPZ-jx$Ci9HMf}*tvSt}9K7}ML zCU?*2^pJM$Sh!|25WBH}RzX-`h_(D$jw|&bT4Xb|EQ?jbOC4!&Y&$3_XUx&P)gLz0GbmLTDtHISmX?KW+PHOmI*2Br?uNMb5j~p zmitW+ZK-R*)k#-G^g9}BZeXCILWtUU@5taQv_a0(ka}dk9WuVbIN73Y96IzJo3le}sDy0}t+URcILx0!xzJJ$zeZyh=iuJmhnUrRf9=AVYFNLKB zK~!p4GdoYeuu3c$34hM19-|Cb5A&I@+64pm(42;8VT)_;fH+#}axxr=G&O8Dh2!;h zyLR}ksFgb3rKO-Q8z@-DP+$QLMJ&T+%V;O!?3MVCDSO$@2%{PU`||xQw%0&{e~(kp z3cb9S&5qvB4kejb=2n{v<9G6Lzr(G`j>E;B8j=Z1M@RWmm_Us9H^x)t=Vaj~v5-+$JNZlKxnYEQe zC525x#AdhG2-*IS#JD61O?g72e(|4%(O~mvnOi4?Vj94{3!L~Ol35{uN2(SJyhLt7 z{6vJWZ^MQ*1XAi%nJF|QV)2B}WfH=~82rK8G*jpK>yOq@%Q9Q9m-a2lJ_+ zWeYu4s<{Rg-FhonoK(Ut61)A07fQFybGXi>=sXsNWrm&_dicwx$4G#)YIS$Pw8VL!zZU@Y>``Xf8mxQQ4_3tIi>D=tCL#bdWXFN&>h z-`!#FJKy69lfW*+d33fFMfcLzzaLUrB-mf-RJgUWp$cBu zqjFl9yBx3UFY$#cjg6T$koQZ%XN;p@Fy?pJ5eG_UMT8N{>TDgi9@h?fp9(3)(Qa~4 z3<(8Opo>4guLo+mU|0I?oF(gunek2Tq3NY-Rs#UNQ<0NrnC!~{3j%y5>YopafPf(7 zpC(E{g5?lwXQa5x{&Lt5IO}a!Me>voC=& zg-*%O$ME1}xYg&BW??~sXm?Bysb8vn+}z4I{Yfi3&I zJGK z9lm?>#H}bzpZw8kIjAXum5YNc|FWKrZJ982?cZi-nxXVYiJ(Fh8drAyB|8SxQZQ=| zM)@Uk6-IM{{Fj15vTxr+|K)IvGP*N9DcxpZGdmGyyKhYE5 zh%s;RJWTVRH`jr0R3p|kl|^WiJpQ-^tA_#in0of>rm2*vq=%nHls<2;f4_Rf7ktos z3W607X2uPIwvV1P53>xc|6rcXKg zoJ>4dE^-D2O+rs!{z@DC?}}K!@pT)^jmRxCTfAe;n}VNslk*bm;gS$y@P<>6kQic; zdpRz^+MXeQ*9ybt1=ZS~BO~VRk#~7BM0(ikyz+`$uNN$&6B!Zlnfa4qGT9Z9|6=y; zCIqz8N6L#&{uoi8d9J(P!U5H1WCC>=&>6vxff)m}RFELVYbG{Vp&O{tqf_4QWYFMsJD_8UI`VI|VXU=u z))k8j-C96=`S+5h`3Ut8mvu;k9Kc~GoLsW5FVBO_Co>y4HzBxv&d3u+{ib{c?XZ15 zq!iSmyKZY1%O~+M+QKgxaHSa?UXiQ~Lmb41sO-qd`xj0Yi9QnIT@yC)kuDd9nrbQ|DtdBDIsT zi)HV8L{@t%QSCTFGW`R&*jO>4@Kg=>a&=>PvAUhygr8%BE4SG)wGpB34f*8l`qNWo zH@MOA_a27iFer%iL<CC*8POcDBH3~8@S`5ru^;Dazw!U6l0e37UY469G!`L0Y zv_Ofct|)tI+xY^4(Js?1pH|pC5DEo+>89Y(s*W@5nBQ#V@_lB;4zY&*m5cANgOB1; zFAdqENgl6)nHU!@H5K=9xGpmCse|#GEyG?kLMz}J+j_5eR}b!17%rY3)dW@O_r$PM zJgqHd2$Q^*LyIk!cu?zbqfptIhg;-KGQKc;9)J`viSP%eF*bS*)JOi2mpTe$1%|pu zs8>JKf%ZP~C#zQk~QfeQh$AlXMGOm%}g;!D>GWFyn zGYksyq@JshfUb4>0M&P|UJjZ46>OnFgG-5|Ha?qN+3hDPs4O$H!Gr$7h^#K|do-11G(tf3wqa=AO z5f2MdyYv(Vv4n#GdoJ4vZ#JSr)0qJdcA~Hxq&+NI#@0ho#>gxESG7G?vVtoU;I?&3 z`4>#(#OD-q*N#rtnd;u+#Dk<5i_PHnMxyuR^kgaQ83AsIAX8}9GV3@DOPMXjmq!VV z!-?U#q;sED-=YC@Q4!5Rk2$lh%KP1j#WOk<%jJ;mr6M%Tr{;r$Y<$Gv#}^gBwcOv0 zlNG9}tJ{;&%XiNnF*mmdCTe!uebZqZg+*+E+Hj)8MZJ2}MU zX98p%k;!qeKtV*DCa-YTrdy9Zg;7QV2G_hH!j@^z2-bU@8qrP4iEv`?GpJ7Wdnj>7 z24i@e+ux?2AfRRIq;nKTO}~9=4I$D8ue*Q$7SOtRA1AyX##xO~nv12`%Bwqf&}_>% zckjv3MGg6FOfu(NdEm;h8z-aw-{4nn+#|L18B^Qdg)QLjw#Ig@ua$Cg@LuWV(hs$& z{g7U|X^Uw|OFHNCa?yDR=&C6;zP6_=Tk(xYbtd~8+y292?9a*U0dcf#)YM-6%n`f{ z6$#L!I%Ynqr#sC)A6$oBE4F%(?D}Uj&EPL$BV$!+j?h?FuW5zAH>0&$hW{^#>Er_g zCS>%XO0)D<+8P1+$k^&X=vSM(jl^-ZRv_@65x9 zG0bDo1@oJA8S>vskDYRL5;GUFqQMfPfjQ0|tdNnV%v28yZcf3gj2Kd&9rfiG_}8;B zkw(A)ex`^C+};pFCcQdR3k)cHvhsUak4cguZlv&m?7=TX>sca2cR}#%ctkRn0(uFZ z#|#+`+Mfo*)+m{>wv{7=4K_KH0s3zYcQlT0JR%6PiRWUW9C|m;iZXg@pScspV{s-s zNxUc(M^t`wD(ZXsQWsz#2r`bQWP_Ui4L8OsSzd?DuCn`na` zWuZ+mdDqA5$j$V_^ zI?8~+YwOy%)v2A|DVf{bhd0*+CA&QffGhTB%=yOpp}L*o`UW<|B)W>~yoI~4RAe7X z^8gx(D~UXS8Z9ssmo=FqlU#nevwe;ynY6+06XD7sXUdQYdy`ZJSsiXK$!HoFda89ij!u0KW20AaU#PdK99vW4f-LobPJ znH04PcN8DhADsPGuMXxMw%XoNnO-ld+0175)}PHl_!Swh^6KFww@dBo1BH^}h5I(y zD0Kn`D8M9+;o$_HpMhkKEFTMm3|pUnPB>ajZg8k@&N|j@{2VJj251+wT4M*T=$Y`% zKKp$_`ME?m>Cl|#@cVLb<%W{k(`O1HVcOc4-7KS3OWTHaZU!d2cJ?+S9_YG^ zr2A;rf87KjVReTjb<|c8v>u~_!1^T!wz$yD*yAHgPCk^ahDt57egzIaB&JHqrm+g!=coZgjN$7O9>cSSYuw@ToK; zu9Ebc5KmWldCD>KK-!+I5sh?WQz1QAtVq}AF8Uq-;OYM+{tB3XkO&1jpxVXKV0PU@ z{Ww~KGv~x&c@!~X50<<=xscz0)L)!p(iPA;rdK!*#>)A7WhU;IFfUUyHXvLEU4>AO zBOho3lrSOoS)XD12RA*22eHQZ_G^4sFqp!A%C>!%^h^1=uoDoO=yp+;VT|RFgR=TeubtiOqeE%q6F4^wBR*j@@W zp4s9M1h3vt3)RcdJ-oXXA`>W33~lGSVfoC- zX4@;`0rK+U`kxP^eqcISkk*9UHF38tP}PsVCCk$_{PR z6x5UQ*bQ#*Kr_d(ao&IZF8#P$gTu^k#_eKY{aprPq1~XZ-2`bR@KI2OuZSO*25>G@6P630y5F+-#krh;XRk-9%6AAXmy!fmYDS;KiqV9Qc` zVbOrtz37ZBaK-Pg+e(jw-d8HM@^&l)hqv0_lei4CMLRu1MgU&=(4f%bzha2GhvA#U z5IX*-_t=#{c$h9IP!}4W2&OUe>Cb(CW@#A-Z!Zn$RF)WXby4)j)~e%s6NzUBCaEI1 z6Ytfw_Cgr5MHA=$30@rI28zrE0^GFG#?yO7cKDQ^Lp*?1zhH!f)vV`$$*l!l z1Lo>pAPfHC|9;kN?~>y4r|$FC%`$wwPBQSZpNY2F&9MGHoIWV;LL4#sgT#9TqOT-d z`LUyn&#R_$HQpJS=1e{NfGP~_R&Ialx`AD{w_E$d3eBTMdsONX5wav#?*!uJG3#I^ zQq-Gh@)MI#VeDvEU>FJW#H>mj0-n|F9Soz}ojwKw8gz!{!UuvJxx z28GxUhDjr#(L$jNeui%(Bg>Z1!oq}UBJ43YFMjJiu;&Tgq~?>jOwRd2xZZVKtK-Y| z&nnd{^bi#sZl={DbU*+63Dm*@*9b1DD0Lx~;dT?=aQf9K2WyvT&LB~S`RC7#HGgfY*;#*$sTPFR26O92iTG)yB z4qldXgn=MJYJHtN?CX>osX=9Idavx-6`hX2Bpil}Nq3FjqwZZ7k$;D}mlLuMY!l&a zSHCeM1+&FjxtOL@-Nak@72DX%dMv z4hGjpz26VRG`z(%jhrk%8hEJ1v^-iJ8Jo21Yp)aCb-#{N9sP>Z5J3iFhcq!uoT-Tn z3QYxbU=*Q8Cu@mq>TXyR)i6EP?Qn0c%*eMGveFe7L9milkX(D7yRm8P(#QrGm5rZj z4&2HX7$hBmB?an>5y-_QSAu+Am&0~+3DBp5{jypjL(FLAqK%-?jJ=}CQ&M^Yta5iK z)TNc|YzCSleOfTgj_5rR#lv8ju!rUAPpFdS!^KD z!bHd6P&$@LlD5KoGX*jqs^He|iKKHxuTtT$9tH0*R~YC-*~37&ZE!N2u}g4$wiaa> z0l(#Zxsl^=+kVtOGM27e{@2TY{jg(3Se*S!nveZ(jBWJF&%JeA#jZ`PZ+?8YM`? zqam(+WeXtapMH8goa1ul4Hmz&-8kbmb#F{Z9z{h5REQuTcd z#msLu!qgDJ6rJ9qK*=OMd)rZD`=dh{HAIXm0-FP0H&F}k9q40F%?2&8$1=~tVCx3? zFSJf!RGW5U@;bnX_TBgX{Jgp38Xn?N!Wb51JC>2EfCZ|I=QwfY$Dm$a`(NLg)pza8 zqfA#q+q&5qR31VQ5(I1jp=c;%$rDLnpi%ZF&+-v&x7><t_4Cz@hiT zjeu2onCQ5}&=PC*7+ zYeVSDVSa`9f^_GMK@RxaK`$*jLfM>8`265p4m#6o+}n&A;bqfAhn;24t8Sa*BE@FH!% z=g! zvWH#nI{z)*yqBL@$=@Winx`lB?;qPzzAMbXGsSs@k0hgH|V{0&`MK#RH3gS}?-xjT7|bBkPe(RIf9OIOv4_4ly& z4RrtPy#KVEpvwN_6PT|7)v&_H!;uwsLpi>^CyHkFMRvoo5(AdPl(xqW!6Yw?!0wU9 z&w|B3*fOwTyzO5rII%-p2Zm}%N10Bx=OHH)8yH$a

}^PH`@eer&uWUVJWCTw@Nq zjglY|9ypibu{$V^b}Un|01lp7r5~5?a=K}#K43tO1;!G#`E=}Zwpw5tz?o{Z)~Y=( z8ML5~3eFy?4tMU~|3sUN2X}{B1LHXM@|kb5?2whV8U_s3K%w>?e4y?Oy`GwaqF)39 z3U)T)Pk3tz%2#*J2g(ri!g5SYL#0WITkRpm(qi#BrBO1&O!Tb?AX7;Yzv?E=AReJYpOdN z7luTT_O>gkrKQ+uL~NHMIHVYT2BYQYif?LUuyI*lkluV^a}rD(an6@@_BZww`mfqmUS7XY zw)zP7@xPYHJCU@VYsBq(Q5PKRi_Ve#`iHK_i>4pkB@xF$h6#=l5Vak7xl=3q2Q0wWW?$bui~dIYQ=G3iXKuCUGh8`yFxft zRhtJt$qclW0EAeZEq+kJN&EOD`B+-j-7-8A@%SG!ZpsdHn%$UqeX#N>s+tIJO4UZUiN|LVsG%I z^UxJagSm>)3Gh~fPv}hG&VQTR$2BNaX{4Y^WSvU#(=LOC5bkUp`_jBn+G;i7DvvWY z``Lbe5~#<^44XZ9hVWWhKwfQ5!kki071}JBH|8c4l&fahE4{>}Su=-#WlLc2`^2=4 z#2kUK00w68IgEx;i5CvxB^ALQ_B2xtQ)$(!mNbsG?C;Ll!qO+caWUC;%N|#PO@!Q6 zS+Kr?IlY3raSZG#WH8Zvt-&ZnkZSSJLWAN8SrB`Ul*YV4tp`8xrIGK(w@bVTRiox& zl&%3QooG1JlAaO_&#Dc+7MC}}y7~+#~AQ|RSA|Rpd-aY0jKP~KgDrAQr zi|lphQ+^pK{sr~4w(sa$JlS;=o^%Cgu)cZ}q5)y(#z&)Wl4&MqGYdgtwRo{{G&xJ} zgKU-v5BmD@GXhQ+Rxy-b3<<3Sk>h=GZU4qQ-uW_$@3XVI2(}5JWMgctoPuPtV&p9V zuJ50R9c+gEsH3N4getxJT^Tc#-a{@t;QjtJHm!%7gAcJQ#(d~(*0 zlOCm;k=$^X4TN)#CEqPAD_hW2>3wsZC$Tq5?$nI*>U#9L@q3#c%U?$lhxL2tNi&z|J*-4YEiJ8{ zbaNn0E8?D?#6^zLy?MvRC6eQFSW9a7R^(td$>b9gwf+uM1N^N~uue3%mH z)xGt0a#N5{Jp4NaR4gXq~d3b+OS-n}EK{GB;bkc-4U*JxWf?=&P2A zHS_I(V2%H`xtX+{eVEDN!DMqubuKCH@kQKK9I4bd;+qJWyQi^xx?aqi_uwnS9Es(o z%G0$r&ATn&XO;iPcd(6&oNE+HC$?kfxvItNoB+NRt zFlYuzytEeVu6YiZ_9gA&2c6D-U;G#Qn4(FxiL zO(`_k&h!`Fh>mf&8#bwFDY3E^ecZ5vGhsb*d%u#1yE9-D=&5Nc<0DT`huW+No}+e& zxP8;hqs8u?*`f~zze(gMHhN+Oi9esR)Z~F4Yu<;f27*KC^a-%{g(e@LMxe*2ivr*9 zkB?@q6b;=A_v|M8nh7e?(=w*GHC^-=Iv~X3C!8X4e=|?yanSXe_uJnEBmM9o7<42E zbom0|T}&x@XdF~%ns)Jm?JFC3^4bLQNZW1vF$N0wGUzB!G1$s;Vdx%x#;tyBFSe78 zP^cr|{mF4~TVdo{f;4^4NG>%sj=~sSnI+tPSURMk_G0K!NPecZx?2b|!`=Wb`$?H( z82-{0@t@EUG5)LK9fUxd{AZs#(*u@hAN=@fsGiMG&w83Q;{LJIx6VU_adA%O~0wm_z z$%c-iAXl^NvK{Ym^l$Lueg5MI>C4RRu;j2SOju~kLrR`(LP~_AqaX2ENes&=D5~n} zBT3`wCaX!~N~)UFshX)N1}Hu9Qu4NyYZh(fNa~f+qnRAI#KhV9Kh=QdE)-UQpZ^Nf zuo-qLxRf#pOHv=nbkwRjaqlxT3;>=DepIv=Mk1CxAbsLvk=~4HQ5RXA zc>!vA=oR6#q5cP0k)n9=>)yRa0RG6zIQW+X%`|fJTmR8g>xBmlo zt%ec*7r?5z{>^L2Gl?3|1o4OT5-;I=gxgHo4llTj&sj*7v;^z=39?w=yb@sqMqyr5 zCCTw$fbrMO-}%TZa;K=~r4%^DQNAkwt<@>qe??rz0yE`*4&Ez*eQ}>k8#puWOWW{fX=E@8y12*{TaR+?vYx@iJFmzjr4czn2p!8<1l% zDYV8PYp()_5DV)@qtU-41kp{I_ZXHh(EO@mN7W#>|JBlezPDA`x z9${>9IP?<4f8!ME)&;8h1NH>Gg%BFB1boH{{}s3I@p18C<9H*|GIPmiMN#!iih2}< zT$4QqQb%hbB-{46}j93(Ol`eky;2K-b8IWGKsrmf$U4Z<)Lgu;2u ziP)v!sFwc(GwIw3CE}(Lbi?^Qxp6g@1HUPbs#?YbXhfnNdj(u@LyI5$vg_W$+@sXbwMx%A#k z=WB|T_*Pbh1qB)oj*fF__X}sMOKzt;I$!Ea(;>lEsjVXoy8%-?_zlF1rz6wC@BZ_p zU5GhiY%=Lc%KI4@=fk99BY6s)m9#fjFrq|^QFD;sG++R>j*vOp(QF6YfyL)`gU$r|z zV*tE`FJL%nbUgh+XL;mx@IVm$aE$n3U^Q;`NOJ>LH5t^Vg@sC;wQ??ti!vZky@~Nn zHR5A4$mU04?IGh()Ij>o;v#Y=FRAiU|55;Onq%JqV|1JymQDqy{S9VFA#&PX7=-ro zl!U*@;3q`%8W=6S+H4hR5^ZLY5c@A|Kb2&;;*mCuB|J;8X^kAI&v;18l%!oFXbh90 ziu=DGQ5&x?M}FX12kwK>y?5*?HU3C~sG8<6T8+5xH7eEpFnswbz=~w*sjQWcaB_3}UQANdr)=U;k zg|W|GCkDl*S{42Uq16#w6>N@V5@P8`n-CJjyajG~q##`icD^30cDOJ-4*c0_qpJH&Q?Zb5zu%Byys${dg2cm{>sCDR8b8A4UNJ%-^c! zF9s0zlcs2Z82Vu`l6l||8X_BRMeo};SmrD z>k7n<8$fZoysic})eg8JFF()EZJOv-!!`n*;e`Y&m@dI-@2)V1xd3TJejvUDA`qgYbN&e!M_2lFl>8BL* z$FGnIRSJPlV_5jhj}D!HFIMK<{52HVNL_zQdAaOO*#tS(b%}I}3r|C+tGwWK_+6!f zp@SdA^*SV!n+lJPq>i{;bp~KO6E;SXFzdA!qmH316W+aRK8lnN|G>)an(E3~>sX;O z{*oV2Y|sfmS~hWFA; z&pnUV(*5nN(T}2bFAdR{4I5LqkJp7H)507r@XOEn98a^NVsN}g_38IZ6|2B`Otonp z*mUuIx~W%3=R&q;afzv0P-|a3eqFB^#h{4t0_4)4t-1Z?8wKte#cbkVcZVMAH+6`W zCe9TC*_=0jM;~u5xn}_zELHVSM_MfCY}7A0D{Ot2OCiAhRS_IxVpJ@66f+0ZVdVeS zVgHjGo2h}%@{)lXwF@ds&26yDu9VR8MOo%tw4u`~%ddEK{|~zUGAs)2`vQiCmJ&p| zEqW;F7Nk3d?(XhxL>i@Ax(8(FMyZkR2I)b%`x$Qi{onV)^L*mE=3?N)j6@>(9)(# z)7v}K_WDkcZQM=r#$GRZU~H{m&nTB`7f%Q2KM(^?I-QI7#8f%)*|E%4ZF3wAnA4u6 zH4pZ?4($y2f?KDqoC4N}3wL({bKlGLVIKA=^Xa5lbwi2jR~2opr62O_BrQ^I>h!QL zP5d}e5=-IEVOrKAvv=W0uyoluNrldn6c&Dxx~giCyxvq)BZoV)j+I(w#xa!SVOB~t zT;r8&^F^2-hXG(#wVnsa>xzshXG&oO(yc;yd0<_(j%NUZFyj-y=6e2oriF&5Bq^<& zTiv2DpRR3c%6e_cPR|VvO&X`rF<2KTf!QYPMs9@IAVFlWjw%@bMnD8rLpBUYudAcg z_{B!gpFn~ck|ASj-L@HL5sv6CrIjIBc21#sZwJ$?i`Kfjj|cp&O0d1%j(WKwu zjN-rot62(0)LLscL{QNwUhn!yLP)rAK!-PYkdpOdzngo-#W{P!JUA59D{+?fqsTMI#gp{2FB#Qa!$2HY zdB|Ru(7=$JLL@jwj^~W=dT}%;JE0`$NKr+r5%U;Dm4kN>z155FMEm?(xDkxQe+D(V z#PTQ7j1@{%BP!9AZ&A&g(6Z1M$kk5MXL zP3aQZukE*u`G@LK5nWUbt*y0R0gd)2e{3u=Yljqu^QD{RZr;@L{4oeQDf|U|VZO1s zDSaQy=XJIt<`|&_eEH?e_^2aj+2;|-s(r$`3Rh*zN=q_X6`m%brCdRlh?tYeBA_lt ze+PQcDVt!PJcfr;M^0-9>9>}~cl9oZxD1^)%CkXJfC7mMkeFlAD94rKW=z~|KH|*k z&noDppcIzYo6>~-Ht4M`KfE63yiqkIw#S)I*D2^I_qbp3b?p0M@@CxSz9RbE4H(4< z%-~dNvG1^VU;pQIr6mAb{ZPnqnY-XY9bb?h2u<6*-%)a+7W$mfn){#hrMQ<8JL)SMXvmJvbX4FmKru$vU`O3mJB45$N;~EXh;C zE7hg>3BVFe>XE{JB>H>93BMn$+Hcoj7fzIKesZ#9RyU<9VydNQOBm4umGZ5IUlUm6 zvHK@sRUbPhUEknX30X4Tgv@EvTpibJw^KgNFOVLriE?#PTwW>0cUTAYt}Dw*C!c9! z_pZwM(gLo~tAfMMrmywx|1yJI5HCaL^}L8djy(exyTI>lbC*_cH=_K*mM;Dnc<_{^ zkqB469MU{A!SCp=TO9>E!gx_&? zXZiF80*)_p3w=onOX=1}t|R!K$(ej2Uy=r>g|t!wy$u(D3Yt&@A4ti6mlimBw)KX8U!7l30k{-*#9_;N)z$I7ml%9R#>y#rB z5|S7|+~#f)#2ACA1CbHO8Yw>Vk@j5pNHI~#!;sQA&jm;6oVY2xFyD|%g(k6Ru8P^T zR_5z;{`4X9s-gys<%pj6(LgFv`tx8^L(msN(jDNuZjQ+}C44mM6XDoR=Ge<~P+A=Gp%* zxa4)xtr(g#DI0iH!`ZQs^}#8PuM=yLdHy2v@JnBETFSLGTQG3PM-BEVJLi|q`3o!R zKHl7*tzxVN>o$4oHLnr|wcEn~w+$%hIz$_X52-}j2oX#YUdGIeq4Z{3N)%fFJGX>? z8}hJz8ox1kgh7P^A+Q^{j6CP_Bnc~57AezoMcpxNDnVgT#LHo1z&_Cwa+b$cbdCL8 z5&al^lHRR``Omp9l>##;aLz8I(R8V!jo;5gC~5k_%^FW*gXaebG}kP0-75on{yh9M zR&@wsPly<}Y(Lo_EB2X96XvNlMy9EvqWm+o53U}p<4ds=Anfs~LJQw&ANu~0lq~)R z=vv4v!J@gD`M~b??Tx#iQ0HQZyoBUX^M(G6mcBK^Y8Nf{#QK)%S!HuqpVtqs`}L8* ztsb0&WIkV+X=zrN13e(0d8KR8ak1frkhM_tgbl?FslgLM7}JtVl-xq;z z6aylQ6^MwIzU=POr*&@`!9f`S0%WW&t$|m}!ZPLmVVnPKz6x<2P=^d@1Js+mc{6Kk zD??jf?&bK=pw5Grn3PKOQ87eQor7&Q?p9leny+ak8lvpu?cJ;fQtuy&pj5(KXkFB8 za%<5N;_Rm6c8T^$TlY@YmO0 z6>=UQ1u&0)VWp_IZi6=*O5=1TbIWs+&r7N`G`J_UxOs~)6Fy}(pMA9Y6LTU zT%yQg5B`w2;>K5%zOyL6Y{UCX93!yEXzC_7PVY|IsB$9H!ll5~$Zf1%1s#!<*h_HPsiANF^<>fva-FkNPB{PV-i(~hq~_j_&a zTShV}0O&?}c#HQ{IVH)+=Yl4I6vDRfncpFN>_;bEmsa(Mc8d0;Sms14C*zKG@8X$RSF`Ho$@w;ad&d^Rezk{UO0IhV>#qYBA6X_IpN7ho{=A0oh2~iSb|!n z7kPi}25INNhPyhx!^RT*?pr%jYKv|FLJJ4 z)|HU^b>$UG1<#Eq4MJIi?Ucz5`R4e0a?P-PYr{1Ry<ZPpsFK|*3=h~>LGh8p`+o2;zFG&ds#yXq!FzmGM2J-e4cCU?d+qSVapnBT5PXm z_fIDKC(7lC$@`^)aF^Dz(rk54*2~-X_M!dQfo%KrmoDAVqhuGnt>eNq8I*n6EpmUM z-*I2M?o88N2paWTpafCP!8V&WFiv)*y(Dn{UkV4FDL>a9(P)SLM(C0LU=-zQ(BLi@W0{nyAZE&mb@dQI}m`Umdjr zf@Zq1te2RRLhCUw49^kc z(g}a~Wy@j?cEWm-uv7ZnG=&EEmZCTxgxp!?Tx*H%VwWFwCTe#_k$6)y6e^$4a#dYyk^ax8^pt7gzG(U(b*s9kZ#I=^@cIf4O}hWJJ8n}|lI{Ly zL=_Gw>CBl4asFp*ZtsGF=H1R4_s!-1&QLC>i5@;{dp@nw4F)AmCF%uu{f~5{*J9$6 z#azz+Kk}t8eJ4!mID7B?)mW!TY4Nvr@E+8@I7p=L4E=U> z-&kQ^Jqa^ZX#AVGiV8FK1slF<;7f6zCy|`gLYr>VZGM3@%~z z0kc7%Qhu~QXWMlgX5_e2THp8>C#3|ya_?|KcS zj88-`AaBbokpr2jnVVf5RZ`)Qk_{1_zz)n0Od-Qn6wB=UXeFcwJs|}WUF2g(VFto{ ztMJlM{WXw;E0$So)HeiRDM=4n=(}zXm-&zF;-|x*awa--B3}*V3^{|h$ZwmGA4c$sR3{kC9 zw3W+8{tX`pC(qo0LQ|uHBqi99M#}#ya91heMO#}0Pcj@qj?SO%h~acLUx3xr)uc2$ z8Z!C(P;AEC@voqyg3mwEVDe}m9$~cxCaYXeo4Rj}Ts!bT} zmpg5tT&H=<>4v+pdpZu}zm}sk`K`^sEH7)LWzQD&xKmCb;z~|t5M$D?85!v$*zEGd z&4g(Se%YsH%pR&%jaieo1Mmtseek1M6E?^wGTY?hlO^E(r)1J@i9xJK%o)83SKsFzs51TR;}Gh{ z!Ug1e({-uFG7(PM)NKIc@AU211dgxyD0`@Ngh?&R(~3`e`6~r62#^XVPQY*Z}Nb*f#AC&CsR%rgcw?>+k6OA^@@%`^8yqJjZl3D zD4m|3!Wlo!&z~_kb8uZeJvDW{B~@sTmKFYK`^{05C75%RD5R1_24LEkBty=BUe|qt zPgt^SJe5L%7PvVc;ILG7OdVt9y3XJrcv~Zhral+vL8BVGQ~Zz*4WrA72F$f)bW zKVW=#mbd`_IWRS2{f`*Xxhux8OD84EF4IWK*Bn5872|OXLd*vh zDt^s3nr7Ml<5Lho5U^5xcP7c{(I`Vm!Jzu=5jH5XzPsp&nPI@TgoZd&Q&Us&jv@I( zQQ;$Z-tX}TY35s6$Da{S=hdV#9^1@%+@rw(8aMuho7R&llSl@}qDAR8;}rz}khff%L(uF^XlI^b<4*BhGR-+Y!(gMO#~2gUf;~1@O|P zYY(y)(C47U}g?usN+xUFnT&-?uY8gF%;wnm*tTe$08AKkL(*CSOUO8_Uuk*T(l#3_;p z-*-8HoYwRQ4N3&t^F<0j{qSj`A)J&*-6-~D<0Qk05QSj*-r_Vu5yc$Ee(88p)Es5H z!M(-4t{Fi0>zL$7JH^j z*280@qFpOrvCFuq^W-V2c%9cz|4YZ}#c+ex*mlWqsm7ih)?#3^{F~yy!*I?k;|eoZ z_QVLg40?_(j;>`QwD#`y{i!EqMzs#AKpzQSNs_9!@-7sEM<4eaG*^ViPcP7myfz! z@lp~|{YMsvfvc{23l#dzKA*8yZ2M>c#?{>YBE#59p9k9vT~7;bjiC!>jlQr~KQM-N zn9|%_Iq%T?!SnDQ2VleR#G)$u{F6o$^YqB13cMF@=NgRIWrdLk>_y_4pLi;yVPgBt|F-{Ix>y_+10_B| z2cawVIaNvKP;HPz^=w*}prh9sdV7_B4W$0FcmH-S#S6PApZVPcnuwj(qQP)GKO4 zl30_~%Uwxu13_R=u8vv7j|vRu9?7ld=+*w$>A1kC6J%cu8KbbW_^*bXh%#Ab)=akV zJkNJuVrZuw!dBT}sMMWJFB-|oyqpM-?1)(lI^rZcg@NYM1?_4V~r0u z?vQ_0cB5>_oSWRPg)TaU0!Y4kSzwM=hZ_GCddoSI<8s}R>?Hf>m(8e1Rh}l=+3Sri zeVwPMK@<_7QMBvDL-}<=z(a4=455qRLmBh_jL9THpln>WV#%YL!F2I@2{S_Kfp3NP zW7!1kTj#ZQjGGqjUKKU$8(`O{0X3*R`24g|dzpXplA4=Equzdw2}jT|XYz2C83`%G z`FaqzF>U&j)%GaJ=iTdd;t zmbNN}suq{f%6&{j$LYXBGPB)1FERhLx(4*&-e-!S8~<*Si?gA>36p4(;ch0jb9_3O zo>dj0S(cuTDSB9phqg=iwGLtLQe9f>fzNc33*qim2Y9Q)&4((T|t0y z%1OFyAcm%HGGRgga&iskG*ip2f%el_@1gNSt#-BaR)64)XJO8aYp14% zsem9No#iV&PR?B}@N0ZfKPkCaY)480hltXRBFM9B6QBvf8rMQQRWkpKo3xvt=vd|T z{uEu!1gdbmhsXnMsRg$ata{Y9w#r=`&H>R@pXcR*MfmtzHpVv@ov&e>G1U%Xe-26k z1|RK$QQYqjmTH|&X*h`o`ZC|bFC>#+Yz;m39T*<&#w-g9ng7Y4AnW(=5Sx&&B?iHna<9Ra;A8>o?~# zpPITMC#A_TZaOLsL}BT4R>x)@Ene}AF0Tm+!{X7#;uEPmo>oZt-O`Gckq zmim&Hk|IEzQy4!^H-z+?6Pgja+3wQhwNTdD;pD9#cI>V^_Un5=YooGNd{$RJ<1kW8 z*(q;=&Q7hG*EsQkfUcaE-FzZ@u?eogZ2+(fv8zI>yy!r~2Y41ey5HH}R_k%eTv}S1 zTr;NJH0g+vQ$D`vEZNaw9@0pdeRg;7ijiNZtgM`sXzq>A zeaAC?ua>lVC{-=(#=~zECn2Sf_0E`nA}!#Mq7#weQ>Q8?8_F=2=v#{I?>{K$+%^S? zr#Q@NpV#5Vho9;SAge$Qlt^xjrWmf@^OeQ|rlk@is+j()Gph!m3NN}mV5M@l&D%q7T0~GzFi#5Y`<{Dk9QSQF{gNGoLYFXWQKnPibMz3} zeuX`>?_A!7re5FUnP9$hsOF)VnPbuuXBB8nW0cKJE47!hL` z(%(L-uvziF6>Rd}4?jD<+>43?Ig(BP6sHpruHzuTK9kK!iHH^KUO9^@0iLt8&5yq# zvR@jT3NY8oxEXzjs-cLYi03qxJHo1`J`K=X-?| z?N>wRe2f-;dk>QmC{-MqEgLQ>E7(@akdnlBt1vzE3) z*|Bh4m<@#GPQnaszX@Dye2J>G zp3+rBO2ll?E+lKW`P*uEvenWj*~DAnSBJTeiVr^@3;c7~+1bA=8e6L=G8VnM3cdL$ zi9L?;2w4=Le^SrDIR|kB2oDM!$Q0w5sHP0@x9v}TA{s?DBp#+smhInlV_<|L>g2(i z9E?(3o9Love8Hp7-lDLAL>b!%kQV!%DP_Xn0dVKD+tb0IRd><^qC6wKRz=!RN6 zY*s%O37p=YCK@Qkw}z`!Y$-R^@XmOmmERxCT6f_4a7|PEGh@#uag1 zhAQszu8~jIiz|?CQ8=4AbVMsfb}F+!QueI4f)NpfgbBitCivR?%aSB>1i9QhR^p(H zfU&>i!9}vZGM5ujVs5mJn{F!Z+ zKM;1-WT;6&)O*FT-1^P}VC%3-{6N7v<6Wr>V-WE`%L!(zw_Dgd;(o@0J0rci(&TQ- zB++0yvx?F6cc1rZ8-em@Q z>-}~q;%i*f*W^{g_*IHKwJAO!x{V<&HiH~LnKUJ1Vnn~^5_4>UTw+X%JboUYobxutDqF5V88PS?w#-N&7{* zm7DvOFFlu3UCSg*HfzaSZa9l)R}wZUnXTSBsFJol>t2x-VgIVtWDvZPlm6;sqnG9T z5XAz;%(<7t(~-U}tL`jIhQ{!%A^x{I6$U8y$>G!`wW^mPz8rx?0!P2PRETiKzozi* zl!<$SAE%=nqK;jkKNAww}QlRrFN(i%)E7lx8~PGuy^qYossC{NA4v{9kqP0&c`K zyC2NW%?HKeD3exhmJX%d_HQU~m6yB5*sfOxflQpRI&6l-Gr#ZF@xPEuAOI%^?;BnTU zVNpG>F*%7hV?Xt8rm2XsPl%*&jIAp9PF{O#YjP&vGb2EiKu+yA z#gzjuF9IbD($%qCGaQ99*h5pa)Xgtv1YGRSvX$A-h4`u64mPB|3$HTh(~}9WoX@x0 z$v;%GNP5CTOo}P}dkYf1UL$)YSTwv2?>b;geqKSJ^OgLjI~jWxHjdmd;{}K zS`t0K$A04DgTccH?6X~xE5FrJ0cd~EqT2Ag$pR~j)oY!f|G-leyuRH3wvloF8z};( zbRonL5UAZY{(zS#jm7PcqaTB`x@hKFA6n z{lWt`snFLSpn|S^Ed5LiVl-{vg|DgoM6p$7t1rOR12bamR_Z~qf;V8>ipqq{Kjgdn zd#W9f;+i?lfX6`XnG+94*d!*~#4*ubk%eO>ws=>b%4M6b!OR zl2L*MS{c@m*66yamm-6a%Z*Y=k<7Ly1$3lv5m#Xq27*$XFIYLjeCJAT>0nTv4Sw0M zTog*h4{+B<|LN#_l8c*P0C zY1agY{x&$%wwNQG>PAr0#lv_$8jhz~+P!G0ea5FZNL3?>P0jGa3b`!2QY%gPG?TDm zqM(e=OWBq5K2Kgkk#lSOwK9>k8qK^x6kPLO4)>NxKd$NTNveSX&{_nW-RD6WF%+SX z+V%pyLq9EzeBcG>6G;QVSj^NKBS4I);45Mh2y{~Yc()=YtwrDac9(vtA!+9qzCMR5 z&U5HWhYyYCi#EJAFxUU}OXlFQjlYE}YVdkIB|xwJW})NVE*G^51$z9jVcOVj3Mo-x zxt=Ws(?%sUQMOypxnQWh5! z&kbv3?Q{micXDo_lUZ*jLT03zo;hL%TFRwalIqO7*DrA*UlPt?dy^AZ=Ozdfzv#i& zjCgX#2%IH*uVIW)4?BPVY&9dQ@JbzS=tG-N0rHVMoYQS?_TF$;ea}VN@@fcJ$sS2` zMyMhdWUcw(G3W7ESjt->oUE@vqCvfahmQ zvH{KDcHaT`Ega%O&yCOTU*ojDl)9vhhflqD7C1p6DDv)|xJ>-vvr^$WsMv_{-ti{q zo05nn54(@CwmM&y65Lo7UlPP7TJXiooJdoarM^!j9E#ft8$Tn(Q4D#5`MS|tS4+?$ ziy2Swrk1(q9L20|gvsVfeEoliH7ehuJhP1g8{3-LL2Tz*rR(jMUKh?f+WOk+&hznY zz&Rfd&ITz})u`y`SlCL58;!EelD)iL<=sz%hvKiW2^kM_OIx{z4ucny=_pq+!k9My z`ZCn|a2tl}tfk?m?Md>Vu6kMpe%pQgM31~#X5*M+wn=tq{&QfnK(IuSGC>N_u!Zia z=h=DK;7@&`y1ufyx{%V(A9@_$<5}=(gaf!b3k8s0{-RcVshb`=f7GPj<*Z#AQXE=w z_wgh+J;asfNgWY13FiXsU;>zX12Cn)z+|vHv?xYJM-^zMtB(@^^U&5YGFo_DxxYUS z=d|wq?%9RdYWVD}W6sA#?Cy{_mB^|i3;(gV1+nl#?aLVx9Nl5sJW1b^6eEL`PksS1 zP{H_Zn7MSfyLndMIC8cPt?_HU8%Y%`7(>g}IH)eY1Q_0JDoXO^OS+p=T78yQM(1u& zsUj6oK`9ZUM6D76ZuQGjxVn+ny!=la2WK(i3Kc=+mYhwMK*D;RdfP+_w}k@K&iaB9 zsgo1u!pb%=QitW_qGZBG$(>#rQzXYE)^99qDdi4(Z4~eoUI9EUv*zc&wj~0C^A=pv zBi(R$IQYMF6KXQgzBPLbxMEw&$5VyX(1qOX^s2vKV;J830@`~P+bpdf>`b@b$*=$l z9+ZNY)LX+QFZHwmy64Ekof6loam&V>%`XTinyx`~R8AeXF}tBPRlZ6J&z@Kx&jXXd z1R_aZcPxnddVJN=HJB&-rhHOtt6pUTb35J5RqBI;Xv5aq_fJ%Y*K z#i;KZ=7SX@$+c9(-gbXaeVO7Q{9m}#M1U_&Rp8F_Mmi{PJvBPo6)?{XkJ$9+cj zK6bzPcy?o>0CB!(i~orlY;wc4PPcO3?ATHU{rZaA{Y#v zPAcZ+MH^dN&-~_`Cu*L=WA+P#6j9Ngz-~Z=Ek7Us6tH{0$oxkO2MdaW#gy9s+&AC6 z|NrvMmdsprpeh2_8(e}fp+B51-Ye^KWNj6HR?~`DR>#k+9i~${-+kDDt&Xs2f&|KP zT_u`}P?R`6_33W+TO!9ddz*KIbVmZ(D{L}_^Q}-dK{#-B`-yImgD>>3+K*xRph6He z1!FY)EX&i87KTBn>1k2S4Ly*)>u9qIQAc!Pxm_p>vOgOgJ?idgN%#AUzm-qjg$;bf zkJ0~cmJ&76ahG`4I}@OK0^S4WtvN@)bz8QJtPDuRJLcOPQV2}M@N#(+JAyQ&McCHC zK6mzx=PrrQUX~*5n zwaq|Dch!%#k2ENwd=%*}wyldszP@s(x3`cv0ee<7&BNY#=+euX?4bFiu_f()ZL`!2 zczE3|nrM|3d|Z5g62{{HL589HZAYUfJ9xu}7xgXqGdB-cncFNvlJN7cjg8P703$MM zRat4$XPET>lqL1@p6MsbwgY4^lCfbCpd3^d@vWwh&eN?E)K!*zxh>Fa(`{B-ojip= zmq+WfziPp8Fkvp-3qKD<_f8+XYZ{O#@uAG2j{@S}HVx^?!K!;3*+}CkjS;@f{=x5O zE%yJ^g^b_e-c69OM9PWsmX=lr!HzTcH8&+A5SZK@j7ZPK6yMq^kd~gQBDJuz#JJSf zChE!0!}C_Gr-wayWc27$bWBXzlwI(likDW}-CWLn%~v&$?5p2etgBM8vWiO1R$nYR z*pYLWCuiwGknY*pxR_t2rkI+WOY>$sf%a+WQBn;e4Rh5e^~kmr7I(PGc{J8^rS!_f z-v3X}1h#$JzQjpIL4P^@s~_JJvr)HPU}-2j5>LTNl13zlRwVQQISltwx@Zk z68h&C7X9!@(&8T`yJ`OS_>1TP&)R z)6!#6l*?tJ-|g61 zSw-HBQQc8SOVk$NKLkY$GQK6k&76h|qUK0e4%gnC9IeNdyX`wy3(37xf_f8pLk-!Ntp0`9jVN&BpI*2`d=yv2FM*)%m< zeN2#scK~{?0`Oc2iY#OZw}42gWKQkuTx>PSE1k0pJeLEKx0(A`UBc(9{hGE2{QtU_ zxbV1qgNHlm|GTLe;{KdQw%n$`)&z+9#;X=#8+@;OlI+vWw^^CsL0uzq@L)n@s}3ZD>y{|zhk9wJlw^gR7gRvY_gAs{~KsStXJ*CV+rb5Ygx zN{!y%P~82b@L^s0!=Or?hGA;Bs2e?H1qrN&KsZ&Rri{$Y-g&NNl``XvPrMIhDWpZn z@HVtsK+mZ^vw;o`G&lR;FT*VhhIvij`gO~K^vFHWB-3=+h8=d1o9xDjA8HfHUQwIx zX2-{2I8=XITY((){f2V*5f$?p?maqQt`v;b3r`9!?-?l>v%fo{;kFfV7*K65Wq54{5TC8f2MZTGbvE|5R-nuWV{#(tOM z*u2=5t&_R+b*u*Mr=@*w_5*ZH0n>D$GgQW_9|K$Cm9$joaHbrRnqkgO%k!@svO209 zhKN*B^i2NCw9Zcu_`d@ML1By{s~sb@mAGOFVCmAX2=?we|N1@Re^+;TD>=l}LPmCSE1=l(r?gig3?7TGl=&1I@g zZZcuTrBT(qi*m(hQ(pBzwQKff={Yxq0#%>2@+W1!KkbFj-cn1Lzbc(MIR}C6w0SCip8zP2#{FPaX1jb$>WmdbyGU zn~ym;D;9d!a!K`RgGDkl;4IF-da~$~X_l3p+{e@8^*-mI`55r5pXH2tSZzrD`bqhF zY-h6MpBap@8$mZf6-+8yprD`i*g|l_yot0UFD@zs==py6(+4eK-zK)vUM}q9`mm+sSV2tJ(Jb+N|9AN?Ct@SR!-2wv?XxUljwi5S}tO zRp#f}Pzd3NVVSxp*Hrm*rOgmI#!`UXwB;2g@q;q9O5yT@pKCU*r{~_dAztZTUQ4dHR>C#es9FESvY*0G8n|YnD9K_)R_EKKn-Y$ zvht~#dBW<{chp;NB|Yp^G0!Ff3$|Ig-+U8pHTkmGVG(MEuq#YTkwWuz#0Ketb$8f9w+y z2QvxNub~9m=YImr!&R=LNK@VuceeSkJpj48m~VS*XlROG!age9UOiA)EBhejUKG=^ zFw>V5{)|3#aML)?Y+6ImW8PTz=b>LesWHXkc!Q|@1CA=Eqv6P)Ef#lZwvqdndFL26_P|o5AS1>KAyQiC>I+BdtDc=EcjS!L5i4`PzscpZKc&Y!Gl<9pa zNFTb~@mL&Cl>A*e#m2);F($|Nuw~ryylnDtAtK4YgC>d9SgR@?mh1k^B}|}^X4NxU zf;`{kWz_OwluL-@>gWB3tPC@Jw|1|CGTrti8r^$I4`j54=`zeZs`dZ{z8zZbAV%Jc zh|UzoSG=@o&@1n))GTJoEo0@qrIMPJGZSbV$G?h4AMW1#BeYovS4lA+bG3zrzMzvrUOTV0u=m(7OB7XG}n_Nh;U<;Ux+vS zx_Y#&5z4vB%T6}Fd)0fyWU$cD!|q_<<$(M%O<^?o`_xg6dN)~q5e_uF1%$%5&daKn zL)(3qmrSlKT#(Xg?PYERH?*71cZzG^!ZJB`LoGrCMu_!KKX&roL{|O2p=ln?e1jDg z+vd?Z?zj7XNGeE`$HMW<1W^%5t!dlO>PAj^n^}I(r%IkqjUfM-X+~4BNgnFLwCsX;^Ru%?V4ITU zDj+qv-FBT_{pQ^G^nG=Z!$jXNkj=)XpYfs=0GB11GP6R5W%G=c; z!QZ?BXvD^uGmeH=P7VcWBiu8-QA3LQFVG|~PxWq>I_?6%k+URNp|zW17TF23*^j1+ zS$cdv63f?{ESugvW^?KWEGu`k0lBh?$u>$~%W~au0ZD;1$Qkx*M@@#9?{^V$+ZGp@ zi5wbW8Jo_XBMxmxC5VFt+4iHZI1kQj{d3=&Wb_*Yat`8emOK=ClmiNzxpU7;amb0s z_L0yi9&WqpdE$BfuW6F0Im_SuVa5vI=}AVSZI?z}m~xk7o24yyM@KWe2`D2UJz<<> zVj|*)aG5yvocttCbpnffymXxuCQ^bP{&4|7T#rV$H(HY&7DyV!_JZsnd{X6s&&lhq zS%VwyF)W_E>lF!MjE)(mehT z>>Ufpi{xi7R1CUKH@?^ZCo2(o{lvDZ{2Z4Hf)oS#1eyT#*I=3XNzyCiY`FPDzkoCQyKr^lUnmZ$cXI5Ye1PK9%wdfSk=&7ctwrx)tC1gojo z6ol-Oxkmlf{&yz3A&ilB{2qf2cf%g69)qz~t>yW8mG&!s`-2@;A3RYQT0J7FPljdy<`vl<&AL9qH@PY8ge+E=*Y zk=YPzZ}&TN9HlPrRu6L-Dve_t?JVn`+MVe)zQ6k6=Yx;@u)jc6x}u>ytBzQ3g3X5T zW<_D*TRm0?PP^XLaG9^HKc>S#b)740!MVMrD9qN)Det-SRlPU<%RutLf%%iyZe}6| z->D3_r%|z5cQh`_M}(s9u>6vlpj~qO@b^O|v2`Z(8{H&_0iEt^mGzjzl0aZ2x=9@3 zS9|1-o7B7TcX6EJfP6{?hh>rgCCnr9jQdR;JMHJE?OfeM2rE@DTPZshOLDJ-zHTqL zwxe(RO{k=HrV{?BV~2;Qz?drP?zLBomuyT>(w>d&tSIhD55iLe|35?+lx+onBlt(J`>hOa+{}ja_stI1I2nu0^nigZy1>j$kt#B*ft#TSh0Q=xLX| zWh<@IWKvr&%kRw*mv#tb$z(xF(3XwHWD}3r1`=9u0Ra;>f1}C)EtRg4<1KqMu|SC* zTJFX3EmR>#l*M%b1Ojf{yh=c%j-EecTpj58;2Xg z@OzESVNjM1eueWxH+l zIOnHo;SH;GC4x5}TLTttQdmlJ=EG07S0@9??{2sQWCz#WUp0Pd;)1L?mtt6>pEa&c zMTTdLha*UF1@4#-FaB9jsWd#n^X(t65z0CB71_6gKiSZsAv$B{`F)6cSXjVcA%%=$ zwqBX?hq*C|qmCmX>zO>3J+USB?QR54|8p!b&!=xKfjFZq&($p1ZhmxmQ`~{cfgg8u zQrtY1ppgJH4PDZYsj~5M4VcT{>LCqOti-Zu06vl{zjsVDe=6ze$KR=tZx{rRl)VIW zAvcHCR0}zEj3y=re%;4g9Z#&snh^{Wnp%6H8?~{hqSM_BWKW2jrvQK6+_J_*f#}9c zJvNi$E?e&RQoCycB3%P=ZvRptwbGnKLh;3%wC!)Buwl^}#Z-m>Q4bgnF z^QaD#a9$@vIQR(WsAe!oO+(-fBSEW(KqT;}w{ow17MV2>!&k&s^L1Wsj7+anq1765 zh@~>*BoOy;IDgLWhV`I*XI_^8F~u>+`zW05x(`9SF1*C34I_b_KNBM0HOH6>;OjPY zxOPUPtuj=W(;|9tO$UR250s`&ZS*Y}%s%x8(sC0LlhW>x2l&0~AN69twM&oNumk#X#12z~d_k!p`o4Cw{nSZPY? z?$~dFuAV^90?^JsWsfs)Na0+6A+W@86+3Gcg;YQ)r~|YcQP;!=u-a9R!vc6YT|9|) z&})1Au&U5Y#jgLNdCS$Asx%fq7={JtrW`~F-$?mK-efMIo;zw-y|2Ytq_cVFlIVTC zE}@-m_6viZ{~SB5n%CWGs0Lp7@EQ%%lB`Y`_Wp%i`zK@7c`9OcpUw0uS&XXhV#BrmWL1@w z*<~F%wdMz$Kh2*y=Gw*-f6Q#)t>;Zs`S}5CFR3i&X1B)8d2=Sa<909EUD(MT&>vWU zv}17o7T8_Rm%#MtK52Jf-FVdi7LQ?UIn9+&Y^MvDSiZYf)h+-IzLPs*T)-0&({J{$ zCqrL9(Fq^MJ(>QI`bjpa4=4GATuW0{@HcoY@kX!1?S{u2){bSv$tNLz88#!6>ch7) z+6VM36DqlqgziL&c&$+W1*!m(<2l3*(m&P!iXKWWC|;qIiP|q-p2>WVVsrtafP3Mh zJ?K@JDcivX=xBMQh<|)OWrytgh-wXIFC|96!K9e15%Uoz}v5f#h+DAJ< z5<8~awD*HX(dZtf#n~N*wN})kgz3`?=fcI~Y`j|PMN=1(u6-;-S}(&&yQ==1u?pmO zvOM_vhkXJbq!+SA{EZ^K$E+H$Um288_(ov_?enE-t;0pY!iDRKckyQelx{(fGt^v; z)PwI!harD(!50_jSw38PwBCOx?IFa7%<6`USCK7ynD}peif!-t;E7t+>`Xz6rFKk; z=k=8904vJ5?YPD+xn0}qDcTc@#Cmeu4$+HYRF`y#)QWCYCxg~g*WzL#G9wi^Epzm$ zxdwl~1UAryez>$8{$=Q>pUFGZ#CmowBKufT69eyPlseV-y$*8&8tzMf9ny~3@t=$S zbosr;X`omN_=lb-2dR4L7lQR4=&|pN^j2LBAgFd3Vh1fA>#av#lt1;2Nkkf&moZim3X~(=4Ru*xP;HY2ZEyuiib;6)0 z$Ik%jFZ7O9wPF7z3kG3P=wZID0qMO}YEiC$>iR394SXp59!wk~YPp6u_XC{*2huP` zv~>E%dA6ct5S*g`x@hl-EEk&XUoE(folgdH=VpU^US39R4Tg3P zWjoDLg>%QqeHXx928Y{KY#?GM^1YJ=`DeC>E=a>i^zP>d^yO&}#m2e1B#N_z2Kvp& zlrn^gS_UsovIF~>bZv|~?NxnXCJ-S%I>b58+laMLz4TX@J$j?dU#PqP*SD3BNX!dD60)_itJ>!R|lMIjrI9s((D26V&~bOR!MTSM8C-TV1IBj zN@{9*<3}Iejkk+MPLri*cDsdX)jn#BU1LI}2Cq>Iosvu+r@0F85oKOfZ`*fwjk{N7 zWz)j#(+u$l1iMfi1(_d%kJ65rx;E#Yo{?!{2X%BqXJY)C<|u#e{%DKMuhN!1CD9WR zQ1+5i%%HY&CMlj>zH_BXk>w$OWbj^ZoaW@4$9xa^piw!^ZY|;+u)x&U#LMk5g*~V`0IYWoSMtdGBP`KJSr#16YQp!j-uM9SVfF z>lYS8my$rg_;!po4i~T(WiC8NgXm8Y&w?-)CeXNy6tN`!aiVe{88Rizwl_+nJ38ui zpF>w97Xkv+IJr9w44`^r2k5SSTZ}`~PTh@SEM11|wL#9!=HA^KqekaHHA=;{#Id(f z=_9}(!Dzl>5?{?RKESB*Hol&MQtz*)Y`c?n;7AlLlomdk_$lhHET?^m`nz?9?;}+ug^gw$?}E1^Ug1zkb1UD7 za0{H`vs(%Z31dXdW(JaTo23q99AoP-+AFpVgpuP~);)f-h9ZP&y+Il8mr%+#g6|hZ zB1;-vmx$ObpIUR_wPy;I*Ri0-;)wCHvmQ}dVCOO@aV96GdGmmLWits;pYPbJ+<33+ zoe^j9%`qO#I-n7^8sKa)gEq(TopO8LH4_CR5Z(Ylhh}~)f5!V-w4cUl<#*_v59?Xd~RMd>Wdtgt}Lm(5q%g+$0TlFHY=!3*;UB#VYzl8!#Ju;c6Wu6r2v! z20GjYp}2_l*#i~UG&_)7ZqEhq_-{GtKHw@8I-c9ACt;(naxYxEH@mbF_9)WC9#nRQ z)uJ+m5WA8A0s*4!Zrpqsvf-rM>}eXscr|u<@wC^IEuV#I?D~v{M1EXYJpd7NX#u=0 zXHeQAJWoep&$tR{TQ&QzncuWVxT|SQT#UBjLy)RTTLlDGtxt%swHFMewAWs>PDI$- z#MOb7<=7^IUF#IOFlD+|w5GTd=q5lWx?_&1xb>oGpL+!#Hai;*?t7qU)QbYwlzIzh zR^7-$@C?9^i8)l?#jvb1e3*PdZp1$>X?-oFjrgrOG!)7=ceJ}=zth3kXZrFcHS z&6gkg?kZQ3XV3d@_7<*^zYCqE!^S834oY*1BP$VJ z`w&;p2Tom|fC81|9Cp#WquNbDZXe;&Ao4{}oLwUz({RLuvGIwEqN~dGJx&E zoLlvype!mK$Ix0sIalF043_l*Y!Hq-$$vh)z{S*TPLfOM41t z%zk!>?-w^{7jveC+yeau7{UG!=2*1|I(oPA6ukYEk59#${t?>uXamQQsJs&s!j@`9bb{qpO1cMX+yl^KTlD^|EgG-dbvE zJkea|VV^+~0EbWfj3*}ALUHEbj@TSfjIQ|DGkp1VwvE@XGHq+6z&ZiWFUNlLebm&` z!WZZxXs&(z2}*cEZluy@RRNAYmpxTCg=~>8d~rHpBaFtD+zqZ`kziUd8>^3%OEqt* zS0}4dG6uU5`&bH!iv_zb2zzOqGNn=$*!(P~KMq(tm$qWQ99NW6@rgVyDPrY>L1z(b z#rd5!9xBbk^)-q`PB=zq$1QmkT19qIi!?M-bvjr{&Yi6aGwycQZag~?oMia0{aG+F z+9(d05Z_l+TZPPL>d^%ADa-L=y`W<8TY95I02x{3bT?h-_gXi%ioI{w%RK3cZFlt zJNs4_<;%Y>b10k}9cNzf-3<>%3wP}I!A|?yMaaK|yG_N1wt5PYv8kgF8*VkS^t5bC z(>y6@4Hcx&w;!i`Up%sAee?IzU~KJXH0ScZQw7W(?zNlJr3aSO_dG1sfibOFSydq` z0lq{gaDSmWmIsuCuB7f-LW^$sQkd&AyMp^JUe*ti^bHrCaGTA~at;9R?JI|n>o0~& zTnBEL<3${BC&f%8cAfQdM@e1g`4|vEunITn>FbVMC-JTkoOn;YKD;~n{?s7*i1o1z z$h$HHQ{EcWq<>&=G@^=d(ni&N!~608S1$k*|I~q)m$2#PczbN~Ig~7m=#PT)dzZv> zx2vT+r~1d_^Ekt9>V~#_es*DvIISBXe*DGN_eq95y%M8Sr&;(>O1TSK^^X>3j|xQK!9F)^)zWiTIUJb?*dbk>lr$pqLxbmaX$7Cfl5fGZF`);BvvU3QzK#U znmJ=Q)Qr}z%!Y|fvkSRZ0J*-PDjw1@C*UwudmFbOy^0cSmI%G#-e1~Gd*D}1Y>PAZ ztvRq{D=BY;A)IXHThhv!*d_GELSvv{&!2>VEv*x)NlJ=R)cuPuP={GO19u(1$#K+6 z)BeIId24{iwa9uF`HYu<|MZ2qO5fS?gGC$WLJf;7-42j&1+9~b`YUfSRI_!-S6QFh6j*HR= zN?O70n$eT^RYw@1A#l9*9gByqDkFPgj>kNByU95`t(tZDoUXA1opy697$u?1@iQjv zcgp4fjWDVU-;1#*IhJsx+GpGdM4MR;J`V)e?3yFNPYJZ>yvx*T zU1Cz{9(nS~7z8bz@!pOtJD28qJ;6lv$8a$r4;9q49ffhrs&^>La$=>ssBeQnMNYdV z3+%Id)!#r5Xa&UUF|9N?9hS?P!-KQ%Ckk4QPp>TZF3#)NEcafb(^iOn1rHxYD2e8u zNVCoHXj8zc4=Be##Ap>@*$rJn*#e? z8#al(CtNf?yI5&U&Mgqf0)Nb+`uS|Q>Sw@_U+o5!qOCH*P?ykNmV91@PNHoGo}O=C-I+X_dMVCUyJfL^_<|3F#jl1%h|2c42osa=U2vOao*=JwgfZx;71Zjb?~ z7M^IZ4**(EvjWXfxxiQlXh=H&Got@vi85Q5H9zyBP!Q|<9N@=O=v=L%)I61ZhvZj3 zS2lcE8px{7bhYt^(U}&l&OCHWK{FfcebP{HPLINgs9ni+zwa4)#1rqd z&mgTl2fJXBt)ivwu}tor+L_TjHWa~})v1f43atm%qr@L~@CEGBQ9Bi^Pc<<4?d1RT z^69Q#FK70>G&|n5Kcb4@GB0ft#F;frgGynA^9V#O&H4XLSQ?u;l!w5KqKG1=H<&o7 zXl7f~W;3d|BQzA#@OKXosqU}&#WKTqDSA#J;@A#2F$V4VU6OM{2<`3eOBO%fhdcQL!UqihK*ObeQ1>?_Y<#&i=|W5#XV-f)AZR5{*}qm3I(XR>SXvTw=8ZQfj?idsTTSCq zS)6qvyqvQ8&41B({&1bd|LAY?MnK$&)YAb8iYRL#y^hg5Tm|C^I%R= zZ7o;LAp8jNS3u&i$cv)Kb9@|ljX^O_@B1)qkt6=Jj?5br#=#O#I<4G`T4*Ojk!68_ z(A<0=kS3Rm3~2~gr2{8)z+PG4;>U-T|o>Whj} z37r@bb_jyHZ!U+^K5pRq$oH?cItZ`*2U#$27y;>S=W4c)OIl?*Z7-N} zaJ_Eke|}Fm_~65Y@!GBT{7*risZF3(5)`hP29!d$?!H-4%JTlh)DzGEvL%b_ABTkO z3{igJjeN8i)IusbXF)Duf5w}a^JI5)odY_ z5h73(%ihDn`~M7Bfvj{vW=NJ~4Wzk9{AV(WOG@Ao@@zIv8rW_3UjC061pk>nqqe4_ zt%UT|Er4hk%92bVcS3=^6Br7~+%CX(Nm(C&`sDiB|4&T1*IUxUYH&5d&&b2WCd*M+ zZ22SS2VCAb%-jBKb#t@!XyOht;CUoL=7lXARMdda${K3)zSp$ZlI0Z@rX4|*E=~&- z^Xu~sZrQ%>>et6bYR^R=Zq-I{|5VTd;}#|$#f{-AEcGJ%lHcG$fu$t(jVfM2!OT*b zgCL%=*Q)2i|6w{69hRHEmTRpWUoW?rIhYHk{bd=)bUEW}xlX@PqaTiPJY$d_2nPx- zkItDjNwi?H_>!0?a%xdAYavMko3W* z5Mgy-aoj-*4@Hkw{mJ(Oq5Xc5s6j}i^>np@9%uZsZT-CT5EE6VH8MDtfj+%*0}08+ zJ#iFNbVpY4G(Ne@Zbhp2)aLW@EgQQbRh&SVnY=Tpx*0LnrcAX!4F}6G6f|r)a5xH7 z*SP*$&=YXDc+mpa?&UeeV{1=w&z&{G;^Zv>LHF_~zbJ=+-Y&UFLmUArIl`%;KBW~s>j0Cx$RsmGBsxB8n0_n7Mj6(sFgE-9C z>qVmSx^xM69tX=gUkR+$R41-yTI%eyS3w6?M(h0H9isj<5h5%N6h-re-*+!^%i5|> zl_k(&W^wt8-ldr~CNo-~ilJr5EwZuzWYISyOVcYKqGe}i@6RsWDAGW-KDm#Zkf_xt zvol>8qn=%Qrse^?M35^>LqW%enU%%x@md3=6B<^kYJT?{v7GsC?ljLj8oRga8uH#) z$r0QVO`eoa*~)Tg%oaV=U@^B><>Fk(PEO59ZjawJkSr2oZKb@v&+Y|xO*`{c1adKc z;yW0~!HMQ36SJwMIv0SkEV|$M{5&j@u(79;uPP?oscpTpiQDr5hRvo$@>J zWGRh%;$Q`|=1oh4VvBJ%ZTvUg1IKYrDPu<~6V-Yz8HPAI(%Em#!rl*Wv8w`LS7)_& zZ?d;%><7H6#+NfTRs$0rsH+K`cDB`ps5}V$St1y-hM8|gj_ zi7-b9xte&^`wRMb8mbf%gv%{VRWf|(@z3KYl|phBx0;`L5$I~ivChQq;$&rf(jaEu z>m)a^DmEXs{N920^V_%fq73AA1U*0d8|&$wz@Z=mo>1hJ#J`k*IfMMDB2myhxQ3@- z4DW|T=#^ZOKc5pE;R6BM*S;9u3mo*^%v_=)GB z6*ai_j18s4-v6Qawy0ODfI0SoTC1y09Ama>X`rz~orjmCr*w`sOkj+Qpqm~kcmhno ztj{)`B?gK(HeEB^rfJqL}ggOi*g zn?#G^D6Jm04*9G8EJ$tF_gf7^cY$OGJ9!*zx@cN7&+<h?^132Pd=ybJ zQG7BB%%Qi;^GgpHa5d;VDk?gzoH&+slW6McIQ~14oi|ZZho=l8Om)8A%SRh9o0kfb zw$&?+Z;kdoethEA&0wiVGFEcr&d{V3CHrJEJ)qM1mc-Z(G5|eCb)p+m-}z=OaJ0f& zgeFQoH&_P4>yp*2F{vRAbW<5@ml$LOD^$yV0~Q5PyOsFF+$Svqhdbgqg{ z4&;u`^#pN|q@!yAD7UKRt4xVbY_BQ4aHf^c6tn*9S4}sAr?o1JZO!c4+3MfAHnTMb zd{xy&C-%wK3SWBQLVrGI)rWD3kd<{Yu{J?zV(hgR>OBOBZ--Pu4k;^RQb3Wt>5s^( z@nO-Za$zO6-7$lk6+pg|-?2>a<7oAY5>CjeOyX9<5w~Ku;H{uuD}i@=IHx^o)ecWT z-fbVK=v!zkN11KzuZ|~%N zf{FNBYRpcQXmqRc%?#nn*e(7FNX&(fKUU_8+epQ_X{4^by2EM$6LHu_)6-4TvvXQs zp8O4I3`>{IfL*ubn4*RgSr5}#6>0_JJ8h+1)Cv>tqH5?{QP3L4m2iSKIg71~GMZ&7KPrvsh&qB>o66TNOw>T(YHM>i3d z;vHUI@I2aVW=OAlbdj_rajQMF)0)e4bcG^&CS;CHy*U+;911A$XSnM<^pN<$K6PKE zXMA>@e2++TH5@GV&JkIEI^)&P1B%!({$k##1SY)oz@KOxpfAd7pDG?B2N3o~P2Nw- z{*$}4BYgH(Y4Fh*r|A|1$md^}ia)k~|3M5l78Y_Z(jCs%Eo zEv(+R8)(`ThH6h%zd|HX9^^(=vO+==pX-?L2Lup59w>>+kJJ=}hKo~{yx*nIJ{+Zi z|53pzU<; z!=A}s{8pIc3}`CPbc+Bpv}S^&th2>?v1m)?X3Wdxcf*IugHH?Cp8rkdiqPZf_$6MX z|E93$Kz6#>PK>RHY+8(G;1;dgsp8LR;&rOrwNGSd-?;k>)*2K~{^(LcQt=$4cMe{j zXZmAHWSX(Lo&X_sPv%Y^E5AnbOb&l%;LU2h;9aCzCI$3pDzFOu4AoVr$TN+PZS~Fc z~Hn`1WU& zGH-Fj4mCHIW%9JuwIDKDB4)kiWkQ^<`HR+7Z=u6Js~&rH)12pa|8SZ7gW(t%vu+u9 z*AL(L#Io5hZyDrGh>by2^)*eKWc1X9HZSe9d&k?2F8ys*Zcrkm0XV`*wKX{=Ywjx$ z9T%8frS|pzDlH>>K?MN#E7q@|QIC&r_p6AKFo(vqC!2O(ErV8*MBVK&6!F%dg*0b! z)mJ{{zc~t#KZekk*-vd)t|)j&V_CXzox)fP6fT5Jf<0^JY*jpnv8PrCCSyWxwXlht z_>EDrdW)(O(NRy@TbLN{a8gl*0N1UcfzaQ=9==whv)Eo&kCEL$x01u26!nX!xkU)B zo_Lh3b2MKgH`i7CP@hd~5XZeRQul)A1nDR-pc-pxp|| zt58Yu;hr;c|1nL`nT^V~GJXw0^5^Cb+u8N0+OkpKfkNf4$thCtu+@_Wbjn-<(f#RaVJkqEV zX<_|T-dWAH5{{C?{FBikPt4+m41bfGli9sHz}L{uCmurzl;t@HbI38q!ajDkZ{EYz z85+rE3}NSdW9~Ci|L{4lgzunGC@zvZM8x)aWkEDiS>24|CtZ&%<&7c~VD4Fx1GO#% z!LiNTsB3?0?&J|@dB8H^oHBi={W?k}jv>E`*)u%D00FQ?hmsf~gx>lD*d~5goK6&| z#xm#kzvn!EB0E$)PDK4(;bvQ9w{Bd1Zq$ytgZ2*Q6-~NiH%%_$xKH^q>_#HpHz#i4 zvmuVN5?=x93cFAixpQqg&Qpf1JB09x?#(^Q{94dMU(A~vLv(B0&_&xo)md3&d7;2+ zmM3agc1{_tzRUlVQhIJ!fk&KMl~js#yD$Cc!(JV*05j(v+!6kk`v3Nr0<7v8g{gpl z`|_5PZyy4HZ#AJ}i~H(UFZ}0Y3ou=_neKG{t=ahR4=TXQM?B>Zyw%?Sd({8>-`R0|MeP)OPuTSHL3khzx?~q$nP2e2c-eW>wo%L27v8luY%!!8}(nWe(wR) z%zqU5*ZY4%fnO#78#O$K`;H_2W0F=*05!JlH2>4jNJk>lQSIT~X7(SGfXM*|h~JRt zfB1PZ7l2Ksjs^ceNqUQi(*IBP|Deb}?D>Bs`(jHhtm9!1OOq|oiX25&O7V5EB-sCd E0nk;cf&c&j literal 0 HcmV?d00001 diff --git a/Svc/Framer/docs/img/top/file.txt b/Svc/Framer/docs/img/top/file.txt new file mode 100644 index 0000000000..400fc3049f --- /dev/null +++ b/Svc/Framer/docs/img/top/file.txt @@ -0,0 +1,13 @@ +fileDownlink +bufferSendOut +0 +framer +bufferIn +0 + +framer +bufferDeallocate +0 +fileDownlink +bufferReturn +0 diff --git a/Svc/Framer/docs/img/top/framed.json b/Svc/Framer/docs/img/top/framed.json new file mode 100644 index 0000000000..300491b337 --- /dev/null +++ b/Svc/Framer/docs/img/top/framed.json @@ -0,0 +1,109 @@ +{ + "columns" : [ + [ + { + "instanceName" : "framer", + "inputPorts" : [], + "outputPorts" : [ + { + "name" : "framedOut", + "portNumbers" : [ + 0 + ] + }, + { + "name" : "framedAllocate", + "portNumbers" : [ + 0 + ] + } + ] + } + ], + [ + { + "instanceName" : "comm", + "inputPorts" : [ + { + "name" : "send", + "portNumbers" : [ + 0 + ] + } + ], + "outputPorts" : [ + { + "name" : "deallocate", + "portNumbers" : [ + 0 + ] + } + ] + } + ], + [ + { + "instanceName" : "buffMgr", + "inputPorts" : [ + { + "name" : "bufferSendIn", + "portNumbers" : [ + 0 + ] + }, + { + "name" : "bufferGetCallee", + "portNumbers" : [ + 0 + ] + } + ], + "outputPorts" : [] + } + ] + ], + "connections" : [ + [ + [ + 0, + 0, + 1, + 0 + ], + [ + 2, + 0, + 1, + 0 + ] + ], + [ + [ + 1, + 0, + 0, + 0 + ], + [ + 2, + 0, + 0, + 0 + ] + ], + [ + [ + 0, + 0, + 0, + 0 + ], + [ + 1, + 0, + 0, + 0 + ] + ] + ] +} diff --git a/Svc/Framer/docs/img/top/framed.png b/Svc/Framer/docs/img/top/framed.png new file mode 100644 index 0000000000000000000000000000000000000000..7813c271fb6573f03634919ac852a80ef0c85212 GIT binary patch literal 81211 zcmeFZby!qg*f$D@fFdQObR$yI(%lk*ba!_REg&sY5`utqcQZ87Al=;T z&NSt_r)d)yHCpWhor4Ns5oCCyvBetruc2)^_m%Z6$$Q0jxUrQ11>|vj)hSnqxF<* zGOittT(_|GwM?U=-`Mv$pH>=ycr*t#ILl8=YDw^)yS($vHcwf}BD>5&QaZh&U%?Gx zVM0&8Xbb!fo0eQ(|Ddw06k?O!glPB*<46Yjjcv{D)uaUl>-?c_J2|A_`yijyVlwN}R;!4hioW-)ere3h@;8GFgBZq7!ik`Hzxt ztoBZq`Fw^iXG{?Ph=eD7;O!CrMo5se}zo}AB8rEO7IHzvsc~&YnF;GvG7f+`F-nG zh9jI+B24&-l_oF!cu;qpd!p9>Aul0t>x`j=$R<}YfN zFRwnlpbdJtZ!bDedf7?2!hy+&KaYAzGO(7+ze1NDc$8=#Ff38WCSE0UBl_J)m~b6K zWrAWKs<}KFHAallen-Y@-1WMS-2V5%FH$@bIDW7wqZV#$#@hkXx`+5SHw94>NmrW8 zb%S-Giv377jy;a~V0E18`(}YY^|7GcK@x)N5kV+;_tb#&IFq^tk@ss#x4Z#v0mbk_4zq7ixitu?=E7Qxn$>fEXC}vl-T|=OKBs3HXg+f|(C*t-mwi}owiS_v&Z{q8!1_%tA2^o-%!U@MNT{AC_;m@3#^L$ z{Kn=WS?AwzjQBHnYt`w<w$o7`rPvRZLdrU7BqIQr7k^w<_l%mMA z_U3?FqYYnqZwe#X!2`P@boH8n1^OI6ZbCZ)7o-2xxQJO3NX z^T z5tb3E5o$@sa`bZXo5q6(gD(d=lGHfBRXv)Mn%0aZlSIX=#YUR7RUTD4vzb+y)lO9j z7Kanfd3V~uSw_X!868s^S(Tz&Rr0*VnOeg$&LrOC-n4fNO`-{TR+;@HgX4^o3#D^e zbH%xtTR91NTsoy64(oIYpBSmLz5i<6^}LI`ORg)|psPc@1F<6>y^vs%XD{I1{!Yl- z&nNmG{*Le_?L{IIIg$oa;S0+bB(GM3E`rux2 z1E%q;L+`+YUkBO;*G=aJlLl@EYzD9g@DoYj`RWUoA5}=zs#}eikJwmPa!)$On`Ce3 z&{xDI#0^_EO}H0gOma?2Plgv;6{XE>&)Hi)w|;ALFgI%b#M;TG-==g9Yrk=?Vvlo< zV=nXJ;6en-3N1v>3kVMAF{l*nM`=en#9GDLptR*yBG&kJ{VncWX7A~#a>~{z~eeF&0%yXsUaSk zX_+C+PU|6e7Vs)LaXxXW3#+^HD?Q;QyX&XDqUlqIvpPBl&$Y#FqDI7~PyD};2-Nr#ek^Q1WQDdID?P3broE*T=7|{S%-c-g`V65kDWNi{*LqaNl zo8=^ZND-(OUnQgaUbS(vUedoGFCpdDi#bE3VUx;qo8LlF8}~rv`~5IYFMf%a(P4IF zXLhV}taP9(t=ze*(tp@r&vcc|osH1!$6%5mWW;)MZ{I13+ro)pOLIVnz1B!~x{?2s z?zD3Ap}Ez)ZTIOR9t~rWmT{x`V#Y;UyH5eb_?z!|i<*025agv-sJZl*(o{BKybt3l zzRp`$CMLT3#;>(|qeGcKOn3FZ?l&hnxFqy7MN}m?rH%D(^(Rs%W(!eOYfE2)b37QG zY({3?AUQ=~^;Ojh7k-l_FK;aiV~c&Hel&V6uf;d>piG9my;hn`Iax06>4ByB25NiR z3DvdYPAx$jY#VSBzqO}Jy^DJ<`s%k^Vg)yv1HOmwDP~;o3pd=un+mN)u#LiADjRMp zF0N<9MM<6*{YG30l;*%{k+iX;rmx%*3g6|o8nFE9b~#*6*|*94&8p&>L1~AIWYITk z9vMN+PZ6Jn@(xO{CaWfBrfP@?or=o;)E;cx$+zs6a1}E1mbiI!KI;n=r@c|Y`?+Tk z#qONa_kLpWefII<&T(#O+H1F*9qZpSs9PdKDFQ=0z9;@mfj8j-_>np%4WFE5)*R1q zFX<(H-5&1DV+KP&^slHn=8r^(8VtHRrv5b2Spz?GSlbeLAZr5Y2x* zU%pMZZ_&#(W`;YYlRD)V6nXwvsmMYwKYG-R;ry^VQiQSz0*OylHqC ztf)n@b8B((oSMcSJ3aFL18v3-Z$fJF6!7rod!XAHt8BJNlTMRunfA_y5*(lV_{#gX ze4*b!zkRM>mcFwC*EoX)$M_nKhp+Y{&6^?rC;o4SN}r(I(iZVCqlX~Fsgx<-c2yF> zy+=tt=j%aBUd0y>!2DHGA}U8+;jD&FjgOo91*Pfk&MpF;Yy$pBe0FK6w!Y<|U;fn| zF&u$ooS9-E=E@HPtullK4K@psE8*{3V~38n<;Y&x_K5-x*gb!L zpTq>gAp?KC1P;(Ig#YM`qWkN~f1JZp0c~)?%A(TJz^}5Aqlt;FlewL9KnC41aN(J~ zl!g-=93D07fR|RHIs(R@viPL#tSlx$-vmo(1ZzOV-NI(gX0770H-!4&IV*4 z8*5u99uPmpV-FtS9Cn$Rg6y%2vlTyux||}JsGXw;87I>_rgszq&&kNh_#BN*d6dK? z{<$6ai=V>W+1Z|lnc2d-r2&=mJBwofuWs?Gd~3d>_Pwe`8!V&ki~yJ$=2x~vH${^VJ*xoOz)Wg zb8O&NKG;nr}}@plZE~Ny7j*`{XcJ2 zaWZifwX*@9=`8SH^7`kw|Gn{_8~K=Fr2jWo{N?lGRe;d~&-s}DQ)mLue+>O#1LR0# zA*S#N_yx4=@e>1lzX1-|FK{IO;71VhhJzD=lNJ;H1cKjNaC0Ww`f+%T%)KS_`I-JV z3OXemap~`Q3^VbWT@HLR*shz43qMls)(%qdd@p}4G?{IZq?McTO*Nyh5gE_K#5qxP z{uK6yi*}M zpT7n^eqQb*TDf}luX>XS9r?HX&&+t7rT#YrMCMJD?(Tm_BfLNUE!w}BFszFc4jG6= z^1VRNzoQYeaoO(QF%B~^6Rs_syZxBu-%0)R@>Aa@|Ax(EpIeEZqUa7_eTyXjpM?UW z5s~?d@L#IZ=9@Bhe|%}_m~~ghhZG+Q>6_WJGw9T&dFwyC4{2%r&ZzX@@NnoevZZ`c z=vjqK10&EcoBG`ta{Vm+kLv{68^;eljI9ABR1KpRQ2xDJg1S3}Ed`d9qpN5lOee_1(iUjDw}ts4D?bbW9S>Yi{nC z9|_Dq>aSx=A`fy~`4xux;@8K=TiH=~{bAB8JA0Z#LugKORskNK1$+nZm`gqSXJ{Dxzd_T2gkG^)tNqJ?3*4&e z^&))*Q?kOHj=clDamM`mQu5L%KI6XvJyQ!xsdImSYN?Y(6ZrNxpb!xvL#D+_c(0V0 zg7NIo7f%6)b9XADnDhfCixzE4Z^nq1lTR=n#R8x9%sh<>{7X?rRYkUUmm@~&lUKFi z%Q@Q6olNuh0sojJ!Dn>>y;xDZmcRB4a0R_2sOYd5LJylhg)MNHy*u*r9Zw%N@lfW%JDGieQ%!3p(cHCsd7X?%_!$6+n43ofk&sVO2;iu zowPiF%L~#Md0cH|ZxEDYm0wPR`z3BXjDIO(yxnDzwv&zhA{i7=5x$2ElYZ7y2K$ei zP4Y6Ts6GnP;$fNci3r1RP%QNwg|3cmQtnR>Vn3N@ugCc~WBPaHm#FD`S%1JzDIV3;%7p(K&N@Hl z-9)+|$GgFHR&HP!HA*UgpAKD{54*&*Wb-+iLh+9WGNXn8KLzYN>^V< z7uYrFSQDB2ReHpiA6w;}C#}-5?ytyS@9bkiQyw*4-vE)}g>HU2DkK(1r9?e3t^)6` zh`iqDPh1r#j5=Je#uRkbZnvQlGP|cNs?_YpFT}(o?RMmt#QxoT)L;4a_Db(eISj}P zK&`m`u+nnlccoOr%xwPa*GdhR5qmdRW>pF?5>Ey0sUGinsoH9YhrPDuxY=ozrPHm3 zZdI@M*JcJ{^)NEU6<_kN+J36W{12{%zJ15dlHNg<8kbb78@+4PmjQLbsd=6#m09E?Jh|k}~_s4sZ#>A*h zoJr$}{fv9u6R$K{+wq$iBa}`z=|^2QD$=;(Y+!2@fx2w}zPoC*Q?-0WqE7W?UXF>` zY!01w+{9-01 zc+OT92$1v=@(}m9{wg%-+u;R}I1{P6RxnZhQTnO-<5b855b}3+Dx?FJ>1*aGc7A9a zYrK&a{%aTD5HbUvlT3KPTWt8T+;iWt_8t;!g7xGt!{ZZ5>!iSHd zh_25SvRazr$R+W_QUHMnQ9Pf1_9t%6t+(s$GVEL-@h^=+%a;f%nSR{W4X@@#PpJ>X$_Q4u6|GMy z9yKWX`*$j86)WR8??@S4=^ts{)13b>M{fBnTtU`qPy@~21@kOtnIUi;*sk5PO_aPL z0{OG`v_0V7=D&93otarGo^t zvpDsu9~JW+uPl8=f&YPUr@>Jp*fjFW!w8=iluq{t4SG0YAmJ)&YMWZ>H~s#f$;kfN z*^}lfInh_^Hnc&2h{IHpQL)^o^3&lAZFXV7lcuyiqQ7Et!riv9iN7%l&eDL=e0Y4= zF@8@UbJV#TQIyJ@tF)tx%&l7MORPuKqrQr;rWsm#Jit!Obo1 z>U)CmyGvPKcIb!$lQ8(Ns0^Q-xmES<;HO0|ZU%MEB2I<_*AX>;d0Yx;fVa>YceGw@ z-x+WH6;xv3=ZO4y``x_MbuX8a@MWjR*^nUAYhrmNp!e!3>e5N~N|PKK@(#$uEITTLVp);W z!PPCPbOAcI$ey9!u?8`0Cap1;iAhN@N85Rg_X~C*XuPXi79;-nmv^1M@dJ%s=rp&t zQ*AYmqGu@hOrp@^*>aO!H8shw>ssarQ?7t;$(pa!nkK2i!e*= z(D9YX_a=d>p6V}PIWj;9#HC*^DZQ<~klz08m55RLSEuy7WAb~SxnD2cYZOtWrR9pF z>drrKpy{q}LT7>=jS^r7MxLTS#4LAaa3K%^1o`2XEqBh&T_C$YO#g$dSILK+FS0Nj zLxQRLVFEWrRXh?|l!(lRLZGm}BIf}7 z9PKAT2>>Jg-lG6RJ)sDH)E$&Y0K~U)vG4-RIQ)&!ks;Qx2FG9iVUdAWMm`}j^Vugp zlKxrfE714Vi&Plj9q`CNSZ0cNk1B;J1$ZQW)~c@0;Ss$kgpS&2(b`P^+G5Sm%Yl-o zn2krR2LC7s3jo&*-#t$3x5npX@t?vPk6JH827rFV3XK^$U{4MOJiat`#AH9%^p~xG z;YkKXkJ_IEYdoqS%5NAAZOe2(E2bIH>VRb8@Yv!9xI0)qrY5&M}n0kT&{`2LqE|I3vB)s+8TKL2Y|{(oa=W6j&b^Xa02?L72runEP>=&UR%X=%BM zG6X(J14~H%81W@Jh$S0eYOkSZ z{fjQ4w0wNk+1IB}YEfNc8xDG|>ORQH$%N@fN=wU5L0I!WQY1>}wyTq+n_St_r)>AU zIjJGl$vf9KNO!);F?*ptWE!;(9<*Au#jW?uu1UHQ6}a{Bl+;SM1R0hZ{9KbogdoV0e8Vpf3~%kt4ovH}I72vo{0ZWDO-S(FzrsYR*)ilunt}Q&#uMzPxCrS}n+lHXD(_wDXLjo`af%-5fMO>{NF00yR_;Hw#c`I^c6quXs15;YA~Zk|}7^H*6a97kN1m{{d`=)MzPQe9Ga-KMSB zS*2v!eIWZ!p51sO4mPE+v25#ef|;^I5*^j*EHhKx)6;=R1P5vX=6UJacvvg;Om~`8 z*zAs)`?%e19{-Fu4O##d5jdT7GEA8ab4fNCqD>_O9XGe2`#d^#A-I567PdLT&~7t; zl~y6WqkkPOIsh0Y?)T}EfBr0p=ugfZg;L3Qt@()~Br`2l z%}Xs%I{+it=ZBy}i1u_0mdxr;GbPVt?pcwJ}OR3VFVugStH5 z1EEHa_V%zAx=ll5P+knt-Y34W;#06qjR0WdJiDHEXei=i6u zFjW_V1N0v87uL*E0F)LBDF)yp*>>2d*R8bAl}ZirmP)G!FQ|tscdi2~+1Dar%IByw zCN+++cK$N4Xu45H0{JFeG#ICRU%lQWc&=pja?vra*RKA-=%7h-A*ICMy%}BF&>$3h zNRZm48@;|IjlEd$W4%v!Vf>29d3%93(e?gNby62E>*x|hKwE?wLd%T<-*JOwVes`~+>8R`np@$wAosEd#2M{cRAhb(ZU;&(G!N%IbnarBa zG8euF7}+1}ep7?6CRSl#iaH;dbXA2hbf@tzvwZyAxF)S$7bh$v+$QPN_7_Kb-|SxL z^=hih`ksZ)E?ViW$G2B~U(fnRiuWv7hm4YgzXMIq5E)T5p1w$LcOH~a4EauYb1 z@-21_?#lbaIGb!P#i;f!Sg1J$n}}XdExAZ|nAXhIZhN}Jg8i6R_Q0e`584Z1%EX8G zk`ctRFg45)Ry}0UeVf0tXoL+G@F!_eFn{>Hn3mCfuX~3$g*;+1XH?Lbg2A zP)f_3d54rtYv}!x#ry8=RA9PhQn2EF%-MY5MiKj9-K1haz-Mw(oOViW1iZWV#WLyQ zhjW0A-W#4YNtk!&M+j^`4r``f2rw?{`iZ^J-Sb#iE>SS_Lrk7``F44Zo1?wmc7w~Q zK}x~RA&#-He3lff>p5~S?wmU4cJ~4-pK(|VVO;Y_>3D1X)BT*Au0We^4qc!q?k(qB z%zVZCIpMx?b$BaQl;*2*x7#1tjXB%LZ1k|_2o48V{wy9yXz0<>=Y51X3 zl(cGk{R!#1Q0qwJ-P4#jm4on6bRi_3IpeZiSquV^12_r}N>N8t*(`mHK;zBniZheD z^4N@(ax9&LU-UmrXjvF1xU=Sfs5YdFxpFu#uCI@tsWKB!?cgmt-}a;pGBbC>{LfXx zT7KI$wTJSuz&qi&iy7D8AW3Ji6Kr2_Jn!yvoe_>ACaSX;PFD?T08=s2_wU=8JAVrD z;5p~-Rnl$Jol?dDgHj*E|6U=$8paS_p@vy=d4y2R#xkckyia95UEBIC5L)%9wi`s( z7irNc^fMmXw%ywvZw_ga1q-^NnX?MzK7kQ_*0c{rOVKHM+Xp8V!*z0#$f4$>)a*Qa zHz?7H>d>be2i`S*qVEN!n0v?X6@1(Sn{}7vD`p|CFGmlM`g@WNl-F@^A*Vaw0R|#N zNOc@8spQF3pE-ViWs#|1rY6=!~WwJU+aih zNFP7^%bRt0VxF5&%-FF5}UBh#eSyMDY^L$pHGdAcKs?iIXR^sR8vOBzpVkVQ=VsiV7 z7waX%)QVgUkRXI#(a#zn4Be^M+089F1+IG|mwPS{dFlSBFc(4>0Dg%=aqt>njoS>; zF~lP^O&U!}RXFov_?(w6oF|)0b<}hq;M91R`W)(2VQ^9h#?fb~U1si&URxnCGcd3e zcxMVPn9k7>B6Z&AXz+aSPFifV^t&)d^H&c<2b;2&O!*W=8c&%s2pQfnfEP_CIEo%> ztOq4}=^34-(yfzW(Ne!(un>fK?=NI#%SCUwmgyxIy@E9l8z2I1?G?gfu^k?U<<09L4Ik*UO`Z*GB-iwY$<1x-L71g{Jqw|R@}u_R z!0w*3>NW07r-e{i**y7Fh{ky)5VzlCjrh`Xrqr`!Q6=XxV<&W|xyCeq!lAdQgP(-J zMQ<-X8q1BM+uHC1u$lvAg@M`BOi%RuPTo}joCm8m` z4BebEwFOSTEzY=nQaI7b4rh0JIV``YQUqjojx=+;3BaiRH$0s373WwTH|Kfx^N@rs+JHj(Wn9y>+Q{NXzI>VQLvn?8>sp7g8!LC z2Y<<8P5;vcyG^^mAy_0WlmP%+(OPNVl0bR^PbzDg^%!}RBnG4+WK&9s|P4XM{ByRPEILqVPRNEnLC1A>1T2Y|X49q(rup9YROZpNAEyvo>( z=l6g+;=X)pYcWVq8(H^KMYXrR{Z;&j4CQiR)!%5A%jiPyxpb<-kneAO z;~n{rfK;>VM!~oH3;Y-@C7Q_Fb3sc4)}fTvs^ih!Z^VwYDmH|ptQGSM)`c~Pj>u^7 zB~>y+(nm{TjEF0ix%^2IWWb%s-mXU>w!>HnnKN0;I{75HnHN`3d=ql zQT%1N;vm+{Nsvl47}t z0@dPHml?^<;Z)S+X^EW?tw1qCYRdG$=v&{yntkWCJ)V8SGncB}XJgiGqvHsquH8v0 zZI#Vpm8r&6mbf*|#27y9-p#53q^^=03Qhs29|0$%zBzIs-xT-GTD`lgvU?$P*031I zJRJ+w?Yq@yQB;)v>ssAOpNXh%O^sdqmojKoe^b8$azGu;{QMOTfUxcP5kheq%aU35 zXQQ6dg~gXTPBHEU4YL$?*^IqK`>^ErVC3a~cxM--MT4e17$0-xw(IUN18MwDa z6{#u(QWLDrc!<82_=5H;`;KUV)6WzLeP?c7s5%@Lr+IawNgCp^STk$@+hGHC`ea%K zcD8r%V9ATpK+d94LlgJn78Ssu|LJr6dMdKvPFc^n?J)UTYo!t<*#A4e0N{TEE-y{$ zgBV;DrmBU)?pxY4Uzx%co%j#Lx*Z7Uo+QvBRK@Ye(-uOgH(qSaEU zS`BP6Q!0&ZEJ$}HB>3I_+Ed{8%Z2boy}=}{Ga)1U{b=n&@+X_6{dSVEwy>?z*NtV* z{k9gpdR6A9k6XL5HG}!e^MP;&%n{Y*aDZ^xv>dYFYuEm&SNZ6B+WnxjrQ_^}gRkno zY*Z3yhWoS_L85ta+)7lI6&4;BehJH#B!!YRhKvH);f^HTDu*x|sc7${sDZvIhX&`b z#$Z|5%&-IW>eHmKs*`5d%Y+DO(~Vk&9rxSoo#!~U0yi3J6X8XlJVM{EkUDK+}f-V2A zI96v6CgIdoW3y|U%8ys^E*=%*{zN0k-=MQv>%*nKdqEmiGG3k>QMR;CY${e1(II@O zHq%E`S{QtJ>F0Cvp`s94erUu)_tSR_%QoH-B53hiEuHes&DU#oU~>7B{yvjAehk?- zpFbBvZ@rzjQ=Cd4x@*tGtXqJ{NP>>W>a@25{nlRy4gsX*p!1;-Ms;GW5XDpGB9YW{ zHrt858P${DEMQwYA`JyEbPP)h=Ih6)G)ho?R)p2 zt#S~EqO1O{BZ!sn?&R<+XG#qy&T_!zsab%Q5q@*1D^)8Zs9y;2Tq1o?C}{@)^*n0C z!v#@Vfswo%b-E26`yWUlN2R{2H;UIh3?Znx=DuAy=5-mz1JBU1t@7^LBEc?oKW>H~ zg12sJ4)3%?PY5qbohML==j&9IxYWS+5=*oNos>X!TO1Z0lzrKl*i~L$_wDv#%l1{Y zoEx#Tk)62mj|+6(XBH+!H@sTsh=v8SbQh3eswNLLHOV{i1ki`c*q;~Kb{)Rz7Ieu; zRY`$QnH!Qzdv^D0cm4WEhrC8+Q;b~g^^xH&Odf`(?iUxx@$M*^&la^xcE#1FtkO|= z>n+xp(>#uAZ9y@t{O@`uz_X?_!~`Z%{f;xCLq9VN%U?Eg9yqnA&Vkl~mmH}-Pwg(4 zxl&X~(f?EOG@l5#c7&&^3xGXojX*)<2C>Xft;ye}fDZC^qAtyv*G1+(l0wQP&ZxGw z6W_lKsk=PT#$3s4rX_TOz_S#^px9P5;K7eR2Wn5 zZyq)ZG_5DFlO}U}fMvj`@vzpkbo)tRxEbQV?%F;U#2Nah(q{~H>4sKKWLgGJYpLrd z{ckM;7Z74w?Has7gc<&(M*yH-t z_6(f^ywERWVl(f1=<<|#Pi%Wf%_nyQ>~osl7Oq*GWsr_Wk7W&n=@+0Ob=c{e6YU2= zg_D+eoH^6Ma`_$=lQLLl7AIpt-0q^Xx-L5TvFFeOS7bQOZ*2b+>8oR5UW8SQ&4&m@ z1>iS%tRCJbGdBnY#HB4jukcMpP)SXV(+|0PPi*qX$O6#R%;8Z`6}{{$4A2i!(x(BV4^x(IYMt}JnDQXMFZjUdHsd|zNB zFh%0iuX1vwf7Jf=Zid)i^rlWNn4o-Fyb7Tk`7#uUngfnmBM?jkLEquS!b`9H#GdO; zb0DMYs+$~6=W7MC^4-tJj^+v56eih-f~GT<{P8>c)gaYL2E~n+f>|nssNW!ig`DhR zPrHkk93+ArYP~C;`%Fq&zAujJ|B)8R4-GG`oNPIvpxpWhb4HJ@UJ$eh9W8?b0(n7)9!aLi>A3PTyNM={HZ^^LHg0PWTlad8ozLc5zd4RrAf8piUCeqVOl(R;&o!k( zd7ZZ`uBP0C8lz>>`n}2-zpQM9yxUn_3QS_mwW7%p!2!M;eDT_Xo&tn*r-u=VLKYDJJ0ka+Eu~UXE3sg zpXNKHQZt=?%BXLU7V$;&cRZh&pFaTc*oiDG$f$yxD`D3A_gN!H!T5e<*VC09??v+kt`p(ys4}Pso zSGJ6j3kRLIu6!i6TwiuU<2bnw!>6xiKN8#q8C|o{eiBqaHUuLvS~IW^+Wrp0D90|F z!w`5Y9!IZjId;*B&MAR(GoNDT8dWa06a_{rSYS8b*Lsoh|JE3ztMQcm;WT5 zw2?D*Lnjq-f(h~$UBL6lGo_7(S(`tD2+~)@t298ci2bGx;G8yMS0VsKl={F5qi`jr z)>N^JKzC_=2o-z@ZZ++Ao(fu_3;i0=TO!E;a+rGJAt$0e@eDPo<*3*<=3^66Idm;8 zR?ef+-1=yBI94zwDAq&AWW%z_=cJtbDRY-7c`?)Rlh;!M-vYV%3MT*DW~Yv<%of|R z=lMC$<(=%Fm!v5d#qnf}0qe?|bdD)ysvzL7?p?47Z>`A&UR)jKV}@aA`y?as5LI{E zCA&b&RnqJjR)>kG3WGUgG#`#u=cT!?+wHOyy47@xExG|`HX8$xS>F6vaazBWUMVa( zh{n#x>SV9)1tiwix7k|8*Vo0RhkCvT-=C0b7mU74#$WUimlt>-jyGnE=kLQH6Lexc)-`wcDLSdxlo=Bh7O?>gmM|7{geI{zK{eowHT`DFWcmeMYq zm|fl8aO~a_$O(|fjpL;Gv0p)%%@p1bx@pA{>V$WUn%#!zPxd>aVvs%=i(0G~@ z$2V6@Encm($hsM&6gBP3&$teCFcqx`v&4h~_85ik!8`5>4bwC_L=MhCLgvz+@1 zjTd)z4FW=z5BGbVf32DL2XK zn0O>m({>y!)(8&+w=G#qPBmHjy0X6;0R4(Mx~miBp!;j+%dKvvkth zz0i0zz_7pcwFmHz#v!kU>IFI&F}w!Q;>`V?CKr(!_=R?{(Q3DJ3Vi6=@XrmbFT$D@n^P zp(zd6jDryK$1MG}bbZ@Ys^5%Su|Ne*O*Cp;*9NKy!1qq_g*fu&WQ##+y-aT$!)xzV zlq!NY_E{R*6T54DkDt_M^#7SMkgp*DwJw|yvL!zjHgFi_xM$;U*1xw~ppXs^G0`@1KXeXHv2@sh(@pY9!Om z*7WD$O+wvTB!mPw$!2clGtVXvimA#!bPH5sN2tE;=yIsR&dB89)O0`RL9@PX@{yd= zu_1^VF2K#z^PXJjjnAdkzO;Dt8~s(0oOK0U;GKH!%EX*o|GnT9<&ROD>L*{4+;m<1 zp37=(#($U5b;$p)4g9|ldc#AFQd;$WI7)i1r9gpH=+wg$@%L%YeIVqLWw=07i+=x@ zf`80uPT6(x!jLB+F3hV`$sW@`d&(aqcsF`Df9#z@l54hsZ?4ZPN>j~u2ztNQKJHp% zOMAVyZh9BmF^lZ}@n%j-hjil)?Y+8VSeTA)`gQwjG>~8^E(=dpK_|RgIWsr)#2;kK zi5JAN8lv;Dv$YyP9L23xt%|=PnNV8=jhD_slveXv2ht)&%WGgki$2D&-sG^v@1b;V zWUIyS`F>KNdF`!zk(0qeu(ofvfZ5#5F2=ozrgQS1(}6LB7*&rta9%Bep&M=0NKN06RLh^&1SsWc4UiB1i513ue0R@*W(DO(IV)@kVRNYIT&$ z)?5o+4JN2351W*I4;;A?XV0-w^;_;qmmJgR-;~;?KZT5)K_W_wIs!%~6t_x>aTxXT zrz9@w(nN~Ki3vzz@E@RpvI@!p7bY_6s{6j`8~l*kY2$v|eD1Z9!Rhmt5G%1lFNGGP znd#6A^^yhV5aYsqzGzV^BSaji( z(w^z$pvM#2GaB_|yA>DIFdXxvg&RxGubDc9(sKRwe(2yD!wGilS2#`URLTvD3C@Yw z5G@Vr(+H2#J#@7A$AFhGe%V7w^R1ocj+Cf_Pil+|z1o~_DZcY_;N1`)@CNQrs#+Bf zjyTPxx(XjFp8Jmgp?IROcXn^fREALjt*XcZ8woF!1} zn?h$*8e^NcC(bUMl*;kRpM~#=i?QaKDm~bQ zmL{3`rz`vmt<;FurbdApZ!&bIT&}0V1W9#<6Cpa(Ukh|?vAGy>;YK5fR>Pf{M4ozpFP53e7}X5FWaITUDk2dV^7RVS9-?(zNwrQFkt$0 z01Q{}EAFnL{QP<8sXtNUJ5NF=C@)v}$x86NLt})IHSKPZps6q_s($HMY;rbzp_%_Q z=NElQ=jp*+iW-ybj|==THTC*=Dz5wTlw$3Y?ladtJGbu|ZyM#Hm3P z#be~p8G9Boy@P>lv&#=Nop*d}Tnc?0&gGhdcHW4Ebq3xq=H!6{lFGF;(c0dvms)SB z4it}5J0q|w!ESo@hTnDcXbDtSdINq8ex;L)mPr$D4NC+krg;T)-AIp6zAx4R5I%y$a zy4Qic+Ac@bWmU`YMv(9T-MGQ~Dm#7hU^ky*(gO}~mq9la@6W4)op{xK(dohbH6u!o zeX50Xc;GdqH?BIJ0#>4hwYof8H>frIlPy5Xh&Ha_-ozv2x9#`hv3m(morpqH+q;5W z*8NEH2a7n}j`I5t6&Jz`Z)~~#XudH7JSQ-rl1`pzXMkBArb3NWeN^1RDEf39%eM%0z;#N-4szloqF$%I;&Q41Qyo z4EDu_t+1Tu;ONiz)V(Q(BtXk)3Y`tIOZKvI(AW%5yMk_XlE&pzXIW9te&-P{Ypjj~ zs{lMcZ+0%bSmSctReZ4AEkdj#cTR9+9#+bumRHzv;%3i#_Swj_v|&f8I%$>^l$nuZYaWw! z#3$N&^5zxiUdXu(#bny(`Sdd>PkudmIL$zQ)Vw(z+p&Hex6zSJ-0v!uJxvqmo_k^? z&28S3{xo?0k?0BAoZo!`vkZ?|A`9SN7nWmK)>Z$pejst&itLVf|7L7Ah`#o|>q`(8 z@a~UxpuL-oXrYJJ=am5E7S*h63)?98rV^HPm4-^x@GQkrHuaFzTP@}tR>%2>RJ>HF z5i)6ek|8rD^ZT*fMt%(%i7 zao?&|k(f{}&oU-${PVm_&9&(KD#l_kEC?tT0|xEqU75mK{|~ppD>!thTLAZk4=Aeved-5r z7wFk7riuW9!5=)w5uw%!vT&<5@v;53&f>+tgu`HBXcSyNMvJU%+A$N%IA5WrSvF81 z&d@vtMaHSxy-s7J#v)v-&H8UHfGXb2HW=nlmY$%BW!JojyG@2q#=>y}!#k|?4u1lOO{XJu^sr80i1S1LK_3M@Sx!Z7LayEGztOOubporJAZ$JAqLFL1+lY( zfyB{d3BYKqxbWS!%yiFPm#)W?8m)GZvK!w60_~y<0dY2i&uqCGyxmU^f;h9|Ksdn% z9KXNdMhURERWSc|(2zkWhvCZ2rxNyT9;Q@+meECTqPcBZb<3e^)BD{p{7AXB0&L)B z?&nNwb;Iwer%xWKM=%>Q>R`CagCzJL>i}>2zrmz{|8aSGZd!EsMgmZOj!iKqHB@i_ zpuD3ncR~PQy0K`UvqTDXxW-z7|YyjI5y1 zB_)&gy@{PxOO0}Z%Pt+bwxFmjTI+7<%NjibACm$2L@iN(p*ik6l?X-uS)7}>6ow7lX{zW8Sf zN=n8ZoO)|OD1apZ3$KK1g~FlyGqQ;m0k)Iieig9Drhwn>AdUZ{oKWED)r84$1z>tr z5m4cWBGP3fu*e||{`Lcj{+9wV1P>(v04JdK9Qfi1R44zNqYRn^uYq>a4338fr2k*m z2Al?WaKm5ZV4x7tkcKyHY)}EFurUFp5wL>i1Yvj~t%_*vekgMtAHOY``}VswA|u(sXq6X7h`T4Mx`zwDbm4nVFeMiK#p2x5CiOBuq6#uBLnRkyGFQYRZ@aYy++A{mkFq5&# zUmyGrwa!HV`G1_&CgO6Av5CeTTyoK`Y@BR6bUJHt;?YAJKgJOF$9Oo&whJI%ex)Yl zp2TQ|B7A9Qu$dg92KG0y74iOj%h-ceK;Xhc{9?XcJ9)rGm{B!fOlwU;2dscfq>=V`zSm%C_ ziB{igAGixC?lG-@INbR)&;Z234B%~pe$<>`gYSsMAS*3d3m5J?v{#FJJGmk{A9{Qd zk?+PGy}!V+tPF;c8G-HZK!rqJ6c>9UeS$jgp=!W8AzZh9lUs+}Rj3A4ASr-n3x zAy%$#Sb#{RWMq=AqRg&lOyb9gefDKRy^zsO!}`eAIc;kU>Fhp6oA3X*S%!ZAPApXN z_&>>AfCF^Zrq#YT0n@_R=$6vf_=A_Q;t>n^i^i1IZM1p!*O>a$?y3wRF_hH+Y;n%+ zLkl5r5>gb9m3>R|8?<)vjBFf<+_)npB~)frwJKgVioX)bQ@#Qu2cCD>fuUHVBBS5Jcjekd}yMYscivdQ8y7yxKBP?&8%d$}%)5*V8f(p^w0 zoQb%*%DllfVVj#}ctOTJm`sNu4-hg2*>1Lr=004dn=a+*P}0)!1hSM+U}YwBv@m(z zKVu`ryUfc&aR_vRvEd9nz*!K8)hB+`I3;7RaMz$Tyz+M@+X*9hYh9f# zW%(WVbU*@Jrd)!7){63Jf1%+l#83tG2`JvnRNXo20DBM*aplD=TlLY~+pJ72T>F=GY|lTJqu}g1 z&`QP)Y*p}8LW+{1ZNKW?$@khm zZP^^ne_j7TSuY1N$hNUg$84TtW9Mz5XvvKIi|CNz153>AzbrJG$uLKu((R*vf%*Vx zrCa^atR_nWLuwvL-Ym2H0*UjwU5dj(4rqD_h(J#uX=P=uVgT1v;4ytnZK$4onJ+i4 z_v1wZir>d7^u>n5ijUXOGvQ;EZpl9WL0fhJ%7cW=RLVTBoyM!kX&;#@5aMpvO>t8j z?OQ_RiONzY8NipwDNtQV*A;)awWSASmS6~0H2m!UC>oAlUxgmh&7Jga@uT=Aj-YLy zra>uz3J>4+^YBR{0fXj~?AAKuN zMGifXu6|tK4F8~#Z!O>a+^^9?0e99pok!5tr*pg5KH=QntRo@14Ws|Q@^5t^wDkqt z&BsIkpOUMu5ENr&B~BpOUfOLl+d70wz*1vEi`u+!tQbtp8EyxTjXP9;=G&(*!2i{J zB4}QnRo9F}1q78xy-HoVBS-RBwi(?@HD-xJ;Vf~o0HH#JwWq$9nw6npMjZ^hCBaYr z%q^eB%R9_}5#hbg{O$r@kOA6c44&_pq5dCj3KYl1dyAiTFoA3wFGq&C3-IY!C-!tS zI)b%45SWERFFP;=6U7AfA+Rql%K9tj5yh))8_A6LBca|&JDk$i8*+ntfsTz(2G3t= z$3^4$$%^;)xjM^)e0p>$8M?iD^gnk#Le&eNfCpXzgzA8z#G{G&KTHG+9esv>0(9H+ z-IXaXxX0^bSvWXIO}caDTwkS5CjMeM)4+IA%FU1y@Jpas2ClrvHT7_mDxoTc>dsqg zbiwJ$h>4M1`XM@i7O_M=>kb4+ekY|BwO7p^=o7gzK~Jr@Q_A zdrFtjRpIxe1oD6TY+xQZR5JQMJ{!=Ewyhy8WPO%N_!wl%i=CSf?|ZNRn(}{vGU1^$ zwgw^_+06SvC2s@WaJzoy{LY~UAF(dXYwMqD|MX5&qU__5H^1A{6&FW~&A}WMx?qk9 zG=MP$Y##~#Z6AR1KcNDwb2UT*aJ0XGQc?5KZj=bD1;PO918b)%g8nzoZEWBUE(+bkH`Z^!WM*DU`KO6RIk5TP2dMBb`VhR8@n9?!)SH` z^uT-r7a-8abpU$$cXi+i|G$6_xc{V|nxDXrWC2^W#ncxDxagRH6@ImndIOt-2PY{* zCySK--nu>TZswin|5_b*;uQ^CnWF%2{4XYtx}V@jxFCToQgs2@imU-R@;Qj!0h>dE zZvbz-TK3;tUjyFln;ZGRRtKJVCIuJ3?|?V{R{;z#m;jI1LjhZq2NRN{f#HP3n_(wl z2ql^+cA*7@acc}zfK=`WF7k7@@4P^R*>yQ{)gOd6uk9T zrhjkU1?W1kuEzdrbzu7!;o!>J4S3^!^|1i^2A>|nzvZj>2&|CiN6-KVw#9_MTi5&d z)(-%mW86aU@6~~d8x{EHM5n+T|C@UxnyGHNKYDMEVr)__neZhu8|y7TXu^`aaJm#{ zG7R8xnQa7UhB739zq^i@DEvDhWv^`rkV;9DY5gj%F-ZEHL}s!={1y*+Vlc!_3CD@d zqdwxH3O_Ia;rVv+HFoW3>rGN>I=!^?7^ufRakLEy83jm=6HE{Hq=Y{v+K0c6Xq;F$ zQ3c^f?@np|U0(o9vl5Q}-}={Q3~)6mCl}Ljsi?$Osaq?sNZM8125^VN>o5(l!-lmoMgMeL!5LT(LwZ`fiR zLse(CxuQZA$+@P+h5Xtao1;Y1?s?k+>L6SYXI3tc@2mwMd&x@(r1Y$xu$zA1GS9n` zP;||o0F$Dn9j;ePHC?Lf1fnSgJChww!%Vb5v8Pr;6$!BEkv$LJ(&I`^A)o)*0ens0 zq2Lqkk9w0%(_ig10}X5d%74+te75iFvuX|=F>!h$b=<_**KkTUqBLx^g(QsxX1mGB zImh;?P$v7%VNEGIm@)%cUi6*zm(*t*S>m1@o{J+&yUp^)Q{% zP$EWXHXNdKqw28L_v~c8kB!RG+4PYgPb#=^svf7F}^_Z3v zTYJ2x$axXPAd2_7*nI{Azjf0AqelfS;%~hk*anJ0x&iQHAYkZ<26LsKmZmmA{t0#1 zm)}p{P&4@&xKot&UKa-j6p~YFw7*b0m3~Neb9UDa#(Bx9p0X^e)c~fKZkj(z&n1My za5P+9QFi7_$y6>L=|NB?6~av|vSuE$qen*M^yOqnSmu+f1i#CS)|7I((`S&lC{&`? zv(?gPAfN~7xkjf?v0Il~>wfSdBS^!wBKa~H$~?t+Kl-DD>D1#_=H+Jixy89ywgGTW z@DG_%57<{nn;Vh?>7j(7$k&;i+w>yQ_*GCEV>%oE>(mr;jOWNRf6g4{lPfjKgpy)< zibicZFwbXi)@?UA=XIH_pFo!iP=r~NklVa+?og%K2BIIEXpRirvf})l+Rs|vi+}zp z0${74Hjn0fezf)stS@*M)rcN_cx>(%O40WiPv}0TGffQ}v{`xF`(%=SgA#hMPnLm; z)DL2QcR&iBK-Ro4erjPnBe%kLrlDa>E{sBS@A+0^VA-8Vpta`OeLudh?YUiUFd<}+ zchY{X@WXwJ2)7RJEm7KGu8;DR6^+U9lwQMqA7r_1v&=LCQfbPi&rW98C7vMg<9lb)>-ezzgqnlt-5 z`nRQUDim_5&vx#*b~Be+uArMf6MIW%pOltS?pm+OmlW*1qf4>YF3%PPuS43lh78y$ z0)TN3d~Xr{{$IXUXbtA*cF$J_@SrAwClCB zEX^P3*;1}k!k}A_9Lm;GOP4sADn3`cz@*Q;o{w-J%0DK3G4SLN)()O_1fn0qq?<`4 zI($QbT8<63t8PuU*K{b8x?QJQX>ekaa&-PCb z$h31keJ#PLorZTowll~zMXlB1Pk8BiLR|pbl=l19xN;s2n}?BaXV3}K@8xP6iVyq% z=Eb^Aei6*pGxy5^ow{Q+lzsg z@u^@ltD#b}g#~=CZ|NzjoxgtGX&DCW1R5dhA3GwIabj80tl{YsSnRDAn^t5k-{=zV# z!TycoKmIM-^OUFB<0HA}keOHbB9nW8p!~!h)!e7*Epe$}96M_j?+1BCTEZk%SJp2( z*p+%LUx%3pPtInn-!{)Fy9^hb6vuygVGFBV;>$+!2PQ^U_IQRNY zbN((JW>MZP~9PR+q|-j9)*FG+iJil>BneXg-;noj@V!KZo@Zz zZ|^`~uSnm1$;EN=Pr83%M>MY4*OuyrKRr*yUh9wTHO>lovV&VgC2A9UEy$I{4P`=~ zT{B|R74;L`-mREU57XUyxk+?nTUn-l#jW`^!9wmfW=6fif+z7&TSMXH7x(~m4medsRr{|~ z^|@@-u4z>V<~t~k?@rR?-gRD@hmA!%!7}wh)na%3oM9VIkMF765BWeTD~spQah(q; z(}eh{)-_|7^*y8k`NQ0T=Hc0==nxU*dZWs!#egv6Rkrld`rExzWc6fD%@794C z-vl;;r?;IIrC+z)F3&SDZ|CMd@Tr7OVoe{U`^AJdKx^sV{MvcX-)?nX0 zj8}D@WQ2*s$1)V*!&%*hafLvbD^1FA^|;YfVqq$StyJPIZ}yn)2hO%zqS*@kksAv~ z({JnXW`}j}n|UwC8_0ft^Q)9dqd3f3*;~K9ohwme7T_*EV&UQ33$JvpS~W?f7O-w` zHT_vP$CGKrhJk3aMZUw6qN!~iwQ7IeT9B~&@p51>FDH@8Xno@&a^5nGI(TS<1epC5 zuNsES#q4^3fbRtwB5N=wf&-i};sC_qo%vo7((w$Ar*>hhEx_|cPrFoss|N5jlbeXX znK!|;`PKJ&hf|M;rk=D2j3lte!MXaF5bS!CwaSL?;Vnd={Yp|%qWJNcTw4&V`i^TE zMd7Q73Bbv~6#SU1qRF7;2{X4jTd_dKyZ)SAh=EM2+Tn@ASr>)+<;_ctaY%QsRQTB_ zvmWOJX;ol&U=7Nzd8brS-i4?M zbVPb$>eph>L-OlKyM2{qrL)nldX})IDS+-~mji>N zW9&UQElierXQpvGc82a2iW}qsm`hU6WVh(m+8F)&1*XC${c;o9^SKH<`kUD^-lw60 zXtt_%iI!?HKc9APA0F(Eb-T2@mmx-t-{#D#h0n_##C9MT~>FIH&euSrQA!!dS zFC5gz$yym}kAhk&#N!LEsV~b)NsDmS0{${jez$X#6V0!gx81e`RWb&j??P`V5v+QL z9(~O1eepn_bvDO0Y&6)C-b%AUoT9zps98!`Zigh@YC&`U(AGSX%h?0Cd_-74;vbcUQnJ+75&K$6?2llRWbZtKFm!x?Y#e{{XL7hha_Cz zUmo`HX~|OCx5KAKe|!diL8h;$oO5-*PiH;&P@>%S6-hX7-Z76grJ@l znXd>q8FfayC=1_ZfnIcOR(4MSaW!GR=RO;M9!?r=yg|Y$m-(SSKis}#xELctJJDfL8m7kAKg)F(~SJ;e>Zjgq2_q}N>U6Kk!CL&6J0uhCo093 zE>p&BmA~73GW^xsTp*_RTNTGy{o4H4>17k6P6Jf%AdNDF6dKQA3|)~3WN6usCoCd> zVhvtO2%YLY6)|G9u0!;Z5G~p^y!R-`V1!MQs0C7JLSLR~PzL zucX1tQTnJuUf9%~imHC3yo^Dz$ZvB?*scrtYD27VRXv@%`U}E3)!Gxe%jtKu8n4UH;hYF(L?oKLUVvXjB5O4eGsBG9Sk0Wvx z<_xgR1JGHvhCmMmpHpnFI|3lRltIubsW|HkNwfOEXW z|IR=r0%c}wu2A#!b%uxINsRm1sXiJfQk<4m)AyJf``y<$2!g?G<(>CiLzvrKigM6$ z&~7|X(@@OI>-3ss*ixgci1|b~pDs6axK_K|T4q`F$}V441)pVLy}T%RnH1nvu~L+~ zx5m^x@8j0G-Q*?0!uJN-U9LDGVj+Cae^;DpTmZb)j;sh)9!%uLV9Bl4=I(%q=leq3CAsZf2aV>56K)S*KPMp0YmKwEq|hp0c9;1xs-VRwLmH9NczNtu;>pU?fOt#Mm2menTEaB#Gc7O>4|)Xi%HaFe;+gK!CnHG;5npAzr7 z7f@@EDtoS|Gx1K+_kt-A_3M6WzYGz(a%lg^I+tZvPeU&;GznaeGl&rU5}|mG^VpbN+8Qce9&5@D&8*;tHqBsOvW@yLG^MpOm zylX!*@8j;&)9PK1R)3!uN(yaRsRZ21`#!ZdCll8CWbdx>7Lq!!h@iUND0D#Vb1798~j;OlQ4URGD(?1>^L>~ zn`iUdZ~?VH@HrVb!6N@676hNH^!d2lyUdZ(1z~DFvr;KD$QM&0LQX14ZVyg1d`s7+ zGYVI=_V^9f_R0BTSICn}d(ffK0>S|UA(xTe0B-gU7V#qH4fkhV`OK?~0 zZ)}&suH-|A^uw|h5|@IWFv);Jax5?Ej0Sj*kSJ`vL&E^__K|7BC%!#nJP^b^LLY9I z)bPWF52g{9w9=RBZQr-h0U`^6J(8LmS?}Yy+AxjCJ20lh_(+ zO+_^|cJ{AzUJX^@3THuQLB9}&MoGnzHXhi8QPOdhzKv$7pn&{bCoT?|Rs>aZZ~UVE zq;)R8(|PvA;MM)D3oj)thnnA~-+E)rbS)eD-TtbV)hmfes5i2|$5gHk;E1Cb$&7Db zy8Y@5`ax6V@U%#A^0YK)h*@#jgPNhZRE9jxodxf#vA!gw6H=e&GK6XmLO}#b{0f=- z%4aQO3(Y*i${#7zxJ z#$ANFH2`gh8uVtL8;6k}Uio6!k4z+p610mr>~4yxN_%Fg+x-O-k*5phBFGVP^*a(n zP62!W^)J|Eq18m<^ml{42}I#9JdQn0Dx}=~mmQEswx+ch@vKDCvgu?()FJF;Py?(O zLHP}^(}A}woHVk!zRN{2_~*HF3#{Ex${`7eY67s3yl5n2QUPr5`!McLy7-_yoO;Vu zMqGbM1qM+O3KpQnXhkc{dcD45Q@?xdk&aTK_RKBp+sE`qFvLXDw*@ z=6c+Vzvj0Q;B*Yh`g|5>^lh)a4f~?yp-l8SfwNjphX1bnq+0epL0O5;b7Z>Q7&;IF z)MfaQjpztH1l9IqeFtw;Wqn2Ob8=0YF=Sk2GZcjW&v7O!TALc*!l4;a!H%j>;qeVR zk3f+^VhZc|sBsDbdd293T?QGbagsrFG_1lqLIjU^j4lS52D~GYkL*M+V>=)RYa~qy zyVnDoW~NBl>BJaO$!4KZvEY0OogqCKTpGdbk6u`n3%0;bJ99O5tE;#MRf|P`(iR-3 zLUm`$npN9hb1Ss5RJP-oXw072VAqJ;>dKO<6PVyb+`iOT2tIpvj6IPtw8s|;i; zeRBda^KNGsm>8t+k{1}F@};T=U)hM2ULKd+2G+m@mC~>(@1Gs5hx?Ecl}2 z_LPzE2*Zdhssid%hbwB1E=${>_-XP754)ActIYy8{a`6{=*9dq9$4J?QB zk|!%erVzrOBo+w4p5p7Att)Br!+1*L+c&`&<%$K6!|Wd5y*$5R&C{K`He>4dU>*7L znUo;)PY1++if3>i9JUbm5=Ggp<1R>TO?HZT&SbV^P#M~`-Cwo@a{OAeNx4b5+N77= z0QfZ8tkKoowp{m5HZ~6W*3X=<%!n#q_8q;lgK#PY(^7UzBq@xrW{4~z+_tm|xaN>V0We60 zVNZ;D%Ih1{V@f8=2p+;i@D(2k-?RzsM?IdA{_ZFd|0>@WbVpJpy6$k6rcI-%lo+T^ zB=|vtD$$4(0?R@*wE&?4N!5>JO}H$dgi^mC=$KpG_dehB&2U{Gh^Q7r21Ruj?~ShT z0s@^v%3%o|v)TyRDSF@^i2jsljQb8d73bM$i=|q3MULX z_hQu`9zWblR9&8b@2ya_QijK&SbY#~6E>;i$Jx0zb*8F^5Tz`y#>)XA#&H_+909w{ zG8kAKeqIN4+JT>9V=6HuxFAqJk!B*)!O)L~A=BIE$d}V1|_Y)|T zG$RGw$8ff;wE({Yo7MTb`%e)X+-6o*W*SOW&yh{p?7(iKyI+NgrN5)1=BTNxC^|d# zB8d$_>)}J2S9Ap~XSV2k&he2}w$no!jslN4XDG*3wC>Y_#ZFjlqZtPGe%^IUb^DW{v{ZX$&gGxsMrm9Re5|xZ01GL0d4GxhORHYj!J|mxUA@ z>Q@-uQMh@0C(x&Y(Z*LB0WinFmk4RHxN}Ts7O(xE!#52!mb>D+Yj+X;EZOCHbv0BI z1+V@JPJQ_;hdSbYZc;2-FV4_j^sjK>);SmpHT)GDz z6a@DBOA-7K0irhqk9f%(3d?fu0axweNe(#f^!r9G3wyGQE;1p_{JTd3tU`rvjL;-X zHHeOcsGc98worQ?G$BtYXa;7jL+W6SV(NQ{`j#W>;C*DV@2XrJjcRJgaq7@0wsQQV zDsYV|_Jqt3SM1T)OX)VkC z$+L~Art#IKc3-BN?u8PnhKBq4Gm!=PMUaVI?W07zB8}d)0K~bv317!?1(paxYy^-j zDPKZp+{s>30u~o7Tl}jI?J`{K@n8$aC_20t59g8C3hD7tMGJB$ zn%UIDP$({2fZW0Np&(@I!@7oDFW`0bUJ$vFM6Cj2$B~?r#21u)3xt1BPAs+!9(9VQSIZNEB;G!RrU}C@Y^ri0@_x=$nsy(Fn(oI%AxNE+LP-M2IDSXH=WO074<8a7^74W0AO33>~WQI~roCjhrm({xAxzSA)g zN5>fJ=;-$^EhH~!-stKN z!|2FCSPk_PL>D!xU>PmeBdPp#8QmLq4}Gg~Na2-KLvAQc#x8Ou6gt9gm^ ze!oX7C8G6z5?#(Ks=1qfG2i|r*B1;k$$*8a0^!U}qVg@(xJzs*h}mJ}%&*3$21J$O4N?4_UU|BTF;z zdTo&6^8Gq4;~cSBph{U?wn*=ug8>_8cB$oB?JrgJg0sOH#Nfh&`4cpf$EApW*TEi; zC+I-8l z&}@pgO3-SYi>)=1sdF$KLQt4LBo)f>B`3JJum}Y`4ho^j76ra_Gn55g^Gs3y;1)FL z5pxwjcuy4Li(*o0wvAUjs;f90eI?RPnUUtHAYC`m21pi8$iOi?ODVJiuLYggKS z!GG5o@5k7klY;?gxI5Q*F74+urqZeI>!NX{+ev4F5}w`R_^}_fcuf@3 zjRk@rTYixKXtiT#-8FzA5AhyeS_}f7)T93n!W#F!;9^U7($j92Fe3V}%nhB`Dj8bS ze(()b!6|GiJCw$e-CC)gqiT=U$@kOp@sCM~Ra;PYvH(rUV*4^T(Ev>d4?L%m)(+{T ze>YOvJOs0sQTUa-O8O^Z->=rt+GY8|sVH=wK5r_~wKK6wsmCZ7lm)8G(gjW|I2Mn} zA}-(47(*A}^Z;$IkxqoVFK;hGIn3#zlmhoG?K@T`p095m@}g1~THCq6@ur;&h&PM^ z4sY~r(Fw29z(K!8a!YGVd@6B1=~Ep%MqtZAkJcW6rCmUjI3r*9NS*RVM_+6tJ=K70 z9iO2Ns=m^A`WaKC5}iC0RjkP28hZHd4uBay32)wFlp)|l9N-QFjG_t0 zm1#uuyh)SCTO2HsZiRH+;Mmc}VQfnV=Mu3Wra;F{z;~tqV)*gY?fAFXMIq+akmR33 zgWHSGSG(ticB?;Z)~+vKH+;GLWA!c_0!Sn*r6NMetdPXfH@%4q=~Z+67@=3;e)>J$ z5A?ppxs|T?X;Ot1z(C%Qbhw;R;mJKRvfYXpe_8L8IlKv@#`;feuLs9=+^1^}3k$Nk zO|m|ov2S}JYroeeGvXNNtK=hs0xA|VEM~|O5OKfJ!|Th%#|}j8QW+vYxW4D=JB=)v zC%}4kdN!;$*L!WJyK{O%?^}Dr=xV*&|LRIKn4@ur5c;yM&>wx-?>9-FmQN)NLaR8e zcJLjI?y#w7BBy&`gm62BjWCLinEYzk7gJZEp$@o*d zM()?Oe9HiQsp367w*RAhGs8A3{BO2Aoz(~4Q(T0|JwpC3oHRC@{<-nK2>N2-a1&NE zmz2B4@gRXKjl^W`e4qLjr-jqR6KEdzr>~SW=j#r{gF|_d%~>Z$CU5jlthp!q!BJ*W z+^}>Drq>@qXRxHCd~%e&Z7Zgj^f<2LQiY3Tp!fOpkBo_Y>~cZV?NSAr>(P#l^XnX?ZDY4UF7NWahY=9Z4FqgeCs0;AtL*&UFEdu6k)Q&~EPtsF zg#xOmS*9>EP{=^7w$|u!bxePcwYMC(AjOTPtRV8cfbWCaAr^1AW@c7Z9EdpG40~=( zuxbnDp4_AVeCjw}yC`&#LX%-o!jTm3mfru_Z*u$DoVC{&IfhGw&`&8SHlP|Im0sa1 zYzQbFr|#TBEtdDy#Pe-ZGFIit)c|OtJ*lUUn0^HC4|wR%^?e{HdUt%@qRmUZqKM`< zUEC?uJoG@5Md>Ry>P(0XUK5NKs=gy%6U^^U(8vv+8?42#?DsMYY|23<8*Jd3{}!GPvy0mce@nQ2{IbDid^XOw8BgQ0 zldBqD7Z&X=0-U#${YKlG2-qY*cmJ2SI4%=^frs!#5L-{m{H;!@$2KtH38C-P<`tI} zh^yxR8x;%xsSckW;|QA;18Mp&7XJxe@-k_}^MR)iBzM<7z{txZuMwd2^i4t0YP%6P zjXGtzcxUL_V4HSqUA{C)(MjyR>ptPZZdS|dfp(Ss8!Mz`GE7c#9!>NEd>4Db(0R9y zSiLw2E{x~vg2-Ayc49l^BBquDjCtzrkX6EkO(n%cVH4;yCXO)Lc`n-a?04mPyPxIV zZnxF9hHBiJf`hH*B17U}u1C123XgMZyA+kkk#Z|JALOoZ>>I23TDF}sLR>allQ>Yg60P`5vTfa9^`@;;cxSY1!VOq7skexLM|W? zTyo9&7&ZvB-&62WbmyH!it$umU)9(UW%QIN_@zkG2 zeipGi2!wS-EK+=1D)Xs-cTtF_^u*49OTM$C7Rcg=spT;ogBaRWxW+u0z7@)k1h}2y z3*7?JuX{y{@q$ugvV9;b-YKpP=Y@d4lb03~R)y(xafcH7W;{ERbG#H{2y_2DHtkPp zMy*gooTU5b2Gi5=oS+$(=VisldGGtL(v}|+xZo(;&0j~u@rUkVm@QA8poJjpIN%AD(2Y$8D5JB!M_LNALD5jWnF+$} z(oC~~K-PYeRPT?LgFx925GI4LK#Gwc*MNAxsAF^C&Vnd307LW9lyaD+$O(BhR&lxl zc~n^FEi_MswznC|eVSJYHvNVRkxVFvx=LX~K))yow~4V`Ws~&H)Ck(X*G13~VJWDQ z0u_gz?{4JYIzM4sm!JJq#S-<3>u}ty3NW9Yqp#*PX-fPPAGU#uEo;lkH()(-1>bUY z1XTH2_eD3)vc&&w2Ju3DfMJFQHEr~k6Mcoo_(@BMo<;JS(KR3L0SPnw{@kwZPynQ9#S-3I%_F5XWwcNX$HkR2Fjh{RnUMjV zz>2_aqHHG{!#iv+?-2I3GO}+MXshiwF?=HjOSd~7;&_Y*Vs_K-S*Q6qe}Q=6*cPI@ zS^~c7@=oooIFnESP~+cQRd!WgpAN1CC+U0LAdG%S<77l%ho}@CAg7?>P^so`n|73Z z@0=+XS|ZAFNUhtKJ^W*{+U1jW{0UZupTH47J2ZXxqmXsAtqkLvaCWXim{7eWulBj*rbfLS~iak-+4dlcirkL<#YpW%ex3`g0Fn)t={KGSw?U)ij4;G!9G3iwf=b` z9t`CjD8AoF-nE#PX8E4B*s}R&*P*DrMgbUU-$&|;&W5VxA6l`yySns)VXpY_xF_sg z8w2HRXwpr+NJJ$lsKLak*|Ok@S{4dtN4N1o3ku#y+JgxwY#)fOD{u}W2)T7q7$axV zHwn7nh2KTuysIUi(zqyWXx72^4mY)i<=|tV3NO=l!Wzd9e9*IchnISWUTQk%fTC|o zJu>zyI8%hh6pEwN|EWWHO)0lQ2%4Y8ug(DqE!@ZzBjWSI!V%S5B6n$N^M;;-eotlj zU``ScJz`CWC`RFck#7>j&->0)JcV=kt~QW3QV?l)!BzjAxLPp#8}0&LID+YPlYBbZ zk!F=4&>MYAyh&8Bg4v1vz1AE1ue-ft^krHP;d2ux*rpwlzP_Nc=A+2U4hhnw)c|AE zQ>iHCo_6Xj7!CK2>gmZRF-hb!ZE598tUnCyR+lu%r#6@%Ft@dvZi0JRL765m{6{+3 z?mJzNA6y2eMHmbm2E|>V2yProc3`U2!anE}H$Lj5ZtNe`uxHb2B-fWoL*>O9Sgtwb zw<~zfo?|eHH7-vq*f9h+-)gRF)(B0~C^ z67$0Xw^?SCrIVwl9=tM(aoR7g_dc_!(~pLQMDP&g(3Ntcbq#&qUt%MdrUr2&ies=- zkpxh#am36?Q~BQz%W$1Yt9?RZ=lz?jxBERsrg~#i}4-=zM^E=P3~l#evZN9iqyyW;vEH;JYWg`f86#Zh6BY_UYF-0VMG@p7YRjV!xKv z4+D;;dYR!tQC9yLx*$80P9W}U8Fq+pC?_8;{-#sn!v?Z=&bNw`(=H3YO~!ly$-2TX z?OIn+QTsPT(GU#IH-N8-%#eM7T71V(Zc@R9jtJT=yrJOv47z}d&OBpxlM$WHH>Di3 zukh$+C7zT`H$IUx3{oe#UA7qDcw>Wc9#l#4EKo8iF;2UjO=03Kf@Q#GnUXvEe^`6# zsH(d5ZIo{5l)|~U6*L}_Fj<52upfDDaW2tetFhO=FkQu;x_rzG;s)ZV?ueMS|$8cUd5_tE|}KiWrmCVOu2 zr`9&ubx*$|_Cn-KDeSJ#>np8ElHcW-QEiC5G%F{}cR)STm7*t>kYDYrmtlId7&hxt zNyy!l2oXcl9>5_av3L45XPNpzIIr1WFx0da&32zODeU>>??1(r3oU+K#Y*y7Q?}NykW%quBmUKW) zOc4PEF512B^BWYftprS!Y7rHFhxfB&$~1L05C}E-2>5!UDc`=TZ;iWXV_`WKki7a# zLurC=xQ?*WLAD9Q_6yr869f==jcR&a2kO7MR2QsIdidUnH(_pqwH(4@HPwt`(!^C)pf&%!y&_4 zJ&cc#LsTuQ?=+iAN${3bV(}Y^%hH6%$T}6WxTyBhiqdN1o}xKVuszLbluSR=*Vc>| zXdP_}&cPfYKJ{8sok>H!5ubbh$G9paui|zR5CzAX#XbpGAHPi2>f9QX?7gwR>(nf( zUlG&XVO5Sx?sRF;aL0g{*~**}81)SW617Fw?+!_=^u~6`tRU{e))M4?L`mk5IDWnn zu6ffkZOg*Cark?$sMEV(e*;y}XR9ameie2`NE=|7K#?42?L~Z?2qH52Q zqXRN4AmlFncqYh@)5FV96UZr)o(`vI412IqbD4u&HB~MK@`?|w3nm21RtOme zg+tEWi%Ek~RU1-i&KaOS2h()pI)>~}7o6Wk$9XfJ;QBT=6}<^-dI z0Ut1+5S8pEEr{#XU{aMLYwI#vd#u_>$SK8duVUTF9pP~A*RFM-$011&GDyBq^|T4D zgI0uBha;P5LO?|_CU~0{q3+3iH0Mk&iM;LGu4OL3{kK6Q_GZxHga1R$EYI@4qHS#8 zrQbk(Jt%KUFnQKO;uM9oyzw*3_6~``lU@RCd%w6)#q!B?*-mbJcR>s9-G=?nUiD#5 zP5&STtoi|Bd1kh00>gYA@HyKt4G>8WE?+tSCeyv#FKR9f?PJ21i)+7bxT3&A({snD zENSi741hu6y>r%9kt2n> zo~EoJcA^L9;(T5~6GX=6og+doh(^4yc*~|gY1m7ticqFK3A9vuK~VXu?drYhAo)xb z4f)tg78nYru114blW?0bXq7xn*0`li-UklsmDSmITRzFpwzyClD{~YC%%0)tQCwfw zZo?X0O8%yy=2nWzwZ{ogHith}ry$Or8KZhaF~}9jAyYM9T0YCHQe<%1{6%S{*RpEb zoJiiiV2ML5p;20TjiQ%WCpl!rRG!mG6_Oi@N;(aaA&)om5a1U?i(7;soU6D!LS&4FgDUEGRv}ysPb_WsmI$}Wxli_-|=wr6b7yz zi!d`!VLPdXj0!bPn119>Qc_3C!ho#V8wtE{$Oy{=FU1tesS-U#l2DA1;RcKk#aJa~ z{MTRwuq!PCI!+lhy2!$vy{WDkb=n#^3m4pOH0}mO{3IG?{V=wN1UQMzI67~-f~!t% zP|AkkIJaG_Jta6ZJG_yT`Nv&tVX(#aC0v(u_I6CNtoXdsez;|wqrTY5wJqUt(#fJ~t+Xs7PaL#ht&JRX1 zCXb8sBqp>2T&j9{7zfyFJqa2dOI}S?)mUvB+Z4}L7JZ#{cmXEz_||tfw8sdeix7bf zvjXcUqmj_@PGVK;7@0c~QE^(eIS03|fE0ZYM&zA1;yQLIs0g=H+ASpx)Lv7BCXQm_ z04buG#TCD;t$QiZ_(<@R_Hgfp&WUnTGcO(td|O zZZ1>jb}f%?2pVGl&$w-l;V&ru-z34Nram%gFlMc93Q*Q{3H9u1F{5`}%Eq1{iJ?pj zyPAaKVoo!&$g;s=8+37b{|JB~n?sR^UH9@dzMnu>Oz;+A^mFB87auf1#End2?@aMR z`bGwCCmq5BizO%Hg&Jwe8@TsaJw*ja_skQufZf5~6o z7Qv(IgSl(sZ(^*A!Yg%c$uggDW#I@NYHxt%+HhP7o^v}G6p7(l_3PWui1Y`m5bO1kq@PvcdpBXgj(CjZCfyDoPvxriw04bd7xFhmCab7v#tK}=80F8 zwDa(5sP1c_fYoyrxc1c`r^!EyAf!j-;9b5&3$4c~?SN~Ie_tXk>@g}RNDVpv+`^57 zY8-^fCRRmEjC4uOoEp#*z+|qK*Z8aq4Qm1hxAB!7G3%fyRgB^veRQgvOioRDrpTcn z!-+qX6l zQ@OD1lZNI9O^jA5lXRe966gfv_0gC67S1f8r-J}o$fx4k4neL?6#g!_T7hV|(&sR8 z@5lLb;a+Q;{nR(QAo*e^8UsVO0%F!>A2pNH9+jlYl7&#>Y5* zK=bCTi$Iee5E5?=kH}*#7&Vzuj9cP`aWGA2sVLsZ=M55v@apiSBN~f0wp3J&W*DvL zV;S!wEZcy(G9#i$5r(^AGKmbl)H|I&W8==}_|u)n23v8!RYy!NTIV#0Ps>=ZORR*( zG+~}r@@|CSgmh@Hxca+M-T=*3CLg$yL1@OIX>gm*UpogHp6T{%3-j@SVk)J{;OIut zS;l~3)S9={(wPm-v8hZ49O&|kX~-%n(cvwADV1u+PgDm% z+ZLn(SZ8?9O^r)?S_G${dfJnWm}5->Bsg^1#+4V4r%DX(K>Bl8^`vfIS+LR(uL7Ue z$5YuHP$qw#aeS_Yqd}$s`*gU5QVicAkbb6q@tpt+1+!{poz08=3{JQ*RlQskwT16- zN6JTJaS8-hkm@%V3xNz*Fv_KMh0~|f_n|PnXt}XC7=giJ$hqiQtah~;v&LlBjNB_y z&r!F{`7}ph{M1sCKUan>4+h+nQ@AyKEOtV0d8z}eCS|BuNuzZItFO^H--9}hUGg1P zG*ciAH8h@y$xa}bVe%6nYZs-g+Y~+4wz6F4jPT8u59h<;xn>BT$x$o)Pm(g;sQwA0 zLGD+|*$}Z;C8nLP@>`fJqf$U!lW`8c{sGoQbxOxv*Ugbv-NEk`W;hn*R-x1~ z^7X!N1#+j`QYf@!C4*@_!=oUYuim1e%63Xft(7z<`@Rf)wKVby3h}k?%;lBAh%Y5X z@VP2&VIz6)eoBjJo2}zb&i|lxa3JUA6``TPH%hbC`?^)*%l#VKynQnc%_oM-jPE-^ zJy;Sb&DHb+4&IEvGgV8KXsg}}l~-x1P02i*7sjKK#-V>=lRdE=8^n^RhQH46Z&3_u z&ow;jud%x+^`CWYp#+`+KkgFp{M1N2zzh!)G6suuK?U;uF%n2Lc8$k*n}O0QfOFY9 zCK@mKvDcOrHzS>8Rflt9NCw53@J+8xk=d(T8a5Gqkma>2#@_WjXr=ec4>@Xv$ha&H+IBZ*zVT0E#jnaqWhc1qp^pP zZe{oFDYD$i@Q+p2Q&&1MIJ!zvI0!nrj=ugC4+#-vTw`P7Cf<&ZKYJM@Y4g`7c7MFq z*gm)>8U4(@+=^*X{wfCtM{ilnBKgHnS^w%8eUOfmpm?jkqKfO-p1*5>p=V@d`D=8d z7|qzpw*~f;-5*aYZkNB42>UpCl->q9%)3SAa!#Kjb2&`a9eV0r?9531)CE7+OlIO>k$B~b3m5R><__kQmF4)koUs zeH5RK`5Y$G>nwk4)66`3V}AYgT8MS5M*V1^d?{pMcfNS2%;y7rh>L_qnoQ%%JlI&i z>`+ffpJ|<@MBrW72s4r^8Ot|FSzcSr=0x~3@>lypGxaqVHWr3k7 zQ8x|Y8KaI$dBt_ImmA0uljj;#x|(+V!EN)LYWCwm{iin8v9SxNO`Jh+R~Nqz?ypkQ zvNOKSa-`@`%C3ge&x6I|VNih|orplq5F$beI5ZId?9+KJWx`x(TLqR^>gw_D-$za+ znrc9>^YikQW(p(bx{$-CA|t;tyI-8;m9!A?cwDCo&167gWs}7AadVDoJQlL}7-4a# zz}8g8h^wK~0%~3+b%Z7&bl6`I?si_@BgDP%M?#I1SHv34Z(w;%*fbqV^jb?TD*|dQ zIjWy1s$MvszV3M8AYndBc$l43CQK+%uCmywG*i+@soJyX=reb7D=TVYRy_LN-XeTh znaBvP#H2)%><_))&UpL!>~|>1x(0TL^*M;7i8H{XX7a`aaQKF$aG@p8F#-|TBm=u3 zBg;2a1QD2D`rVZ^i;PLa zaVZ1Wra1;^Wj)N~<-?uw{%0o8wJtKXqF8kCL5CNEo1p?$p5_4zhC${?16URoH$ngw z4J45PT&l{jP{qK^jQYpBsb~_PZqtH^Z9q25PenzgZ}3E?LNhE-||Ly$8zLjXqKlmV=bS5EyfTqP24L02t& zD3QsEGaeK$@nSuwz&_0*0GD!qALaWQluHwBi(~w4b~>jOcqp?;P)<>i&ynaB9^U$B zKShIXoq;_PjS~*s;Stv3mef&BC$`#KZm*>k1vP@llZWLbLYJd22{02EbV{!I{~85~ z&|ttWCiCDf2&Z#n1-*C($trG&nRB@^EU> z0BnkEIgk{g;Np^fz+d72>B_-^^54gOOYqQPKiQA>0f$K7f+#pLgNWt_KgJ3k96;v4 z8$Trs9XV{zHB6lR$DamBAzBcM_`;r@vU@M>`ya?@6foVg5RUX4(SPm|_kfs?|3*xv8zzSPc^A)7tQVUW@Zz!y(*RqHsSmSd*qCOG z5HUYL5!dP(HGTbv&rxXKW;F6^3y4)x(Iva{`(X218nC9Oc*aRJ2my9`39!NmDta63 zqlZv{+s-+LM~6+pG)_l^n!<_eMT5OuR1xS$ z;(YeaBGj3<`#DMx4DD+&&d)5Y(ePm$=)X=m1^FBnLA;1xD^a+%$YOmn!6ouk=THXo zbr^k`1od2A9O7iruiq{a{3x7wL%*p%oFUOY5u*w-87ET2oz=1N8?|;ww*vCJuUfHzPiF2(= zhZ<&VAKx-uXf>-|mzu24nG%krV_-n8|L)5Z>!J#2T^r_C>WN%Jj@@Oi4`f12GSZ~P z?4@+&sAixPv$qU0lMVIvQsoX&zTm1(lVM>d-tjZw{X|*%>Rmc@m^#ZIOravuvjhJI>|-A&rh$f$U%y;k_K&G~dB5dWQc=QI6(8bm zLm;UY9SmzU4GS@dTNp-^8i!v>0Ap8`q$edqxf5(4+rb!goSP*&tg=wmh~4r5SD7cz z6cRaue%u5+@i?`8&Pu|C=f>E6}DB`&-FCK7~@mj$?t+Hy$ggB$Mqz?lWpGAu>R zlDE+8ga%SNUL$-Gt}yF7TKMfSik1k2x=#kS61^oeyqhF46IzOhS_osbayhqrX1P;Y z3%qpP@R6sD4WK+74Ef6uJ8%);@{YA9LZd)%qV4piQBv3{3)ov>Evs&$GHbtDw+L~@ z&uDjdcdd&`I=c&16s{6*FK+^B8$8z*|3HYJl34sqU^g9^k|KgKX~`F2_6H`VflU=b zASHd;x4)sprnUU-`_cP;cTXOXbNOb2p8bYE0!HuwwW^wCD3PJJykUj?7-HT^>Cd1) zhrcn;7Cx=Ute#XbS+j)6JrE=GnC2XL`4>uzQQ;tyCmJWxf_gw&a{l|DmC$N0bgl6mYM^>5rob3m9W$C>;08CwS&m*U4c@ONbjm5A0meE4v!t z00gA!2L$&(7uVsi$OM<3ygliTqfp;@hAs#pThu8cI&?|)^x%R5x=f!9-hfT*c8a8O zqPtL-KC3M$uL;z`1-m|!`b5x}^aF;);9f(Sos;fwp~5C9mL+dC>ez3+Otocjiha?W z#teb1U2;vLZ|l79I~`3c_GHuG<>JBtj_ji1@-8kMBYeV*Zu;e;!z@GEww(h~bv+YqE1shDIoqZBB__S^uSfaKEo#Q1)r#0Q~2Q;O;76Ao;xQa=Kz=wVxtJpGw%zqOd=BbQM*9mn>eRplbV9 zb9bY+;3HEjL#Gcs$nZbp4LgM6yobS4by4?nq+|O;kE5*&L(WR%GP8!Jc_&5J0#E1o z;PA?kzQtN36^(Py++!>N$7nwZ{OP7uf6i)~?)QMQySs*NOJNEWZ%c$yRV3u7}(cXZc-$J>eAkxR9mGN3FgkR>L+S&znVv>h@-2D=} z?Ixyz1Sjkh73`V^J8^2X!;`sB6N|z@yMoP`hx1{Uy-;myOa!HKC9_w5Z$o0>&?^2c zgn4+-xG)Mt==mNofBupK!EYRR10{(21z#-U*TP|3QUq>`_~N!ULRm~c66&z|5<@%3 z&X^hg=;+wagHPAe_I`M#6)6Dx4Kr%`9^gNMpy8KmdR*+1;j)e%A-wFU7~WV3e6fQE zbeq71V~9bj=Ed7UVg^XG2nx7j8ykT?*3aI>tdv_CM|ERVR8$}q?I}*`kAatI#t{0Ag|WJ} z$+~m68?4xN>JvO90SA2LCzPnAm`|7JK~+D2^Ler5+Q=y=gqb>p+CBz?vu%={3Xp$C z_-0Anr zb+J08c%+g(r%l=+&j>NgdTW;7piCn8zBnR4fBuOMiT3{~W+}&2QgB*U^VM9{&CuTOi`$flGfOgIDS>t-Y znuJ=YqifXW^Mt5Ezq_=6n#(j_2d=C6&=%mZ{hwPFn-74|#vAwL4qwa|QBvwO$qt=e zPrCZC*S7qW>2MmPtA9+2)97X|?_9Mq+gu4H53voDp8o#)fMr9Gs|`G_lT*KWTlwz9^L<{=s0-RJiZKx)D3rO+@Z|ok0oL-zXQU92f3ss1tq%} z>A(5e2JX`l%Lgrj*TkgyMlhn;vjvoDdq&x_tif5obW^U-E@|!VOSm{LMYvxNv(un^ zf1L!GqMz#i0LewCn@SmgJYHYnE51!&Bh$~sAhQu&00Li;lQ|m=O|3L=I)%%Z%gZkM zvvVvR0iQ4#xIL&ZUU|7VJ@_K*9(FuO(G!OXbYTZIpA_AjSKGyRSj#nsg(pc|vGU!|N7aV$kAoR470f7ba%wP$UrqT5@W5LOx6o}%KS5yp1-pT?{1z9U1_yHY7Xh9=j+ z{j9MPcZe=+*q+q4uqOYoE0_tGt#ld^5K{e55Xk~JZ!#@DjF?m{*-M<>EQusG;&U)= z`-cBV@t5B}KwQsT-y<(6o{*S?M!GPIs=ZDF&wqrSi|HrQjOjI=m8OzMdXM(&)MaB_ z90)le7$o*jNl0bghLrWc{D5npdsiJVRtxBQn)%o9Cs5%DgUSRu#n@D0WO_x{Kv}u_ zy#20Wf_q{iCf4o9;mp}>@l}+he59%Ar0Cbg0f}{98_ZN8m5gR2EU3~1A5i5a;o;Iv z%T+6>$|7|cV8v5l=yX>fg9D%!J-eDFMNvKDqeJse)^8poG{C*br z*6dktD)QqTq@WtdWF88he*?)t1TE~w!m?t>X~5FPRkiIV^%lkSn0 zIaoJ+kE(JZZ8bF+k${_!1LkgR&)28);0XY0FtyIvtO0Rlyciplyi@ct-q1gY^EoEy zQ1SmaLn%<{vS|(}KwNI-)PT61N`7BsVP0r_(gz(V4>>n&(LSXFslbs^12C5hY13MdV7<0VsYO1+iuD;3d zFT9S++_yjbjkWUgHz5$9cCNb1h{zy`!RS~LoU2c%7&9mr;MMy-%j>ig54R!|Z zh$0)l@Xujk3}x^e2IyKk&H+oBUeEm+eq@`L@CVcY8H)cx4e&RJ7;Sa3YUgDD?4R1pv; zRUZYsxgVEppa6yE6UD!{O$?3|8dty}E$hXKxxT_xP>ebW6fh#QU&LyE5!eP6$1!S! zyeAQc0|#!JT8hzCCIS;?wK;zNU@REaQfS6%y2<%LDBB|fxTp`J854hm&;m5j`V{)N zaFjEK{*6}0%41^jlXq9Ev8LPD__Wewv$relhWZP++C z^qMg-IQ}bu2IiX$+;z{YkM?2n$^aDUureRYJ{S{w2nwpHtG^WoU1bn-H;j)RG_d8A zl-||SB0HZQi)*|~H5pwM+bi=}#D)!XFvSInQL+5&q%wo%x~e8dOMwJ86pLHXofixc zNrxh*3+m!zl=e~zuH1bNc$a@NoJ`E!F+{WD*3cmh zMr+PE^*_s```M)LJ?ig8l?7&S3_HKZR5lY zh)#PKGvOV`KQ#LNZgy!OC$$0&253HyM*PDp-2(?l@B=H9dJW++1P(E48i3Du>j=#r z`8fg~>J0Hf^6l?K86Avxd3*OUbu2Eh;N|hqWb2LS&bjm-r+f>aN=nBqo6YpWy-7iEC*!BY770II~@LOOzhWPaKpz1_iUOsZpVp+I57^Lv93D+8e z4@+Oth!`;laT_zlstbyMx5`VzHhwhU9$-Ok}i-`-4;U7}rqmxedx7SOCx<3L&h9+6}2nqS`NS!Z!{|6s5;sDFYsc!QDELSQ) zC4NO}v%5RwpO~4cznhA1O(!^zco%j4nqM#R)s(8LLBmA%h|8TA%>4a$+d%8ZXh3B7 z>ChbhL*xq}Uy286o?42(xB}3%JL@%wyW>7vOU{Cs$IV}4+;jKfesL>$=ae4(t}EjC zLwh-_EKM-91_{K1uykQp^>!Uxz*dlo&XW0!3SK_HS`iNF)N9@(S=7QFhb;*T^5Z>N z4i8QYpyOf11HRMNI6VWdALTd=U@h-5_R8sI2&B{KgG?JKK}CZ?nkqT;jq9Km*8H=lDx}=rT3}V zBLD}m0e9hE^wtCbF@O_+x7`<%C-Lpuw8=|{Cuoo;rKck;*R)rH?8-eWk@5-XT752X zH0S4X_ubp*=gL91xGzK|W#7AbbDDUjwMC-!>pnW69MwED%lD}laGC$qDcBUnLh&gY z`cXLaYcK`q4FI^529}!S_0)x4~ z0GXV`{c}GU^ZJ1N*Uz5uV-z@U>>elMvxZY2yZFq+ptVHP{pXdG$m!|hUOQ9@LqkB$ zz4?c_uH{?uZyKGwJ7;8lmRrV2sZm@zK_>4ROsO7EQadQuKc#X3q9m|^B-Jwz)*D~a z%JwR?D>`KvzXV!G-wC~Mq0?MPTtE!Cn`)hHE_1~siW64@rNRf50X3hJ;@>JmCo%97 zrdl}q^#-q{)&4O=bKQ~UXVhwjXNLu8n6HoiB1m7+k-Viiu@v$VrRZAP-yo)dJONz# zTvJX(LFRsiio>uuYBfPkz<|SBKv`Hrk#C+KDJkK-2@)@*&l!%0&z8Ik(EUBiy}&O0 zfh&_{(T?(|?EPi!Ft6Lhp=Sdx$KJz1$|VM%pV-=5D*-_cW?q(^jiW14z3_OW=B46& z0by|>lKC?NWm#@suHeH7dEoVQ>EGyDiUUd?;oflw)jDbQAO9kQN-{9w*HD}6^uC^= zCmb$Kb0ZdNl$f!Gr=JId3X3zm;C{1a|N_WZu;F5c0?q4&zYb#8(9&qcP0djbTsT4RkJldUUG>lA z1WrFHiT}c&w3r35+muK2lNhlnNRPsM^8G+JKh++ha-CxCJrZ#^X6CPR>IR{O*?wdn z6Ky3*F~?o=3ARD{T{#65xu?slw`Ff}qkQm2 zAhqxyl2`sF;YtixKHuYOKjQtv;BHa$H*FEgxX0ecM^4>0AtGm(mu4U5ORYjstQ8^w zcG%e5TIs~Yih!5F!?oy}=-I$8=UeXhos!`!^e0eAVx*=lbtHxVez3wH-YUx*iRAtJ z1s`_S4~y*W?Cf7?8z-K@RTNa4{+k731&+Y3!Lsf-U?2Duf$udE^s8ibGz8qgl@vEw zwR}m$*N;qBx82xy{N;^iUx0|HP?n7H5SJ=+F%im8EnwpbkmkPy1lS?$ab8j&jhpr~ zJ8*0d(UfVgFHd9UxmmDTqihOZiVYr8bqgvGkkc{>lfJ3*J?@yGWny6i4h^5{D;EO< z;^)=oR~bvc$;Z!Vvb}c^_lwJL@{=x?G@Cf_Rve=Z_l`-1Y^Tig6{d=+t;{xUGm>t_#I_zS7|3>vt@uVYz za~1Y)H4Iu8VTVIUha5L95%1uyg6$|EzXWF#fK;hlEoJP4Awp}GPKoFqsW=?T?ru>L zQ#aV(SIy{ku(`Z6w+MIC=&0kO^%p=3^q$e;*k_kDyX$%j2Aq1nMV6%yi2C-ewoJ(3 zTW0^>MZT3gZmLE66xSHQMN`fgKn(KkiS+)s5_9PERT6>}yM+eQx*1?hI-8=ERmj9^_K!XjPItyYz5_edlk_q0y7+!U; z3cR^GvwTTV*I!by@%x9#V!TEKOPBF~koOS1mHaIvr7{COgr5HrYiRhQm@>KhZmdcV zP82J1Jvfbg2YVK4UZwBn1y$nj(cu9xXbu+tdRD=uQ|_grr1r}S9OE-A3{#&z%VPTg(BzCpf&A}Iz0^X8{vaZ9L8Pas=07;L&Mw+aQgeT?8V(@Pae;b4 zB`;Jp@M8U?8h~OoLeHwH7RAZdxeeTs>4k05>o+(s^Pg z8+|S9Xvnd(y*5&va>D!63JL`;xnc`=kjJ0Gn=0N6Rxc-+3tJj`?TA zrp@7C=;#m=W}E&|Kg>Yu9dBsYVFA;tiLFd9W_KtW-H1HJqKFQ%Zg|mCpUYJ%*PKwS zi`LbU&0p~t>s1;;VNU(Ol+rlD@g%>%JC6v_P(TRaj(wM$l`*=1EZ71SOUY=wabALA zX68hnjX;+URoJi}USp$z&YSaZ^qc0DF3=%wWq{Ghv*^bvODa zQt$2b0{5uZZ(0j4)3t$p{$FBCo%bE7ZFhVk7vINn8f(7|njGrb^S8inFI;nqaMhU2 zZiGIrQ_dI~uc1gr{S^{Yts#(|3!c?^b{?HRz@xGfJMi^nj8eTpy@WtC7y(fI_&7$^ zR|#QPdSte?Qt~bd1(YtN$kFw&Dz!gs`+GL%;J}EuHN@b&HPf5y`^|fC#{i18bv!o0 zrO|La?A7si-Jx%9cbX$22t7q%3;}`g5IG$}`%tc7)+_-rR77{|biacIl?$}&?9W-& zmw)DL)AtS_H%!IY|8DXY{pY-zV}l|EyWlUK5Fr3=davu=;34*j;&J{F(q8*Xl}nd% zXset^xH=5+@$rFxa>XYi%xiAORYpFi)$SqYNJURdnj$79lhA&N6&5DDdZ8{?hr!Y1 zq|ozmqvEc=At633Lf{W*267kkX4v<5>4HNYD99QiJr-oyfGh<%gdd|D=t-Hw2fw`_ zdK=cCEktX2e5w4ws)4MP%FOsk|43}M(xE{k^7lVmCjAf|r~Mrs<1lgxo5_wT;}}-5 z;W>{*9p`N>{<3PLhGoT3g_ZHpA{-o2cxVWl)*Kib0y50KX(M3?6I>XWPt2U1iBBD$ zO$kaho+u0r9?!nLenCqXTE}s8=5-u*RCFAK$v$ICBJ+5@&@NTwIoj5vRN9ccD2o)JZ_7_%Bt*#A`oAkM)U+Nk3Egogey@Hw1mve5b5GDvr+I&J*K`>6ZmVf%_SXTuT*)>i3@mt85C_yihs|K?;)Ne|65D{)pv$ED+PijFs7rYr)Fm-_^zwV z#LC{;7UuJ9znEJB;w>-9&B#GqABmb2CZ(P*$H2hcHJ8T#h+KTS{~xEYj|qo*azfJ~ zC+X;jiH815O;^p)(7UNAG0c1dg;OJh%dCO)r1!FMgpFLKP+qoLm}%dh9azw&^50;? z1PHBkiZD6^aLhgEq6h!e2?mvaPadQc@?TO4Xp4!cJ*MFh#oYZGDW@p^4!H%Ac5$_O zjzlB0kkti=c*{-#bcO<(BL#Hgp`oLzYN%2T`Qe!1i%Aow=b873+9440@OYg5;K)9x z@z`+%vT#(DmGEjZ_w>Mb(ND7Pe!ZYo*I`5f-d^Wa2$|gjn|aLW^FODBFQ#b|M_5Cd z$>@Smp>jOta!Y}PJUVMVni-S_*}%)U-OJrcV~~ zvx6qs^yFP$0I;^EIgWAiBZw0@XR1a=PvBr?!oyASpz~|+rC6s0f)dL9n;VgvNydpg z3r9l=1s0Y9r&l2x@4k^oZXQB&PietMuG9 zH#gVf-X3|zGX;gWPU1p)jg_U?eO^`>)U*(8Iu!}&FE)A*5WTpB(fuySR8|@&8!*-% z7Cr(q1E!TdS;>!kdI9;6bt1FcyVdqlXeTu}%hr%0n-b3>oF0k(nKmm0P=Wz^QGp0M z^v!%w0zlICP#rb!TUvPCQk#j6dtg>8Xc4kCjF$JJj=ZfPIh%c#jS zSJNGA9(TYn^!KSYynPXy9e`kwoV?cD$RiP-ELBF=I*xop@BN)-GOoKeI<84dpxvM= z7-M(A?kx?UAS&u)Lt46<>CC2#r5>95>(7moSG}vQ^Q(!dYKO@K^*8>BXAn1Tx|9OC zf}u2H+gCJj+Du-t9>e7zBYE<^?2}Hr#i)TsAG%7#t1SnLv-4%czsk zCwxICOFfpvUKfpp1&-}+uij;Z(nX4s>?ke-0h#E>?zvAR|73(a)(|w@xwyuIPue)V zEM%N~JUE_G`dVtPf_qD{k+uBBu^^SGQUE!clta$j+T!VnW7MW{R_GC(EeiUF9rOgVyvbx0xj!8 zEAcd@RIes36*=q$uU#@}x5$uV8ud($^VIECXA9V^MbXypi&iODoV#MuqUjs-MH3>N z;PV6<+R5+oeL$_A&cSf#C&F+}FvehVBuaj1DZT|g{lM6mbRtHyjRNkia1oE#%`ZIR-5yV9bYrYky>eZ4OLH;gHxrHYEEhrU zDeub{ey(MC=H}NCytw}18IyK0ZFJ4Ra=yB#NoUP&*V zaCk#}Awn5SbRkvq=?OD8leg_Xg@~$A=qj`D-DbX><+zhFvK!;047&!x(zUjTMtGpW zh>xqf+M633!{GX6bqEhfD!{vG7qp`@>~V(NCo6kAf6?wl22v4meHtf1U#zk*AKN5& zbLP7&nR=!hJ9LE?Ct@o_vM})sZB|1I$I$wVCd$b)<4a<$9#BPnu7fd#=&rES8~H?0 zKlL~7&*;q;`56_ja02`mXTmdXX$7>jBjGja2jpLN_mtvoFZfPO3b#&Er=8k-(DYK( ziVt3QUHWxHCNG}Zy7=N;aY^&iBuPLIS%ynQFxWfJNqrrK#Zf-Rj$!cC_sYZWr5Sig#O9w34P#Mk*sU8$Db?&moWxx5Sxq`bx>t-U1x{%@R$9*W&`B*1Np1 zltzC0up3q%^L6KzcSt*T1DrtdFAaUe=qSP{e@ zWkZ-YnTkpiZqi6nBAsZ#`?bds*QYTwjRI<~O)a~Yi8FhC-$h!uNVf?Xl6_|B5OwKJ zb7?-g`W+y!^;{;RD&fjugBW-YK_aHV2Mv}yTJ-|*3db0zmE}tG5dVx$U|qv_GcS<^&tBegJiAsB;)O6I8!_?6KYAL zF5>#qPkJE3Py3mtlftI7J2K1`<15U@i?`0wmcf7cJzqUCBVDBupyDm?{h(1l1f>+; z(7MhYH{lZ*vy-*h=jMsQ?XttvoArkFn9-SxzVB;i?+aC1JhQ1ks}MgYC%;T>zZVwx z*nauV%81iHg&rBRW+?W?j9@hs&B&E!>ZIglHg^}~S$S*`nxGy)-D3(|653wD^i*q zZ}HJZ)%o<^N%nP$8-TP#HLAS`_{o3hg%TZ5w#OyJW;hFPn~&O)xhf3C2+MhxxX58l zu(gi6vjmsTPAvP8&_6*|_1}R7zBU~GjVoOXfEJDLbHwlx^a-X|qA3onA9m!ph%H48 zPK@$O*w<~hYhEYD2BBx{kKD||Lxqgnl9QfU@zW>EjoaGR zS$F!=7KQk#^y98$JPsS~ab3Fl=J(!+uRWYrT?L&FZV+#7kY8Y{$#Mq(->l{sERkNJ zE>@|ve(gRuTuphqwA{7pzBX0iM9b$lN+dW&z;8KTa0fvC?r1C}Niv z5{oK8zi14?A)%o)InXtCNQAfsR7;o{lGN)N4l2-CKQS^Me`vpARf53W4_jsR7x!n2 zr9}L$+mW;*ce-i0KdP8mo{oW+jS~wc(d4VMyjHoz16p#w5cGPfE|RhI*qEC8U|KnO zn8;<4VotwX-}qrG51ScuzUrcXNXEH_u3S+yEv=sUEtP2XyVTPc)`O?-#V&S2 z-UlYLnLVNR*2Og|kDzl+oveu1>u!4e#rlwB-dR9%jWahd2~E%{PJb_EsG&#NOnxAj zBWrN0nD#oJo>|-7zGaL*^t{uhs5?~1xk%uX_?oDWfvrC07TxscD3DN?eV?HD7qFUF zm7(ckHi9Vxh+IwP0RjHdiNU6lqpVL7rk9bRt{>)Kn2qmy>^H^y$DE_0m$edcb?K#7 zZcXwn1y*_638*qIjz(U{UJuC2sJ=NSwvElgh@?pmC32LHfV|BW&YP~e(ndG09Lnt<{>a*Nan+dicZb=xO)m8juTA2FzRiYb-yb9I z9PCR;n$e10|4fapbK)#NFx1oZ%H4m1&8cko8SxwN`1FC*k!5~=k%3d9-@QK#hu&T( zF9EyFq4{$|D~C`#qMxE)>C6M5+1)3MWeoxskp_>>V}AH zzl-c~*UhNiilXDSjr_O+CJ-w+$niWzVL@!tiB3Ee74v-~e*C)+8SKcP6=FK_sD$Ck zyZKw0*WeFQv*(S>7OB=OxWDzr2IwCWbD9RXR1_{hIk?{`V9tJPG7 zjMthf{Ab9okB;bTjS~=#NQ*u}r}EbQ#Psv#4?G9Vg*yL4=aZ~ z&yyPAwuC&73c4UuF?D?>dA{zr6-LcXY^|z{@#||$Ue+()?`G5~d`{h?`2{Fcjtf-2 z>Cdjd)w=3lrErS%6Xv9+|=Yk1|Ffd*yUi3Z)+m(ky7 zPI#RW$7#RnbnNupJ-j;R0la<&nvKVJ`R|cV1xx--YZj@cU|6*Q@_vGvwvlOhHsmbR z4_|B6)U}B6uu0c^i)c_1_p7piMX=pyY^jL1^D8xn9+J~v-LBPbG0psG8lWo2x>4>8Es?2 z3g%9r@d)P0?_N80wwczTy@KZy9EZHNT27QCOn9w@n%(a(>9Ucmy*lRxQj`@h+g2Xf z%KnW8f}4b`jEj-8=P!mx{$K39Rajh6(=M100tAB7xJw{dCj@tQO>k)l5*&g%1Pju* z2B&fF5Zr^iySuwf({MW9_n$d)F>^l`bHnpM@4b7m_NrR%TlH40dgQmaoDNj)%a-Vj zqd6zl-h#vqOFk;Ty&~2W_K+=P_N`GKigW(RCzT(^|L$Xb)6ropyt<`e=yNc=uDw|n zyKx#PqGfe|;Yn(ZNpsy~x|@9KE6>cw0V@K{X?ZdLo!X5W<$%{WQ=H2v9ah<+unB*q z(SH1!VA*8uTHSfe^=>hTCSIl}!W7yP;#5a@=GYapIxuzG#iJs5>3eYxyLUVJ@fV#K z83+n!GbI6g-!8#joWVoSsl~^aumr3nnxuv_h?@O7Fe2(0Mqvp8*-`8WpoKhxx?pZ;sF+{YLTkdIJm?X9y1kQQSLrwSQ>J{u|Nsx~|-9 zKf$3pOW~lCObbdY^+22DbFD!xjLZK~0meoo>`tW|@(MePFHoiBimzd6%N6j-NBblxWIOenY6fXQF&m;Q(D(Yz|@!c-E0 z5$IuJmtLcHJr$jfn5lo5qvOP~SMZ^yQ1LQJffVZ)!;&PClkPxtoQFH?ql4F29E~z@ zP5$dKlk24i>QzSgkq)ld)qrnmD*axRT3m8u!2!o7!ZIXOA$v8~0$l1Mub|As^T6wO z<`BP?I}K zQC{qZvALIcAU*<1HSm3T`9pXLSTq+H)=oL36n-bFPgGs>fwry;DKS!JNCKW+FE+}@ zCHO+mkB9tETR6^Cia6B13tfYY38y_^Mh6rmY-!RMt&;}k;%!DtEkc}yVB z?|=?4rsyUO{qHwO4{0&)uoFLZ9n%<~U~($;UwGZ?WzYuHsC(>lNTIk0->2JrPQKfA zlgr>}zDP4l;+XrrmA=j+4i=d0=e{qWFnPS-F*IcE8Y5xkZ~As#kzb+pG7HPjl2OKw z&c$+O@QEdPuot?da%0HvYq_fLka3s03Oj~P$j7W^ymffhpX5KHs8fIz68V-N)byS5 zwE2egh_-dzheeTaUdjJx%+olC6hx98u<$)ewdid*lhps*+N7|4S zAv9KPO2#I7th8P9_r4b6^A`MQX{?`Gr%<#}4WI7=Sq5pbtMH!@TZka{?uL40VZ+qooW^TiPo$Ul4F|<{|w-%4%Ke* zu^_LySZh}6!USgWGx@B&@O3@^xerC|#(s!-D!Ot|meY;pa~QnKYJ1ea5egEzKv>|0 z^~d*yrb9}}sVj7IBMYM%{#~ze392!pXudp%q=uVjg%VAjiv=GR$WqC|L|);$hFKE_ zUYr@iR1Qkc_wgg8-79jOeeSXtEJF%+^l5i~ali{rToP%WZ#Q>0_#w2>iAY!Z@j!T~ zvcJ-Xcx*CufCzjQcfc0yiU$D)=r)x8gVwE1*D?bIe$d_KlLbIkD zjT%gwPgqWNks7du1^a1}glJ{QaTDh<30T4c_rcM)NNd%81{e3g5@Xmuh5K8&|APS= zZev1rkU;P^mt_N<)q7H{bD(`WaDsSn6 zK|_Vre^gRqM@+G`v)N%Ebi}Y?!;)*2(sU{{LMUGe>s_#u@2+AVDUc18X z{6+;jWgvxfAPQ*~>Pa-6($9T3bD%?46OeSNAhv6J-;tuwK?mx>Vvzox^Zv`!cn6Dd zX!?dDr_g=+diK6rBYQ@7I-0V2LJs@8hc!7Vd{@9!sGfAUzl5|t#0F-s|M7%g8F#kG zD=b`I-C2#=n6wUY9BQ3@hiorf*r!?Ee0tdswb69~t@s~Zs``sRe#S?q+!!1*qZCWp zH6Wa0$Zg`fs7LGm->bQA=VI0tzC9i3oa7bEk`i(i`;w23o>V=@6~8r)(rDc4&N{xO z{S`RPS{{1u!HPirC}?|Y{^6`sxSePmrYQv-5r8bN;C}g!t8n(*SELU{i@e{K2(60H zOys;P>7%q`P>-cUX<+;IDu2C`ZaG3Bz3gv*!aD5G_+tfF>5t73pTJ#}__-{O`nY-}@vY*GU>3%}HQ({%{xWU`;9#Z;2m}Q}!B#z@M-D;W*3Hea` z>1xhfLDxvdjpHO`x~X|BHB*!+^sbtY{n&YNj=6#p;^H{0Jk^@sc|laCC^AY!&?3e21K2cHNUoNDggIx^)dOG=nFR)A{TXb1O|RxZI_@4 zF%op4HdulHOBf72n<9)-z$tVfh{lnXzVQIVH)g{qg zCPvX3AB$On!h5bgyZPpO5>;TM2R(&$xXhudmA&H+=QQ?WgCs=*1F~~Ua?2)Fa?-MdybEf(q{d_ zui~3=PO03R-s`3I`h;lo`9d!C{lQXE1DG1ARv|A|X4ABF5SdJ#pGJDs*4%o6b%~L< z0jkEY9P!7^YmE)$^$r-KG;cwqk<|#ThtN)knOuF#F}tKI^h32s(e(^3xa*}vinU(J zr+&m~gx|=&mLtT`lOijsmJ2E*7HP#MGR+ZQyWk?JWrCIot>$r&fZKeL;tetv20ohN zFY4a8mb%}9M(e9fqZ+nksp{5haU>{6MDTbL3rN$OHh1pnpV z2wpXEE}#au6iqDSqb@?x&MSW;;?u*cQIz`=9mp@~4&g~WsK~~?(6E3Q|L{-KVyKbJ zvH{EJbiS-oqWGXrKH;}nl6OT+aEsm$i)a2u2oy}4u`!SxMK&LYo_jO*UM^V8#KL+Z zHj`!dBg5_>OQ|>_RxU-ZYIM_by{;FEFD9|=-{~0njt)x=(r0w&67MJ_h3bX@^rjse zbEf23@mSWz;TC#&A0ICD8lzYqH(KK$>5#JB99*mx|E4oMcZ$teZE3w-K+u$SwO$34fO-c;Nea{~d<; zg{X4yZ)*q@5pEYq4&ta2gy)Eb@O)08jbANv9537#L+umlKuy{sP%P3{9WA#DuRDu( z_T(%}k#L=d$SRd#y{Dw>(t%yMw#DppVjn{(3%A$ev$(}E0rT1rL~wRv{MEKJ!o|lm z_8#*ta+3!@s0A=XO3;5pIaTg6M>lgoC=Kt?WezGk7i5tL6~CxksKx z7~6>?@3j4tBWa`K#1TQf*;4DHjsol31F}xS~EGDiA8B-y%(s9*z-0+%dDCD zKb@kQ8kKt(=}S@y6Cn1Scr+2_i>cRiFS$wdy$_|KVM6*s4T$3Ne+s2zz-?WJP<=oCT|X|CzW_a?Y92rMNhn{Bn2reC5~vQ2>lCXL)yp0W`KZ`GS_e zqmX=dawyWfH%1*Lct@QHTN>;GwD&3l{y8gx>=DA@771y^>=S?rxz&e}*9R}o)%36{ zTrqS0P`ep)fIV=LipaX<7QErRjTo>Ql8eMt$u-hQCg8dKKo3Ziky3pA0S#3 znyWa$R3Zvd|Lj}zW7Dt2%LQ~!#$y$oIEbT#DX7J$uQ@=Du}2K(=5jhPxm>HmN+HdN%VGhih@~O z$GVtkHj*(vQvEDDD(sZo?N`Ew19r!<*3V1aNkLBs9Ot>w6(leF5thU}#grhtnbPT{ z#0*Hw19%+jHaQHBRWrl7#>E$vx>-{LcBocbkefnTtr*|~#c(fGwi7V(OvBi?`I1N; zMAhK4(Sm4QG4*C#^*+F1<6lzlH{pNO9H{@J=Fm?6hsqCv)YyupO1Au42wP~rtapkI zYIxLAnUk}r$3PB;71Zm9{4Rtx`PKX`a4)kBzZf7>0H@40?#$aP^hwp%ORWukTOrW-+@;@@N~W6fr3A*g`>UH?|GfG-Y#>RUA7VU zl1~|0Dvl1ITJpZdRFq?mop^xHIo$;fRkMLAqWKl{ANFsRT9_phaGjgS^i*z_%H*1I zin*qaC8V&JKdY(*g_BHmOPC1VH$bTsMv99?tIMR^Aps~#vku$WRB|PRK=mmIQgVKX zib9#s2Cd@>svnEP97IsV{p%tA^ldkGWXuLctM!{c8z);>Qc5Lmr_DEScR5ZP7mEF6 zvvjsUV1?mx<^;6bf8=DS4j8`h5Jf0;%KAZhoxIF*$Pc(Z$6uap-=ye>s^lf=#kdc3lN zI{QwY8y{z6UK_ROxkElpFS8Kb9`X_0{wv4wPei`*6{QfE(F=H$!NA3};aj=YQ=R0L z?)NOTiMTihEA(t*8|vqyvEJQXMU|RB?>PeXIjkF}eg!#r_Xl4pn8?2NN>|)HHrGRmU+40lxkTkSdm1Pj6kf5&7p(1Nk~9; zQE{1xa$e6eNod2!LBht$<@fO?nZwAl977vB;BADFE;+E;w4b%ICI6nbl_^mLeAl0d zRT-tkah@>nVzDS4W&@)>;s_;V<&tXn(}Keg$2k8k(88Xy@@E&>lE1=#)9FgMvME_o zH$!~|Bkh6z^hySN{Qxu|h-keVajLg)q)O>#aQ)SZdS%I(cm@W$OCK`5oE(HfjGTJl!trci zpKgOA)_8&xbU=(VF1ApM4&-e4S}vG3OTfTVFfa6p~i zbKDOs;A&tFh>5np&QT6}O`05zoeKM@q|c4(YN6)uSzM20rGLN+$$14RDU#?#q*5Gl ze;3Jq^^0>2qPk`d7I$ z$2(X4go^Pu&93Xpy>dz|j*_2~EmpsLnSE4082T@sLFh9rvHv&GJ(RXA9qB$4MBEo+_;G4IK;jv$Uei{==d1Wgp!S`4>i7O>X>-w0tMgfC~)Wy`gyvvN7}J z-CWlkdbL)3+&-UpEI(PQs*^*oNHyY6wl<>MtjTFoGw%{`Rg3PZwY@3p9L9)owXguf ztQf$puU%z%N)3-yr)lb>*NjwLmYQ)4t=+*=4jX&Dk+&-eA%qxlx|_HOry`~Z8(679 z1D0S@bZWbyBJkQ`-g`^D-q;T26t>2V9zEM-jlP_Hab{9%FjyvE-|dA&U25dr`WDzw zym`q86?>eD#pRFcEtXPcT+A<jVeO!ZTjy}zeAyrpAe{^9F@B&!S?v-c#DCss>|vyC)Cz6k z7FaQ4n3i?0Yn0>qtd(x^4d#2giDe>FZ=jNhz$X9d)&1abH?7WYmw!^X-|R?;t~qxt ztM}zD6uAPW79TW_GZi{8;AtKL(I-A5&c_|S(yAY=>vGqBQ*Gw}OtJTsoS(b<*RDd?A$vldaxKy)+QT1!z z+)x<_!KDAk47L2)->F!6{cj0o$Y8n@317y8M@rBMKOM@V%uLDU%AoYKBVtS=Lk|P^ zy~Fpb$>bgU)^g@_mg6L9FlO-ZT8{5ih#N39#YCnXg-4Io$X-r)o2QH0-E5q^AG=?4 z0hdJfi`UYrpZoL>uU-T8>VG>Y*rfkGD<|Z9el+CvMWU4ZCkG>>KMPJal>D;!wB6J$*xU=zArY%uKsk&P+ zSA0{p65U%1w_{g~soy?o<4F-X%09?4|50uCzwvXF#L4NvV4H0WQDnwwsZD~%g>T08 z@W&sBe=&UA6d;N;`fHQmhZXL=zE9^BIY(cw46|W&L>M1?%`KUle^34)s(o)hyuwHg zM4H@V8^lVBE|+kNNR3=D9QSmhT5Y8RHn7(JS`*omj)QM7XLUKTS_;CymVhrKzsM$q zDolNpG~laV-A#UDaR>lK$hSGGIAqp4B&3BQ8Ei~JqL@-0CBaegyXN1B{UZtr1ZQWg zmsm3KenxKC;Ssc1$j2t;>wnI*Kqs&jaoHPt;zN`N{;2tn6jNw;z^md@7kh1NIyTf@|-uPT#Pj4m{Ert*T zoo6amESM;DWTOkA3Yr2m9%HQs>pxdQS>FJ4SMD1GmrilEZA6!7;*=<*mqoNWg~APu zLseusi$5Stx3}TcuXpLU(Aj>n5;Hb{0U2zF{07dJ9H|$`&xIUJ#Qd4~(5|<<%AV|8 zJUkCJHZm926of`1Nt|Q+iY+xN|Gd&XVog*8D&?*=?`+DKAA+to)nJnUS86nu=Wpta z)MQ4{qEs!fk_A7JOCl4&c_)qBKEy9D&}=``xm&4fDZ|qMi%v2nhTCa)AwL7@-DqZQ z@{E|rb|_g70$+8~y6)fI`QQ%nV%|!Avc8K))n*nQKkWz*OqUxR`DmMxlt}TGEoU%; z5FtHEO6g9#mnGWve%>Nqv3gTe#WFnj7k3^if3$FX33|M9BobUv;aAneJhEGtQZW>H z+7a+;n@(Q8N8oeg7*P<2{ps%3*W7?hg)k&yDTlVdSfBYswz!TWSNLA(joY7@!`ZVH zG6j#g+o|cz($$9~UY(`)&A*7LI_K+FI)brRWFT*|eeZdE@exu;$AuaLx~1#cKg0Xy zeJ>WxF1?zP;B{VENOEL3RYA@@(IdnY@UzXO^TWyyF#_$Kq z8E~8sN8<Xumm?Tjh&C>n@dh#N1 zFT<0;$Y4u+R~4;`s_yP^iG@s>i$!cT0-|_)+{Lay$WBmceE*eg_z&X}6A<;6ion)) zlsj_&0~?HyTOWgy9ro5HI?rl?3O2pw@9#MvrN(^lbzLc3<&>_g_|qr+1zp{k_~ejX zknihAnW&%oH=DOB-7=@mn9+-oljb99VY|X?up`AR$v^~v*ob5)M-<6!MG=rc7(H8? zcSUNYlS{udj|2zu3oI$PLo7upac)CV4@%bv#&7-nF4N^oD>K#UQYMHr7(?+Lv0ON3 zTBC3LPfnim2JSLz_0o9Riq6DeqayMt5V$~`qr_{Hl||$0)Cr_`SCi;ae9r5Q)#meY z3ZE1LzT_J>byXZz#;)V9(7X#(nr42G{xLbHgJqlI7qJS$WJ>7nM7=Jm6b`L1rjRe! zdhks@Wzth(qr9TRL8O}=|2R9+9U@_w5bQX8MQKMOpxKKCnBfTruZwvUQ%m2DAMPux zTBkEdXhYA87xv@S+3(}N704d^v5*8xJ69UJ>rtp(HD!~thtl-`92h)q=3XA*Ysr*9 z2SmtuF)UvW#Qh?+4`OO;S>+D)i}7XpfAb1Oyx;rKfD;_al-Y-!55=)!SD>aJI*Y&L zxMJVmtT7LbRnr%f==1>E-zRxpGpek_xzCu3zM7$+csvuP=oL?T$; z;jGVgy2E$bSWgBy{wO1PY^SoN7l>YA-(^8EfFI<(4<428mgqJj@?6k>6=;Lt0!mD5 z#DSj^D(O;Jq@-2+c8bwh5bsklx}#rsg^~U3!U%;!>H|VfhkRJ=SiCPLEwz;MUb5O} zDpEXysk&u{Au+r_aXdZA8UQLPVyIK3Tnbfv=UX%1@7S4<9*3f|m~;QJT-8rlrluI{)&P&sObJFMp~#Y~{vNz1(oqAf)x&FH^f zp5Ol(4XA$iD%PD@_+3zX1;Iz>l08WWmMh)X4q|U zPI*)hXT?>@3uW@Qw6Q&g$9bfbT|WU=x;z}_!O<#zF$^E@qJ-Ur>Cfr7p3<&NeCw_~}yZHe0~< z3>^9`5=s8-(@I;2$L5jg=y>PQx($yQsj2@ax%keAII*4R>6&WYW%OU%5f_=9Lp*lv zV`Hllf^H{Dr=+U{6OlA{{JwTsp9!&VXROk+rgHBqYtq}wt{^tp*mAgSnB8z!b2%%* zl`H~F#yMY1y~$Gzdf&dQ!rZ7D+j&m~f0ce?IYsWH${%cor&SlqU>E*F{9-pnolb7B zw{_}dZO8eE^6$tGna#@@KcjI zD89O{-c;jB`>Lz$(-H@jVy8OUB<9`YxqqN-|y??P>L zH2VQ$YQDSQPUG;h5-d9t@22WKU{AmD(fVdr5m5|aebavG=wx7R=Dl&Zu(}+1>bEQKePnpO zK?~I0FGJP-ytYAC8&tj)Igd^M(YTtdL@{qvf@=pbe^5s__;u$DiPIhY$L zS-nO1AxOlNm>?$lih&=aM`trs!ar4-4MN1X!fM0NX^Kj^xa}<=++^rMOp=i7zq_x2 z13p7m*LU@(6dNF1iE_ZIfR^>LaG|Gaa2SBn+s}3Oo8C#HaJ4-;sK~RM&aEf^qxX>p zCBeyF6TZ4yOwQlYb6dS~LZ*4mL;qN5>|x+dHaswZh+_q}XX~adYQ+j;9WEo3ms6Wa1uCl|#NHc}YlEIshj+Xyi8+@FBtn0H zo@>$xG}GqjmhbWMz-+^u@)|=$iLlD_8kv?{3tGqd1uf1WGs{=rRlN%`tl+MhhwWN3 zp8gCG9q4d(UgFdow$;HArPf742F8(N2N219ugCBY#qeHV3uaVNc|JNV&prRCrLS#n zwW+pk%U#_CZ#~fz5j!paI2B+r>Cd=B?>_$hB#$dyWFHdrt9{jH20bT3)GXOYqykKrH ztmJx7-iE;@QcLc;5J;sbfhK;KY+k5E#0R?(333qL%A6K{+F4L=J)X>^%w$3bh|9B- zN^ltZ6%h~?-=Y(t2bC>Xim2D|`fX9Q{E@1&o%8A|)jhg&JZWf`vlXjw2PYHSFMd9P z-5|z@M2PNP`CUEK(^`p&3(t_$OQY$FGS4r#$8oBzXU-C78Ex|?8o+mPM4ppSO?t1E4XM?$&=$Aie%)q{pYjAFvm8^C zc6Fna8PMTM3S^uQr2~Jj-o-TE4GTimw*Q#6CN^KSgqGLNVB|z{C3_0B)ZSlIj4`yJA=&u>|O>4(;oCV@-x>j|`Z&%h^lBNffHR&#| zOUwk&sDH;Gqk&lSa)(=Ke}6}gdks|gfEHCxNvut49vn-BH{+GwQ?2Q1o%D5 zXd3ESM<30bptdCT4NO~iGEXl6cZhz%=dpc_>g-mk;n70hP_uj&N{C9iIv&~7FhND) zfgMEX_!f3KFS^*Fu5NvuvmU->Q4f!638**()PCK&@6f-c7u)~A22KTI!vG`hrpp&i zY<%UBLg(RzDzQ02Y)ax z(XmlEncGYJu2AO3OSq#`Ly4uj9gHioS~?4Awf71`1-L#mo5yQ;F+bSp1uoz4Z5Y|mHzUe@FC|_}*6`}=`x6FJ37=J3ES0cBm?=|v zo~B`p5*E_CIe@77{mWs4m6^}dVfT7VSxxQ7SPvf!G<7H!AkFvv_c#RiCm10TV>_nD z!#JelwOAs}E5^Q=pt|CW&=N?WoCX=!P8d3EE={#xQ|V~n!=X)bh@5=*MR`TT@(RC4 zzvqem2h}53<)Wbq`h_)R>4)K7-y`k+2XCUth)CpJ*c(Ex!v<*eDm|LCzG~yHTw!|n zbruZnmX$-;k>AW5&5;EVp^Fy%5kF?FA>FsLt!<2_3OQdWh)8IZ5ATQH6-x%nX z>42A{LcWKUM0Wi|5kC{#R69&AR}nrfS926}z9_hMs|hj5x1wqQ?TaUJKKKY)k>vgj zWA^UL|2D~ujoKx#mvdn`}KzB%dnw6QxfuBiijz82L?JFa3gF6S|v#-gXZK!zBUf2g!;yY6O~jzSaMt+`uW)S`EH9*1*?T3}wC@E!$`Un1j(t`VW(G~c}zU5b2xWcmIqdrj)@$6{$Kq1W~7K)!-R zB6weO#S3Sk@-})75lg@y0iRrc?_QAzkvNP~gQDwso#((?wANWJ_{P5gTTK^Tk24*` zW&>yV((0tR+#wC23!eHnKk9^yw77&cz7*XgwJiH$9cNT&NidnzgwSR#w#>hJn-4)> z?M;SyO^5tqyR^?8sdo|T{!ziSRB;`dFR6x?tk4PLqwY_7Op-|kt2wB!chw9b#Ae}>$+ ztmH_1#XMaiN5VmPnRAbnnR6~|gr?VL+G)f~Hs{Gz=GUiU{=UrXQt{Vf8tr%U#R{&| zYyfpNYB3E=FO;8025vT2Nz~{C7KXF1V->qaV%>nf$1M%0DFmIeB%Q|Z4*xP`LA`!%y(hr_xbERxdbJ>3M*J4k7 zXR5y>-+HZOcb$IuklP{gib9F!T>z2w%wke+CT725xk`JG9wkBjQ6iDL#@Ew9XxhM& zWmt67+%Sf@I9UuWHlE;l`6{|S-t|uN`eX4KP1}MlfqTliJhTzQ6O%C@1&Mu@! zexqr-2%LO_S=ol&Az%bt~ODw@^SR`37? z7a8~J{w?uO*W2gnRjWgX$J1wK_c9OD=<=1;#m=|O{eeWSk&z&OaR5(hv#o6BJU%2t zR!*uWkqt!JGr78qTjFeCs9tWo->CGp4W+S3JZ5Vr_zMJ6e)>X#Msi|x8n-9LP@8-K zY9oA=5P46wS#{cMNx^g2={u+m5JZ8`6^l!O#Qe$L2Jt*=Ztt)wB)&&Kq29kX0T;X0hF_PChnu@k!VUGc;?|19Lb z!X08TJUm>RIGtZRs27#s_3)r;T{m5K{WI@c+8zcGm6lnJ$tY>FEnj|hSs`&|ywX2U zjYPuo-S13XC?3$vay~<=L0Qjq$xV$v8>jRf{s(q04QGZV^`za*tisE=W>$a8WVtVK z+b$C-TY;Lq=ang7bI%kbHNduq)N@i#sk^)@Lo7_T7}UBK;(EC zzHZ;98%6K{Kgci5tQQgTrAdJLSWI&)o@((Gi&PHG9c-n__ZszZ2sZumukoe+~ z9}wYIezoM&UZvIRR%OQbfaW_98RejlL)#xsmeHtx{1r#6?#h@bZdmx=4%|D%vyN4T zojb37ZxM5i8t(=Tb{)JC|NYMGd3_Xk`a+Y4&m?=Muo+lzuJZ8jOTEUWSEF$FjmqGUS^(z%&0JCv|7qw4oGQur03$mVNm}9$}g$QDEb#=nvAs2YvD zUuL(CKRifCg~BQ4G)u9A@d;3VY5(a+7uyZxGFQD@Q+YbK_!TI46g}-UAfyTj$2v`K zCC|(e4PfRgs@dpGKJX!nTz4J*N_lf17eECb0C%!T0;tuG#S$6R0VcfMq|A2d&90xS z8^$&b7wXv3vHcFWwsCq?8NgjR4T?2dS*lG@`A_S9v05WzPnIe&Eep2BOR2XOcGEn> zmzpv6?HlULN?x;pL<_6sq_f|!^XfA)ON~M^4fTH!-FV4vHm;Z=^k-hh`MJy?Osqh? z;mVb3Zbqx|oLXvhU{Pe>OT$9(>xS0T+h-o!lA60EXs+8|f`ztyHbqXxrIT_|%Ej81 zMdIC%W%X^0;bq6>;6Jsw9tBb5Nt#gE^W5A*A=xkF9gHRJ4lBK9U$R)NPLhk<9Xd+& ziUM+?N&}digcLs?Y3gP%2lr)<>6H{2e+xnVcy;%s70OQqeQtFT1fYyp-q8H~9adq< za#@>7S|!epUgo_8P)EB6k?4G;!Fm4@LBFt2+rjj_OTnUDuhsb==MxQM0Vap|qaoOn zTw7HusS<#A60oQ5O(nVn_tSaSEf12eno-NV zx0ZKChSS7W+`=}mmNQ(ByVRfozgM`ayqSY2ue#>4Z%J>hh;7}r z_~`RJQ~)&G`zvQx(d-9Yvf?(&XW=D^P`mNP8N8KW2d*vspS#gsGbL5{?b(G&*joU! z$DT?^e=gWqs5M+(bPsmaPvuCAjuTHSOB`xSg$MzCmKQzuFqZ-u%^zMlTntkMbF*wK zBn98F=sfM*9Q2+B8}(NZ`F6_-HGf!(XCo=P2u6B;=q5tilU-R%8&X?%7T`OZ`{x0SQ9zCZul?O3W?JM@YepV4f`c=g&hudZovF2f!W>g_LHKmNrs9yx)XQ@^x2DX{qA(Vf^ z@bwNb%2*meH+b#*B)4tR-d4kn`~!w8jY#q)pH)^RVI)G*Lg5&X$b}DFs|R~;w74Sg z`b7v4cptlpvk_{+oHlR5v~23XZ)(;Ho%^BlG5xOW zVo|hc(sho~jMlPPs~=5Pj}!wh*a_BoDg2sjcG<|$`gsP%g*)5=!??q(7<0xtx10vi zU7fG7gBs!&*eTCyX;Qs1ZpQjUKxVX+7LB3K$i1mrq9y=MVhcpi%^PDSC}by+J^;6K4ef{j9t3kJz%@PkdBrc!p7I&tj0!vV(iKN*smoP=L1?-qlxZvayG21qu|@^ zy-OES5vij7A$op%3N*^osz%~OFjy?W%YW{MUF*(IU@ zK;9VOPf303TvF{P!drUi$t6#?2j~q#D|FgLd?lzcH%5%&$sbrQE@2cXVs0~ z!8(zH_f9py@n3+FG0#NOUvtsF$Zj6^Te>o+v?$1Gc+^B0dl~EAxJ7cIE0hEfEg-t! zp1%piTQ+m6;H12gYa1!QprBhdN>irmcpYYqQhdiJ z)a9RWp&#=12a*X-?E69z#^Z^Gjg3Xk^?lARsh*UFrn-76hD@ksGjw6`Aby<^{6f#H z0+*7k(=92+kt=VulJwZQkuL6wvWY;NMp{L!to?zK?*XIF!pwh(XL)^^SP{tN1yU8G z=$Y{is}4RAnxu?qJD5VC)@!>3U2p3cZIF=d0{hywYU#yA(*YE$pj-Gxf00 zA|BjRwreGF#ar%n@vBC8I6vImPESXdfLXvoKh?e@zZbrV9^LkddwBFJU-f70r+M|o z@f*AX2GG38)M&69%;ehrcybFq?a5U*^}s2jZiWe8**|9Ha+}ou3}y~0!VKRDs%tq2 zjsi2snZlZtVZVydb7uXcqN4)sX6HK6r>RP;Z(KlR_uhqqCu>Bt4;Hc6P zQ;QMZ?Ox?)p@SNThuH=fhsWxvpKu%957C2vmRmV1H)Gy*YcGEPK##r2jtCQecv;gw z7IN*$QijcaWiMu|h9>s>{Xpr<%(9&F#>zabf=4;b!J?crP#kmNB#_XrK6+5)Zq*~# z^|_wvD*e9kc%^kuY0G^M`xyL<9(y6}!|OM&)848Yq40%fcW!j?W+5}sF&+C(qBJD&}bSyY#mp=y?NkTW~ms0g9zYGNQ*R{UA4j|R&7 zoMlTFqk{w{)L8VpduqFmPh$}Z(xNPp+ehB@X6J9n5zQgA6`1ym&LM1;CCA8Ens`&& zwd$OKHu#!T>p!;F+@hvJU-JSj1d(DF1zpQGB~GSADvvtzkqQQ!8NDng*)r^_~^ zHY2**Ri(2HUtC|A7l;T)Xq+g00FfHfc_mJB=-kV%yl8oqe?LRNpRf9!p;C6-OceUY zS=p89=b@@2awGeYUM5^o#Ci!+-C( zKo{?SuKo8soPW>b{r{i$|Ka)DJ3gpv1Z&xP+pun%gmt{=>Fu>CYFb_x@gomLG@C^% zO(*|+F0LC?zsC?wRaGM$oq5Yvo=;RycX##IZ{N-vwzzfl^z@jwiq9b4_&>(X`fpvD zscMG2K#Ik=TlTw!-E37E{#jaDl8s=T4kV@kFA5Yw7i#ouiz(3;|6@R+M&XDR`kwyQ zj@sQ}G$0G%IS|N}acp+d98>F%m79~ir9IzB(&QYM?8u@rily-LZx`;c7f31Ze!KVM z!Bn2FMf8Tl0qI*;fdZt_de&}P@XksnWFW_J_sG+~bxcAliZBN(`X>JuNLjdd<*WC$ zUN?iIdO9B6=5~ffZC6-W^QgOrN7B~4;tWP@|1nQmR>VF1?KJMO$RSPt8PR9<4|5`j zL!FJAD=2rO)EzeA-%%X+;3Yqr7%>HBDp&uv_){E&6_1)z1+AoF99n@Hxo48oEMWr1Z-0UZ! zSnnUn!F;}={$~svDnHhw;!NbvXy0JD(fph8Jbh|z@~WsAZfi>m`Fri04?osdln-so zFg1WVA1Heem+Z5t>g(H#HlL;Yz?$s8yQEMJWcrH<_|~*rr7a+Kf?I{O@qhMD!h-mZ zO|aPne*O(0oNMvRYPlJnwHHjI1Mx zEJF`MjF@D3jXjdRM;pUr9ZSOy5wa%hFd|tpV+~_}@42V%c-}w0_j$knzt10YIF7kp z*Lj`i@BE$1b6?nzkWSSQtK7n3*E!# z6Z__ClZ%XkMAVNkTHGv{YNa+eHWn8CYlga7<^lj~4m1>sv9jMd^@4?tEvoS-3hcx3 z7a(3cawZNsOB~##3|Y_3(BeNn7i4EjxemBZ71HU;0z35d?L|otAW|F?OH~j2eXV*| z_haK@;NCGSN_m(yn|`uyhhweXO39@P0MHPFZ}sCkYgr3B&+t}6PgdHhi~lM@zcTnI z3Z4%1q=F9Afj|-GJq6JBk;{Syfx6Mz!eOVGXRXb>Xcz(wxr-RcFqXebfN*@6ODCgb zRg#Q#Tna($K@1os4m0}8#JbuJBQn`9MXT=R)q3t|)T#)GVLw()`S9ZWddTK3J9t%; zI_Z9+%!+Gg1@A2bw%2#>u8ofEW{aSy#VMBNXJ6SJ-Wt9lTqYlj_rq26IKJFIN&IHd zLOlnZIROp?kuNh2O6KgmbZxfq@NhqRs|+<`Z<}1<&5Edvif_W>-;Pl(1@{H+kEkKf zH{j`;;r18R1sP^=pa7)XD+J7VqWmh0Lhi?KVO`g8QyDYWtq}f={J}*XVm}YLtRPQD$d!9Vd-{0 zAgVq5l&qo6NN?mVi%O^KmXm^Mt3@`Ro|IZO);Oxnmp(S}$s)A4T{`X?Sm z4QT)pioXP_yv*NK9-v{E6MJ%*;K|sa#oX5S!)hK*0prQG!t=CZN(MpY>!|1VM;z=x zIwF4VIGbKm)7pe3a_I{RI)v*hn0Dk#v~{uZ%E=;9JO(@oLwS`Ij#`X_1SZ}Fs4*Aq zD|nKPv)x=A3hh$y3LXSp#@}N)d-S}W-LQH{H#yqY%e68d+GpdzS~+Nxv9B2h5Fds^ zk->Wq!0JbZ=e5E7CbJ%ftRq~gv^H_6Y&wrt#>tDqBWs!rUPdZjwhj)7l=N2@CY0(+DAJqpCpR>s^HY(+!=b20gKch%`dk`QhHRdit++DxP-N0Z-|0 zh@ng^>3=cz86al3izuM_$v?&+MUN9*gQ5IYrgyO=gT<>9TqUOB^hrtIBdr4xVcOz+ z9Q|G+_qs^*$3Rkg6JcgHE_2x@SoQq0?%Um1k&`D??JWFeow0VP8j(O*mx&T5W?TXp zcuM5v8Ye6J8}2-zG2q*QQP8?I0xwBc_G~$oO3gof{kzTAWz#-|^vmyQjyl*2f%M0K z&oR*B3+6fpGFvm#2vhj}Qc`7PfPWbKF_5T! zOZizRv1#xKOq_>94kw2i!|2lpUb{H_Ey5RXb#!9Z>qWiG2hMFHt@d2}d_CIVZ|m&4IpAqN0BE9}=PU9-JOS6@B(QQ*&!AommKky)zKncT+ljj%K}2 zf1dh_=MXvN4dU^)vL)@?A|Mm2$N|9MQe}2S84--viq)dJTZ}$N%>updt2xbgI_}HYk-W^ zpyB$z(3v&t2*k+x`|kKqUaE`m>ft^(96ldxvQ4dw-|SkdLiS}g*fu{Oj*Mvr?seKH zC~#f8E?hsNVZEyIXwSkpaqNnKSZujQm<|gj9H4u+p=-WHAV*9aPObp=ZmmeJ;NY0d zqwFgDu$ZOerAuztlG3H;`!MD>e+OCTeT|ZQNTnU&GOfKYsIc7&lSpp6Vg@PzDvV=L z;ZmNGGmswS!_3UgIKvB+kttKsSOKHwM$ zPEU!Y$6w#he4atC`Pg-nXKO@H%(mqBs-D2ANy19ZxgwA&@a$j3d`4ud-amfWt|Jh* zkC(KC+I)zP;2U<&LEjt2cl4_E(ACjOqRnp>?0d9t9}He6Yd?U59AwZEuO22dQ@Gc# zUHi&xzUb$0z1;`vL5aZE7kA_>EJx$jJX$x6dMOXGCSyK*LVeuR5Lqos>?v8alhN!m z)(ts%tpCn$#>xVy`_)R%9V$R|H!-GZUDG1zk;k5F81%SINpEN(TeGwTYpP1yL<6a5 zCwP3?vtDEH{J?@`>;R&J%1Y2NYZ(;!NoWj!v@#+ySX}>ecn>PW`vwy zHTDEWeO?07>);Ne+SIuYQ6{9^o89klFduiy4pnp$T8$oE*lyh`{*#hzu;9=?@xy&e zV?K{BBk~cAr{GpagZDNM$6p%=&dgTayt0u<7|Y8Dl&J)_ZNKHv`$5K|_5hSS`kHf% zA_BxiDC{&hFvEZ!Z#N_^cAA|3V|`GDLG?e_fX@98$ueXVdILWx(U&a7vmg8eUOiR| z!G(pNXuUb6K&;M7)mWqwGvAr-?+vP}K86Eli6^WE9UflpuyOfUwa6ZPM5CJ#?fftB z`Nsz{V%7~sQ_~x6?tb$GqsZ*?OkrHu+wIVEEFcB9a2-7Si`*9<7a&dId&3J)PEBTq zwi8oQ%n?HrjgW(*G#F3DWNTjP7BYY}saA?Fj7#Z_VeV6>aU6yW_d4Tr-b zfo>7*6SKbo@CLTiYC>)6@kiwqsh;;ws0C#?`vO7zaV?en!Ryf{@0H~n>Ov~<3=e1Y ze1V%_>i4~^=|4wX=!3U@?Z4=%dxqQodA>*g+O&OzkeBKW)9b`U!%t7dzL zL8S`0Rcx<&|NF}xXfzswE#3kas~_QXdMK@FK@6BFaVhlZnW!G(bk}286((-Pv8kp; z9hMOrjy<1a{nh0Dn=?v{aNxadp}xZIxZp1NBAdQwizm$=R;Vu( z@~5P9H3(U8F#Ry?R5#g=tQbO%8-4GqsNg62`U4igZ8y>5N56>uYOa(*y`U8HQJ*us zVkb%zuarFeDRZUtL$>F;vl-Vs`hm$4&MKI(JxRf;@`LE3pAY5n)=#*8dwEqo%>S+3 z#-bhZ!N%iCP2py6YQ^CYM`_JZJuSn0TEIAefqiY~@-k%VzI&k%^WeXDqj-3%uhFE5 z^m!Y=yK)4=j9nMCwXgM~eieK^H0-$dZcUQesO3Cs&Pq6TV&-T0@STN>cZx4F7qo+= zi^l+_8)IwYPpNR8wkH?wDSd8hEh*d(Wg#=u8*yzmxpAA2pH-t5SO2kEF&5X|BFGKM zoG`>DUrGCQsr9xzvb0?-;hcOc^<@VI^hzndZWl?BSRTasteHE>TWLr~@&U3f?09uH z#g-79iYNQjUoEI^ID4b$(Ecz62G13-HSXK#_wM7%q&Q2dTs&7qcD}?UIC6Tz1g+tX{%UCQRm0Xcq zGf>a~QbF0illW5>Pz6P0KoD}s%ARy$k}nc7vW>Q>@za?pu(h=kX*h0sN2TslC>}ih zD`S|?Q9BF38ZN1nt!jcjk$QXa!&jat1x9%bF@KTk9FAYdnx~?M9jiIQ(TGwQ@&Hu@ z*s$1?Z_9+TnTmz5S!o_H6G!h*bVLu;@sWV3ma{FT+#m(X zLhc#ob~ibAnaKVK>LrWDH9MM#D&Jw)UD^6YV4pSMH#rLAswVI4vZKRsPQS*Tr$L6c zg<&8kdtIa@`vY!E`1Xu?%hNn0_-eW{BDW`!?xzgB*%u!vCzwn(A`bBF109b3m@Q0W zv>%uV2ArpJ^YU;bR~NL3TQm-oAIp{=X0C{wmASl5PI_=sp)M~#V4xGnj0REJ^)1~A z4@L^tyPNd?j9KOY5-<{|HeC4Qr?eN;yJJ(0tg~@;v=gk_69R#M+NLfqd!}Uh^=BQrwt~Uci$iIf z`x-exd4ZC)UgsN)XMpB6YBA^Lc@PDkkd!QY&x42n&#Hl;QiVS&oc+ZD2ZnOWG|`9~ z6#=ulgvD8Wk_$7Y@m|6tj-Q(IM6GpQRoohR)fs_~Q=UK#StLS5QVlqu^K5}EFY61C z$5JeB-FB_!f0i8KCb-emB-$Xmv~`+PpbfXz(weD5uUBt_AvhEk&5_(`?n)Vi)vfD^ z7LPBEhKLF-j&1EcaSk!?IP}Xm{AtD=irW(~K^G5XtJWOoMmss$-|+Jio$yIIr@FLZ zfU*48vQpHos1!)7j{;9BP#kJ4)V%*dqp(!F5!zmvy2951eBSJx#7z#(U`w&P%v<6a zt~?2()*t!&7T3{;+)(;XPU1b!8{d4AGq=$T-?Bw&vmA7p_Ch$c?>qLgvGMk<5;Z4Q zN>j4Oe@7E=A|1-I>B`Za!Y;&@hyQS1bWF;l$WBiF$S@8Bh6_l?DxTA87mef3Q?6f^ z_^uBEI~kI9d?+sx8qt^$-7{!PfA{JQ#Yr|sh6<)!USeub)(e(J3Cl3uAHIBW`<&;TWvP~R;_ zMzQ{{6azB{5_a9ymUG~3#NRCYn@ehdLcc{!Vt>?s(l;pl|114}gyjDvrEiBcNPQj? TVtppV0{j^28SB2&c6j_x{h|bX literal 0 HcmV?d00001 diff --git a/Svc/Framer/docs/img/top/framed.txt b/Svc/Framer/docs/img/top/framed.txt new file mode 100644 index 0000000000..3dabc9a9f3 --- /dev/null +++ b/Svc/Framer/docs/img/top/framed.txt @@ -0,0 +1,20 @@ +framer +framedAllocate +0 +buffMgr +bufferGetCallee +0 + +comm +deallocate +0 +buffMgr +bufferSendIn +0 + +framer +framedOut +0 +comm +send +0 diff --git a/Svc/Framer/docs/img/top/hub.json b/Svc/Framer/docs/img/top/hub.json new file mode 100644 index 0000000000..17d0fec967 --- /dev/null +++ b/Svc/Framer/docs/img/top/hub.json @@ -0,0 +1,63 @@ +{ + "columns" : [ + [ + { + "instanceName" : "hub", + "inputPorts" : [], + "outputPorts" : [ + { + "name" : "portOut", + "portNumbers" : [ + 0, + 1 + ] + } + ] + } + ], + [ + { + "instanceName" : "framer", + "inputPorts" : [ + { + "name" : "comIn", + "portNumbers" : [ + 0 + ] + } + ], + "outputPorts" : [] + } + ] + ], + "connections" : [ + [ + [ + 0, + 0, + 0, + 0 + ], + [ + 1, + 0, + 0, + 0 + ] + ], + [ + [ + 0, + 0, + 0, + 1 + ], + [ + 1, + 0, + 0, + 0 + ] + ] + ] +} diff --git a/Svc/Framer/docs/img/top/hub.png b/Svc/Framer/docs/img/top/hub.png new file mode 100644 index 0000000000000000000000000000000000000000..510126bc9d71079fc891694f566d0e28f2a34b83 GIT binary patch literal 37919 zcmeFYWmr|;);A1@N~oY)x68ZPZjc5k=?)R;Zb|9x?q_ZAf6jUD z=YBswU(UX+b?vp*UTe-V#~kq+v4cL!h`vO^MuLHXc_}U?EC&Pg6dMKxmJ;C^aK{C8 zCl&_gg}I54&_{70A;OQgRz@b~hA=Q^}*AP{lz0l6gc%`gObcsOi`p zvfg4maFaKi=(-Q{^>=TqSotR!7~6K|k*V*5YZohT$u=nn;iUOtOIl-lqs3Ji7$RYM zbnYFUJwb$D?vk>+x6_yJ740tIuuxzOh}%uvu;`vIJ%c%r<_=;;fyorKVxW=DY&|BN zh;4%*(kg7ll4un58jY#-XeHx~duhW2W2!)_oCN#1!#&@4?U<1;yu&y!^_N>DCQScp z)azqk4c_)IQ=%&?Qi^}%0xdF{;Po(34kWI_n3k<>OoVPUEIUw@)>sHle-I~$n9^}@Var~(XDsdHi^cNNXuj?7!Yo0ztA8I3LMh{ImxM2mV2|x*-5gVi zrK{xB>@g}h!KfX9Z9&pTSye@(M!Uz!_?)%W$&BQCD2^&mSlx&5PDG#xwk(>OidN8& zsh+0$sKA`z7ImgA8t6x7u>vDJ*

JFa%AnKVdTZgj|O!<g>#RluUhYt` z&<9pR~;d5y8GZ*vz{7PV#?Ip4)u_E^6SJB+HukRRq zF{NIR`@h+>7MdkE|3$LMg35|9i+qmXx17wgNRi=pkYMdIBvQ-tp_2bfC`MlZX9Y!Z zoOt(I?axHSC>~1NEg_dd2UabSb^F{`0(5*Bo(3Trb+npH%07bH`?w#DvO8ad^sA(kfKA-QBu{eS*$~DvQ4I`t~P*@~ZqN@kB@tB=6XGRV7WwB~5R+EKkBn z>;qOCHyN@A9=udo!aB3}=F-j*+~+0rEI0Qi!xwHss2w?0^?ugj*Fo3U*V`?d#JsT9 z?Jq3vtF1Vbl`fJ#?{6X(I@y{u%LP!;!e7J<`EvEcB)}l+ARpVn;u1K*MqMuv7dWW!ye zarmbQ(h}2j;jO$L32GGJ&A^oSVE;*f3>z=VC4-t7E>x5}0}D*6_L){NJ}U>zQIAqA zBAXFEj048Gdb9fjCO3?Mo~iHkaody%bDVdMzMT0hCEr+`RTVU)=jq2RMK8D8c$b7z z!kBDCYrTIS!lwkRFF_6rFGSo>v_jK=lrDxJSl&>1iO>_Xqq-sBwmAtt)5Xq+_$WB_ zfn9FC{D2^(=F3nQ(DsuQwmePs;8#!OkKxi@~gh_$ZwOFMHYAQu7DZSxqTYF z8>2Nung)m@X$#keQM*o7bqQtjwl-u0)VWE0><9_08kst@jnl zX}AL3H=bDORIyn3czH*8oP5W8D--4<7Mh4S!QL#IJjEfIQT!1XmJMtfY}}X49U7sG zp{Aiqp~^`H(p1uMYX<#r{crkzCMmNtRCcLNsF~B0OyCwX7VE3kRJv4dPG?nSRY5A_ zP4>r|^KUf*vh|BWnLj60vnzzwD`mLwvebuu+u^$txs%^gHwne(n`QM5_m9y`%$3e$ z&lKlnt>?z)vuTz}?bmAIJkeKSVh=IzKsx+z zFOSGO*jt>d^cM-wh@PoFD|})40v~h9|IB~+MIM$V1Gm`}i-u$EzV-Y;=3;>V0*hei zPN-g}5%w;9z22C@i#|{vMgjr7r;b3`LAh9sirFxD*uun=W5PDhFlSYh zsysG6cF448+_?~Cf^|ZCBDmPBD1ByQ#@ZaooYG=%X2kr7ImDvZqIBlXXgp8%gO-3p;zgf@iz*GsQgNh~?!@KnPt!(zk2Q!r&BWsp-$Q?x=W zaT6JB$GeV6S~wfHjJfvhn%N|b#}Ymvi;Rc5EbHyJK`0<~dlHbB_Nm)y+gH>5KcxRu z|JtqQnsYC@);kwDr^8RfmkXy1mywkmR2Y;_t7)`r(rb)!);u6{dhR@UT5^83vAh_) z4(VE_(-vKzUTA6_6rBk{51HqvpBtPF->#V}?N8rK-)iY^p=qW5jPnuyfPIKKf}ob_ z0IN4FwtKqM1#JbF^d%?uiP!GWw0=v34)34d!QRP&c7ksNS^c?Ru%PrK6u;Pg1wl#1 znn0C72uILH^9a`OTeP8MpVQ~=?8AqUd1JrEC}UW%$#&0XF1MuSbm*I6(cc$U{ScI8 znkm3c?jn8SgPEK#o3POFy7N~E70x-cgThYH)UnM;ErpHi@_gs>U!{R9@jA(bvS6t( zsgwkj$O|G0b`yKKnTyC}Bbj^Mco^3pCL&4Y7$q2vo`FFoYp4#P*jIi8!E0UqRUZM@>jFha6#LF7462k zNm8l2RUeiJDPk&DuU1NWcjH9F9J^6}ld4*z(cToa5ZA=slX}MNr)$S8aM9RIFK$kc z{u(Xq`<`BA*HPg;1Rt2%gV8OKIT%s=A1@^I3o_8k%^_UG3}aox5Kxh27xEI+E>i-v>|9p*6g4MBBeAS8r^vkljgRLQ6wK za}7N!$rq+tjZM8K+cTRdXl$wODKou>?eJRi`SbPWPq4PUXOr{$rH{+Hr9Tx#i^9w~ zCHT}7LKOz{_ex$*RF0EPR^#G8ipmCR_BO0!T6Rm=3hB5?9Nm5)_5^((zmi2y*)fS= zwoC0{AD?H>Ih@}-%qvaDa?IT{Z~u+FE;yLVJILvI*8J*5-}mxtuNA zpx8C(W*Rj{8`Mmjbo6&%ZAm!DT+UfB)K*?hpZ2tLF}&XD()RMy+{9m)J5;->zwa-v zd1mF<0&$(30*xLYxDQ-6qkL$3*5u0T;?8|fu{m1NY?3aXF4;2WUT}?lc!L_s?%wLtjs#ZX1u zNLm_(5;#YIfrrJ0c?z7t0tYWF&cDt@VBf<$dAJV;0~25Z1ON9K8Q>fGi2x4hJCEN_ zqWoc=16OZ=!|5yBKTki!{`%yfb6DtnFaq*I;^M%!yuPiWp(O-tWw#)&s}0;hv=&o^ zz`&rtgC4Nra-;{q_>(3IDt0Q;Qk?o$7PPtsR(giCP8QbCabUQeIDu0OLpxnUCkt~+ z2&WSd@xv3Gz&Z3b9Wmj1pYSd65VS3At?zj5y_lMgG1H zT=5Wt?d+^M>F69C9cdkzXsv9G=@>XTIOymZ=@=PlfG21m&X#t%PBfMflE*>*8AsR< zqHk+rZD(R-NeCTRSI^4cj)#~SI?=yAk8~P3nf!YuOUU140Slyq{zAt=H1Df!Xk1-s-b;M55MP9gX^P<#mdO3DcTnHZ+64`$hY@Z_X2@oZip z{(Qcn=o`<9Qwe2C;xxNcCXjiS(&6gESmRR*MgaLb2~?y z_1AlN&;LpoHHH@!SHxZC?e_e}HkRvl+HTO(2MH1kZk@$l>CiCPYm%009E~2@dQ0ok`_Z4nHZ&h7%@-*E-eTVivWM5F0fzJoHp|q zlp5`%EgKfvb26sDe^?Ya1a^GJ6f8kns#j(37F|+L;+t@1`v!@_nX2E1b55nn51oAw zwr4Rf$pao`n;p)fbf~?Ae_gGSzG)s7PtpWK%=1 z28L^WHGjiDng&!xc(QRA-Mx;CJ(*1t(}=KbWkZ$q_f&Nk(qJhunaG_HTMD&?;W?HN zS&28upLDz)+2YIO)m_H0xety#OQND=-|}n9<4S3eT!2~(cox{;qVhmWCf8EG;m%}z>51L+QqXc*@0NDmA@pn{bgk4cGqr-;J+{^|I3yX}vK{L7`u zV_WM-`QoQX{r=TN@^GwRScydxrJ%P=Nb2*+dHIfDRvkKoWnKL8?0L5JDW_*m`m)fY zx$=%{A#_&<9!nWqmavHAgU$vDC##E1DA`dsJ#-H2Lq&U!c zXckZY4z)Ys=UbXNZ-BGb%5X{yoHa#q)t+a)oa8|yZCfRk7pM=6XiNOefs;o@zIww| zDt=uhNn6thWS({e^;b*W<(e&OvJKY7V))bt${th(29Aio^-H@QxVeML>dxrbQKl~p zdJ+P#lGajqYPx0r&NPR*rNrn9G?wR&f`Uq@qo;2rnWb^L;od*vG*?QarIf)y!=^pK zbK|?BT=Kd%s15GXAqCpOt?A+7V8_Up-bq}kC9}}=7-W-V+(VtwjRYalJH;=PR&l4{ zZvF^VEm3QK9-I`a1UxmLe*bWI_Ti2=7T(Ue`e?i&xM==3qG-DOry}H7J(z?3k)4F? z2rBu4!Ahs=oc=1uCbUpv6G0qN@l8;kgQsXMU@O9uE%d<#!6IBF^E>J{Y4F{Z z`G3?tn<M`zvEw<7L1qQ`fwdveLs zqAOFlTbN^fpo0Jm5KL{YbJU8Rpu$kF!+mvHGUNf>b^&ohK>G@%_Qz8W8@$WinUVhL z9~h1%en7In%*XUI_*hatP81vx7RPc;F#dfrH7X%#E#BYu<6mjc2Z8IYJ61nn?Q9|Z zd)%+qr!ECkRmxN{%J7EQ;J1HSI0Wy)V&yj1oi$Pf0eMpQ5;Kd4c6JTWxhYZ;NNBiu z^G$a%{39u{Ut6-I2bzwPPFUG|-Ly9zEV~Zr$1+H%!tOMAH&)`0Deh_b$IVAz_Zt2I zYr^g-Sc1>_C%&3Gd?+6+m*8^UbK^^^aA8B_qssuc%MYH61*Iow;YNdVyM*Q@g5^OD ztQX(`iON>^HY7H1aV^pf`+zbCr4Ut4H*=5kR(I6tu5$u<$(VT$oA@HzEA4`gB$+tg z|6SGzB3K&pa^;t23}ARN7O-3%`~w1_x!VmE8uoc`ZiMk)6UG0B72Zx_sV!Hw>8fzX z&E>uj5DT{>?fjvHB#(QVC4>iRV7%zbtap?VLUp+t?Es5|Ko1MTE_B#Ov8H0@`8#JV zqRO6=Z^s{e61C@#JWzQ9>)Y{8SC0g`GrX_)!6%3~TmsPj=l2D!LcYW1H9QJ^GdwEx zPe=1jEONHTSj-na4qN zfh!X8)=j7qz#{n40h1r#sk;Dn2|f)*Q2$ToXY>aP%YOjk2fw&u$n^WWws!zA8gIy0 zp|<4@2-a65{d*bcVGvw4se6)j2v#JF|Fr2&iZBL6&udBO1Y>Eq-#z~nxj zAz-3MZs>>u*YUnVp-@sT0Gfx%&37I}fKTW|83JZ;%s%39U3-@^dEv-GMfR&h zr%4O4*)+|My$e(7rd56SG}i3KmiHCXgUV6?_QJ-{8Nv!6qjCh{s3GvN|L_lwO_P%N zfh#pE9ITj-MnN{KE=tPS_h@*-*d*K6vQ|)cLmdkvxGX1rY0}V3KoC(s+L_%_Ax$^& zDXQU{MB2q!i^f?+;#ZEbnRlJqcYY_8%suT>fuuQxUAdiUk>d>n8fV8g{Es%n8L*~Q zgDFgav56ESjPeypPEK*!RepnqM}tUVLdni5rmY@KN=n{KvT&2eMAiQ7U!KXD3NSzF zK}84GcLNRuJkAQHvUstJ^Oh7EO)_a$d+D^UR68Zv#(GkmTc#^FUToR&=^!~d!)^KW z=qgtN)&D;d-T)*pNx71(ZbwSz{eGd1vR!tZQlScou;~ z$eOV*_@wvyBP4(&0t_|kPRd(g-%;Tr37My7+h;=vZZ53Gn-YkV)7`WrCM@EHy*xJa zTgX6JS#s4j$xPG1CM6%Is`p1 z1M|f_+k;S=%B#p%L+Ri2v6vBr9Bc#!F= znT}r)ZhGY+imKyVexR4hzg2LGMoxEb-iZt{?1otk+8_p5-Yw0IPjmAaDwdJIqvc&J zImQ4<~=6mAePdyP;BCzQ`@fY)wB z6xEsU!@x%VHqn*Uavi`pGD-E*orjTeC=X*CUVM_$%7nw&#YV<9w9=cF-;96#v@oUUrm-jKgQ$!zJiLP4R`qWY|XbM|t_Sir?HEqfKc zR*#{~#>UI5P4xi{{z(JO!aNhB12iS@-2lqCu<)?j%g<=xjUG#Zm0ERQkG%%w82vi}hl z2T_9LnMe!2tAxjH3UiawZr%JE;R;1TG0EA6{nRZlS7EDQmtu1aQfFIDjHuk~&=02g09esAsacE7-dDXK!#sjWVUG ze0!6Jj7&g)H{q-jz8$?<5k6cu#4nmW(0%o;C3BjA;ZyV@PTiA&$v7M^SK5h|_3Hpd zDQb}65Zr}mOmGD${qFxJG?UtN^JSdYF2nAp(mHeF*H>LhvaiIoU4ylDPE(t$it?#5zOVHLX0=;r0Mja5;SC(&*Tpi1;Tb6FG@TOmz zXTrz`vY<%(om6NO4BEh^ONl$1F5I%y*bhPF=?_gZyURrS98~Ubug_`hJkT#h&7z>K zUSY6;QE*7qnMefS@b0UCv>1C7-jX$cIJQ?=KDQ%E5LImE`ohzm58Z|NQF{Hz97Dq; zy0dwyUTrDChvF3F=e-MKw?{dvTOU$eQYMZoIf;fd%f318$J59*eudMkhDarKftNCa za@U5Kz3fCZ6QZ$yq2=uf_p+Gmen+(l-Z8DSo%ai^F`ah@)WLCwbGua1Q9l(zi(WeSUe;~>x?(`M$y)2? zfCgilo|B!OoLNofvnGEsU3#>$$o<;&xc1us=;V zlXmGnGm%-Qb$5T43VKFxvsIJhHe;Du+Xs$J#I8FTZg9DgbV;#UPh<9C$}7^at*k%w zMM|HvPh)0fToD#X-X_h>m8`BF%xp5h8~N6j#X&}J*Ws9BcdPVrQAR29yK+f7H*q`* zUsJ!Cxs1U~0*q;AMKgNo4C!_AQG?}x-D%hJk=*er>4?f9)9rM$#xvfG@Wn~zEZ=^&6@qqL>$u}czdd3I5oD_n)6IAtn zX36#rtTz{xh#@=TN3nSxD36pL$I!^S&-ZKhae$pc7JIfwrx^Bow%x0Ovj<(H<)+6D z7)d<2xk#WFgN?^uf-ApG*U9cgDyl54y^mwv`onj}wyrgMlsIT=FhMfl_1pT)H(50C z{pFv1w;9BMxP`L944DBuCn4+s-1y2yxXI2V8m?5BtFnRgK3EfRvf}BpGvnqBEk_e= zTZtZ)RK*`fwOda+m>!}bYQoP$wJ_a1r3Xl%r>4C%4GyyRKho>ypGroVPu$5{-Ko(< zS#cUK0+vPyl3rAU6Cme#mW>ozy7{Z#!fOcZEXR9yi843W#Dy3-DnDAjS!S%!^*JcX zfqe8R3-|hTa8^^Q*SP#HgWO zYMA*){eG2?{WU{Ht%6Wcy1amOfaIycF#-fOiDXE_H?FfxYLvHlIy2pDEOwRGZ9m{% z6-WXZR-tEAc2P)<8U(NA@LgU>>b=&&ditSU=$AN%od#v4eJTM&xNv=azp_Sk?XjIM z?pIF)VhPAxb=tAAiVgR;Iv*KV*&gAua66$;COsa>I3M?N9`XanTg@5f*#!67sFi3% z4Af)CtM&MfXr|vO^bObTgw@JULuozkdoJw@ntt+fcU51J-rZV7Asi*X zgCW36{#p&M8kxN=f2bV zr|a5}Mxjw5;8&ZMBZl1Crw!=s!tb@Vg8puBo0cP_sh4lTde4{YLXT*Cn}yDOFO=SZ zs@isKH$IgfoY76jtfq^lPAxSvBG7b}e%A!TF1B9#COxAOSmkc{EI120a@=+^rJm}% z&e{sZMQ1AG+FO%Q^G(9`^l+1L8L4ZEl?;C^MzLqQ31$0+Qtc%MpZzauIp(~Tj(~Kz z^_6*9$K}WLF?A3C#iQsi9kUt`Lmk#eU52aR=#<{=HiEJDh7`yh&aDdl2_u3Hc!{(gkd_SKw0>~VRstC<1Qg)BLU7rO;J&!hL`Ilu z3g|G*s|5EXJ$+(6(3ut|vT0tshxARQLh{=@ zu!}Jzt<<9%ZwT%N-yw%8?N0l4=+f|4xSR`>A79eZ;eOOyrt#MI&Y}oaLU^8WSe>te z2*{33H+1xn9#5S4mZ7PwZ~42oBW!EfbuqZ1j<(Ea+bG^Xe3x9CBVQ)BnMIewj9bLQ zIylN3p^yx<5t@#1GzUWyN>`6WzB;qx_)(%s#jXst8(Sk!bBt77PFg=`4Zkz`;41== zP8tHEl?OAoUq@Pb3@S!d<6g}F5*F!g0*7_=dF#=rfXLIqRp!1TbVO-T40r*gafaC} zd+R6r1@&XO?@RBNa+e2DQs*-=Mhh){W!O@s3$}yy~ zsX({!A!q0H71#kxg`WcYzy{C*1xzO)@J*z@jCKQL>|KQn3?Yk`IQ zw}8PGMWURn-I`?8WQ-g}^BeX^aXn{omOAFmH8AQuob=$31-nU5vg{=NMJ1ttmNXq6 z^-iR2;Z|~4o*IXlrA0|NFKXYfO0RRA=A!#JucHB#8b!y&_*uW-v=KD%gS}Xq3%QQS z#nUrFF0iLc0nImuu*C|uaVL(I^}CMT=kJ>2l`Baz4yUXXN18X7!tm=SH~zx5YaM3%|ZJOPQpJT)RPo*8Gk4o1Y-x?RhK@6k!=ojF!zNd&aDq&VQzFWJvNX}v`k&$L5m896neYzG* zsghg2GLVB)ZTg|cspT~F$zy`$2%1Lajl)HRQd zNlEJ08b0lq3YA#P)#QEr3)7r+X0-hxutAlQOInM@%?3|uLnDz8wqR-ou~x~KpfWZ0 z`n((g|N4d#+$T{*dp|T-m|}_+h<{;Eo0t4Txm&c-v^RmE?_G|t<(MxkIjVs8`gIO} zgnRy({;oO7soEZgW?q(~e9VAqJn% zX5G`hs{Y8Ltx7*Bb%N1jBtxU==>u)MYx$^zD6+zH?j1R?y66Lf$FvF*1-{EV8ieA# z;RYko?5w>cWX0-l#^^{No6K6;H=dSV_B=KDn5Unv#V&o&OHCO&ex(}AyHldRTae|l zzOP^0KC$rzQ{8ZDCB)oOx7l{(iSjBx}~RzE{yqBR8HiXnE!p>^N7>Lf`y z$E^fps<2Ns^xA$6-dj}zuQBn^NKTEz3)K&^Rlv4I{-3TVst3Gc~Vi2tjzD?JJFHljLn}2l2Xrrb?X`$d4FM0?4O*626=J zs!7FlZi?x(ijb(8sj(N~{f))ND>!mKj;t(ruCK51ddhW}Y6Lk8G5n_*QN3tQS&ylM zGA##>Jl&T|TKJiis5LpM-tI}!l7^2nDBf62`e4gWuM&qc0yGc_$sVnqn_Luf)4(vY ziNC+9x(e*$?7pvnO&`LdQUj8EzW83&=-3wc!!y%6FA$XoKg=OmewH$ql8~I_5Q#(f zte!m@#UGqqXJr#tG}e_d@#B0}F~=*PMzLw0|4G@v2lRG%d`Jf^uOhgoeL2x?uRUm3 z*Vv(plG^^25D3)2xuHp2-^(j0CO(cEf=3%==F&4@CK)qe#<=b)Eh)spv6m_tlwk97 zTHiZ+ceHq~ucSi_Yuq`!DO^%)r0!E1h>s?z&$pA8MbBw_?a)*gGxRM>5#(3<@)7Tq> z=+Eg{#?dPg=*X(fIO>m9pCT7I)`v!BP|{x4fz>-7)0G1^64-$ER2!#c@axnkE{yBM^?F}%SkX{0q^x-{z9UCY^nDmgLdfp7w zW=>*puODkx|0VOk-28tjo4!xH3JOdPrDS@tdAUJX-zPz!tAmYg#Iiv{qmK2GSEqKp zD;N2L*Mm|(U873hRwI|Z!>|WGT7U2NysRr(mGiU+I#j9!#0ZIq1V)$`NvX)y%ge2} zEgJ_W)?;Gc1_gzl)~$+fVnszntsUQuUa>jME=NX|A!1>rHy$QL4BNQ!5iPsWB#c=6 z({+~t&G_5H$eneC!ZatQas2dq+4-FMD*$N&>#nV3 zFUT*6>Yu6Z`F3PW&P+!7PC{>Khvdg~(YE=_M*hZU`y78c#U_e0QGB zM0eI7WvI#I=&WGzCzRFW88y}V5YQx2e49b9YKk0Guta0iSa3-MbLo?$hhbCjb@axG%#l*$- zOr&xd^w-J^0@YMH8+K#1m)s=-^V2&3g`dH@0v5RNV&~UnEFtJEv=!j4; z;f9BY%cX^K`0mxUmB^RVTA7JqjGHE=Db^LucQ$Z{6+ggSJQiC}YuNyMeclmV{E(N2 zfvb6^V}exdZTGWE4GRlb&QW{itwdQH>+LDV_}o-cY{5?|shet_exOoANC?kZQL!?! za9zTEw6d%=_0A5$Fi*uDUjJ)wys9U0+NfBH$GNnj;%|e4&If>DCGRa|pp8yIE<>Vq zHiYI>n$~<8qze*2&Pc=Di2M-;xZ%c7YUo;T1pZKI-{U!NU9M->R+8=r<*pxBw3P9v z5w5ujC2Lr&Snas6Ha=Dv{{Ueerkg(SKT_z{0F6CTg);``24i(tomF~ZQYGEAw4>Ss zlitY<%1;4Pm?Ij%L$!!8iZQ({7k4c&FO%5<>(4nV8P)RKbxMPrR3R7W#mDtd-|#4xoZ`Dh<})4m4DyVFwjUt$c*52 zs=g4hUI`;*>EQupoV*^6~Mhv2k*OlqNEei%;-lXi10~0uAPE6u^%?8NM%IAxy7M&cv6i>LW}l_;5HU zCMj-T#vAJ8FQn%!PC>g%Py=NH<6kDTcBkL2YKtj3IQX7i4b1IeVaNHbn`SpT9t_|d zB0j1<;b&mU z@`U-aXR?KC&|~kZxVU(z9WEm`>t0*lpoZ0iUF&P}jPMI9I2b6G;Gtb8fADbB9)*U8 zUq^WEUH>Fbdzz|nE?FmwsDALtxE9QFsQO=%MWjZP+#lbc#g`l1UIkLaL8w|0!$p7Q zU9Zl`$G^t5^84xfxP?f7&Hl) zZ(fw+$NK>L6DdyE@|FK?i|<}kTv{@EVElpT9LWAWVs zTi_7^x(Trml7IyRLX#n`^R-mlluj#jgP8tU)Ka8yG34A)a{ZFzSos(mAOdK`LHdHU zYUOcpPRS^;efNnMkEGEdDKeuB@p98^86k9$<@?Dq;6eT=s69x|$R>HT2MBO7;Kr|l zB)zy^Ww2=2gLrAKgMYEtduqxkpiJ9xUGJ*0$HvV|%jbOWixfJl`*%00?Lk5CUs-`2t;F zpREAN#IXJ65}MZHhH8Q_HTY3>eF>oi`1lXiMj)C2(zXE9k7-x_bqT1k6L9C*pvusj zN3jur67c*bz!lI0z=CFIz~1$*OMoK>(9KCJ`}*#2bG+f0z=WH?GE85%5XWpT9MYNPxTaVMrFxzALErLw%pYK+CFDE(gjXrBaMq(l?aw z`{i4Uc_<|EUS@T&AfFEo0%`pP->5*Wu(Lu6k=BLH&m4r-(C8B@UZIKl>t&`T$DvXuZP##XiBtQ%2M^>+5BbveBrr#u-S8JA7k4dm%B|nx9SDF0O0zrTv$%q)$o1)EJ3S7O2^A zpp)k{wmW>MC6Fe8gHu&aJTmsY5q$%~S@#tI;YN>+0_AY6n$z$?Yqj0Q+a?~{qpsH+ zj!U&~rjtBzueThthzC+2;^<0ok?(;1M@(M!TV`eF^gs5sXJeaC&3c9I7FU;yUI|V)fYD*)>(4Y$d5u zR50^sKd4I?q+sGj?yb4hxvYGZ3V9(3#K7(C?E_yTDGj7$WxFepeDDW-4KQNGe^oyx zt;iSFTUPjfV)Kf1Y?4ItWfkK$ZzCC1zm?)|XO}8>m{qap*fiwJ9V58ERU_%5vB}(X z%OrobTPD^;Mh^>j^&4`OH@}y>8t=b2t9!PIgYCGy9)7p5mw*sjlhp=vKD1)M)gXmB zynrwzRWRh$3crbpwyIrsZ|s^K$xlo)sdG8ZY&;9rW>;PY4Ym+Aobly5W696OJ#q2b z9V^Q^8nE&p2@>x<8f>|Dr+7~rr(&;BGUh$x!t6 zQErlo4b=Oy9yQ*#%Brli!wNYaPa&%Jvog1if=RW0dUisd5*Q+fN z^(CR@oZOT0^23K?-*&7zkJa*`%A{T7g=sdL!*>eSJhW8E*Jn&WLC;*lXs>Z+yy<~A18PmVE7rXoRUWO$SAEF(X@V5Q#RIA{8iFp7&6@M@H6CD~E#ww9aZ_ zZW@(-dy>93e+-2MpG)EQNSUV(ccz)PE&HNpqoNEEb1aJrV}I_qkQ?(}3Xd=`tzO@s zdD?p~=Vc5tjf@Pvw`xAg9MfnfT^%1k@+}};zo~soUYQsh- z+DUF`u6OjRqKrW70#>mdNH*GwO_W+p*tsMbvbX@;r9LHYf1&C4^z54cXs*qOTn)@A-;!{#DcZG+H5%CAy%6r7&`nWntaQ z5kI7-j27DPt0@PLDJh;Db1PSVZx+lq3L18s*48higZJ1-+Cmh*IO+ZzhCro~+M zruA3t#}WZDR$8%C$;@_~s#MZ!=dZexjknfkL+0-=OuQ0yw_GX(8I~#O?~XPUu_n6b zX&^NFYv;E&mviGX7bp1n)y)ETcLDc5uj7oNMvE6zn>@6^ldowUH7<}|Jn%CnM5>AP z62HUku+QZ3pqMQur|c7wV&jdwJ#)u4i}l^e?+HqR=G(ZGiwpf??^NoA%R2%|lMjBD z<=iDbm+SR&+d6Ntr6UU8cSTAUeo;sX9=ASwkA}g5tv5na%yVm7Cr*NY^?bcPIzE!j zO!7E~om}XR9?R3<%;br;gjtjlS|)oD^=FneMyz|)gWY1WqAarM`4w+|b8Q++$~9Ev818N^4X z#<$zP1y?YUDh{G$xhEcMI6w1WG1m;XJKMCPffuEdc__&}wg@0nJpgb2)*PXI$r?^r zP~}$%Z-1Yc4)(Rg@5x?GlTv;_E=<^n*Zx$@Q6OgoA^Ya~9q7;7wEX5sJQuPic0xFXkOJ&)srF8jy=NmkMYuL!x3(m2E%+!~b3KuMg`s?u~V zu&!pV7@x&~#&nvHobEJV^@B>sWsu|kH*SP-I6m|bOsZARc?!F;>+NmF1dRpW8xiI% zCs>ob`@Tb0zh@>$<6kvXQK)j1Ti)vfJe;84L)NP!>8CMiGfE-5U%2QRW!vStZ=||) z$?@yZ9DiCeU0GJTj~(%3JsI7OgO5qI`WvBYV*KK47#&_|WV0?L=%O>oYp7NSK?T6@ z)F7`MgiwcXV6?a>=5Re1nG#;xS^E=tjHMAA$kxVd=ld#U!>=vcluD(MrJnn)Z#+qq z%g*2Pq~h6L0M2(~&T+24+UowW#X&J&zw#wj8GJJE2Z8Jsv@f=X>N)c%eG-#x24uAZ zT2@jKOl*Ius%0)O1dHoYI&;K+{VGO#C#RZ_m6;J#%e1G4R@x%pmoZh~J%4$nM9!|J zxG~a5eK}3SmAYLfNhO@DKCBVJu*F`PoJ=N@G{v5Cjc$<3fw8nRHRz$VFif?dT9>(t z37J_C2j4UqpGj)DeAA*6O^w({N!+SDLFyt=v%hf@DoiO>EVD@i*T2yp;CO&^(1h?u zY?^6k@}9+u$*Luj1C_2J`z&sTo}_fB?yLyO&eJs*$-zA;*Ezq3bw9$phedBZfhJyW zZd1R6xWbPNXn5SpCRg+O2{iCpS_|g*;lx``WzvRIV~x+s7c0|tRmt+&3T7zUvcity zMw3~qFL;Xrm*ITSge1>ZJcU^5wH}AG9NzJ8h@H-d34tC+hubDM-^4C zNk^1Gd6ts-?Ch+&43y`_joknZ;V)wN%aJ~z@YU{*q6IgWFVUN*{@&_QUat{(uJWVY zRW;20B%|^As5i+{Pj13|im>H$uz9zwVx1tXra_YTa)X59pkv#zDk##7%~I`;TT08I zZSyO#jN!K6{_cxE{u1jlDIcFNE863Qf!QIpf+=qc4ibv@e$HnA;@78WPkGjrrT)#( z-6W&k%*j5W{z-DfwWf;gm-^?*7-p3p1ie8=VVVW;lG3|!*#m7>+|`m#r9ijB^$LN^ zKZXS}A&QvHHbV_|`7l%CrEKJipZk<24Vsa{eX{hA*19FPT*ltNw&$M*#AdGoW$RGx z?LLNdbKK$9cw+j{<=A<6|XiILhX(>%FE zW7SP)4h+W2^|#>-`eB6^#)8Y^`ULfQG#rMU3@QzuAT(>78N-65IF`{_!(oc0&Tovz z6jkbV3(aQqKKB_~ADwD*90CQrPrb$YhriEBnbjJ)hMkx;112zfU1-kqh=wP*u2zRu zq!txmXa-^pDoei61pfk?wCf1(##$*GjAHdPLXF4EX1K(3cve`Iz#u5IxtPHGU1p zz@OTIZ>mm%Ju`m2ovY~b+K7g#Jo`4- zO%=Jr4#o8S6q27zcp;>!p}`ojNf!hpa_bNie)b7E=`*iD&Q!HUw}muS&&=zN_u|f$ z9CrUtdv6&Qb=Sp>DuR>Iv}mIgp_m)4MQ6s0z<>l zDc#+0{xf(#kI%Wz`TTx)KQI??&HVS;tJiO>y{FVB1XeLR_2Cnh_t4?Vw+q+evLvH! z!?*g^Z&!cv%t{&`{&~<751~K&Z6IDZb+%s>xu5<(eDe*mc2#IK6G1}=a?60J%h^oD zm$}o1M?)tXl6sDQ$>GkQqm10Rn)ZWynFm)l98 zog5q~O$c{Zw%&pdZa``UU8v>eq}qi!b`2tAJCrn0 zBfRwEtS+NYAiX6QO`kw#v5T`dGOABo35?V6^ICFDEyia7pWaGMvtpG8ysGF3vKWl# z=KYM%_=}_1{7cS@TG75fW+nP%YCUVXok3achT=QtZ>e;>pDpMQ*k%Kl7Kf0H)lKsY zSTv}n-b_=|$HkE^T)jL%`+=}@<>e{YNFPX^z}op5)Kl~{;am}AQ%g+xI@@Io(d|M* z`p@RxCp!!8scdcw)5&~IYWb8b@6SYa2DVdAQtuDm4~Hu>ky||3 z-YS^7h~Nz1_ig%ItSso&>;!6L!cP=95>Cu4Ei6+LC>?)yVHEJfvT$HL%yTG4!9%i& zvwp|T-b;k@*;KRfROQHKc0_Q**GVF>t{KZ?%Bg{MqS8!G4a_ul`o0Ie{u6e3a5sKDYS4>+G( z=2W;#-JQ3(b2KPx)z8RZrIQq*q3S*3uN0M%$Tf76RAT*-@G2zepkci$1dRj_?>aCE zTn33Q^xXP|qxmEWBxjNtD79+)f`HF{_8oaZp1AWk>=~H7a^60Bt?Fcucl#br_JvAho*_whJpasj@1y8Nk=wjSJ zTqi?W|8UAw=?*S)DOtl`92p5ZPT)sWL#p*R?@-5wGXL~%?!)_$|2+EBM+QMb-Kc20 zNZZ5Yq5!>&1rX@f4{SQmVZQGTL(*gA!6B@a5fKsXZEfK{!%>+~1BB~D0>tK+AZ2X{ zqBZWo+{HKe#Cee;_p@es> z`zzGr1-E57?1sN6H>c7a{f?LjM=|oK*qAT!wH!arp2{QcGKePB+nXPnudduufC({- zfqXMz!b$3VoS;UJoeUwOu@-{z;m2$sYsZA|@v9m&w#lcR+UeT^`>%<*Ar4)N!a?4? z1biyL7Y`D85(0WGRWZ%ZaiCW>XE42W2b~DSG6RV~C=f|6KM;iLU58$v&jb;K=M2Q= z{u<;{$s_~k4NCnp!a-R)ahUsMk*ssdYpC~VNBozuTTY-*L8jvzaIuuOWhajzOA?*$ zn-@~1@#I#eJMkas}WY3ngxPiM**~&aV<{bkbk-59+x>Rd@9!e)U?$ zW{qj|)MqfvYQ1j_`3k_kU%;9P4CLe~a1ToE%~{Tz6;S*zGJ3CU95j;G^^*%}GdLj1 zjLXA+Jm>)w1rEtNH~i-x7zdan640 z1`|3V@}y%l6@j_Lg)E#@1=b?av75Y};8?`_{2{qO>M zcO7RC#7X?Z`wq1nF0TGk1x%IAx~&pFNvmYxjb^Hyl(isBcjI9`xs%nv!Ge6tkb%kh z^Yw&jBO)>y-Ukvp58j1$TYB^Mf$jo1KZza^brN1oj zu=XkN5NftQx3zaoCk^NpIBXj^QI79-{Q5P{O2%J^om6vei|2fT*6Cncc(NLO_$!p; zABOMmq)ADhJgIyiOc1i5Q}JPunaEXnz=Re5pvP`)#^aT>PXddKbR*nC#s}dK=WQO{(G%EqjBr8S$bh z6ENXOE6WOQ{s>kbu_n*x0#>_YO76(aEPUX=0KA~b9VfkadsZ9`ECm3kD@{uxZmk22 z2gV3LZA-;&BFSU*0$S2`X7zy?_d123tTH_14k zt7m&qBb5ZfNar^-o#&5>u`D{~ofB1d!W6B9wd_W+jv1zJhjp>+mN4<)qg3X%=# zUuSka63jw0Lcxi@6Up;{yGxpidWNTZSDe(f*2g!oD@LB&ylA@NeXiy?vl7C`%*rZ1 zWc4V)j)Q+CS&=9AgS#H=8NA>T1CK0!+(KJKhzJ#BimHHVxr-G8<>n%1Z%?T|WLd<` zokh7t@Bv8__N<1>3-zA{vd|NKu@(@LEg>q3>mdhZgh|&Zsl@V_FbHG^bAGr|E_g3! ze z0>y76g;C7p2E=3bn8IxF;yfzj_=DYcuBGSkxS+>2{l(XFqKlNN%i_ZPd_59F(aVG@ zr+=U5(#hSrOX zU_ckb!b2$vL=4J&%1MtqX@~PNUdf&Fr3^f?q1@AAn+zu=YDXOMz4DezG9!zZmz>vo zf$ZvamKCfv4P7u39vIYnZw?m{B{0)CL?rb*Eo3x_CV02NQNbT$H@@&p##t%i z_JPgdYG_|!YUJv>p=Yh*Wlm%SPxRdr^~{n#2o{={bj0p*C`0w>+MLL!pH!Arl0BsC zH66Gw%xuROKfX=Khb{7u+kn-zY`lN`K@o~a=%sUGW-oSYpmPq$*EC$Grn>T>Qp<47 z5q2pS9tIewxLA12j0pH=9zm5@XDuaG+sEj=!u)8_#_>(QE&H#y@quTE$zEQ$;!3Nd zIgz?Kf@?t6@p@Y_qZ!`tl$bL^cD_SGzDWj5Dk(SNV>)AIE%}rE5rWEuOh+mEu3O;A zXXi;zlQE``8QiEm#)WdDld>2sji-0Y%PW;4=ug_b8+}%_JT^FuKAO>XdlK~;781Fg ziX^;~)d)tTpbad<1D4RJzFrR^`m#@#Zn*ZI-{5+A79l%tvIc{6BUkb6=s zF=_rs+sOeW50$~Y;8#Jix~^#+l}DCe=TZk$CEFQVp*+3c{sBn`tQuxw10@nZ)|>*)y0Hne6b$Tt%ssw~n>C+L{#MX&IQUKVg5`ZwePoI& z>UaA`VspJn`vAjvpm|jAMX}I;m65*y+?yQBDx#OvxlNgKTwwc67yy!^Iiyp{cZ;GpSmTb3umz)iJU06_zl`h2?eDUj!tM#adfcT@N%-*hkuj6`B z@%7bL2zHCmDNFVwWe2PVY$?kyO>I-j*CDoQizdp}Q5BZOt#OkK0yoVCt!jB*3gODm z>zh`)6eKxjQM_x7W$ii!E@guGCYtu<3$t0hiUS75h+thG#>emf>X$1f&}QXN+;vdg z?bPM7;H)vhGWEUm+dJ5QVGkGEL--m?wEX<_p5)#pC=hV!ab@47GSxxPgr112z?t-3 z>Rsw~wdfzD*sVKltyh0JSRorp3&MF6JBYazVh zQV8S(Md1jlyfPVsP#Vyo34krTgKEF_dHl$2gJ797`BcLzU4F^w6^-n0k5+*>LiUA# z@!(qIyO4!9(w+B@SvwDHmi9+#$q~6SMo>)$E@Vd(T)eh}cC&Jh;#mb(u zutkBguUFm>;$Z{KB;Q^mrAy5si+1(=Nx5bYeV_aQ&@vkr?6!K8NL4O3k zyA32@-rZaRw!c)NFw5##JcPVyF%}!}xvzf5MQsduH6TEU9$3K41^{EJ41lUV*$Ewx z(fMLxSQKJk9xG<*(wC^N$3SkK{L$zsN{sYy)S5>acjkGj5LUK@@17ongY;U#o3)n$ zukr}Iw;`$9A78o34b@~krULL31dZLd1p}_Vksr?pKUR?}P;uW>&63gYBom~FE6Pa2 zPe!ijCHLqXFX&gCuLaelpx#N_n8FBR@E_(u`ldx2`BC^GZ_Xe^fp%D#O0tRx72aIT zb;^X}Uo7e5JJdgANEN{B4y*X{(xCDa|u_=WOfL9vs29?!9vVW#e@nVCv>tiu%nMzhEXu=o}M|nDXvJ*4hB>EEX9x zJvA;E&T-TiUkh%Rfy|jN(bQ1kVk}b&?P?d7H!GP6LPE7);7wDo7q}HnlI}alQke#X z(F39hnyT!}f(W06n>DNH3#4L42V)#OEBiXIS6~ZNO4N?i2*SQ8rjUaeuhf{7nkWGF z!oG+j)|JJBgRXU0ROOtA;c+hG$$k|?5FYS(9#YYA;j5dI@w-(M7L@~$tNT16u6~ka z+V_OTVkNP%%q8enu7p)+uvho`XzpcXOPhZ=>Pvd&7=mHFd^Wk02GZ^>__BX#M*!+9 zmMCHMYT^@l_C(*qRQ)2ipHsy%<1_;>E5;=lLz43=Lsg1-52D?JDwNNZ znbpxj^cc!YoOJ&wk&`m4C+{Jd#?|PR@%8Jz1mTzBz#WX2m);f}%h#?w5kP}3>l3=R zW+UEH+w{L?8wGy7j&9gI?aZ~P2m|#EQ$M_U|CAe_1l!>*b35G){GBLVHr^K>7Jst@ z(g!^Cr=`Su_q5~=j@IwzLywcPb8-$L8%XbmLyZ)>;_*t#-5U1NLrw)7hXh%*t_2$n zi(bk~Zo5CrK}3BGmzH#TQwA#yo9 zG!*CbsUqaKUQbwP@GgPq{yRm+^k<+#TaNU&A%53GVyLg7fPjGb{;mpL=VF<>EYm0l zc@bp7dUH*!-?@u(bg}+18NuYD(E^>yBwX#Z7x_LLBAz=iZ?sa2L@KSU+p71Da>pV$ zQ+XQ)JYr8&g=&ijlbV1xAb5cJ7|Swo0F0^xy$ zHi)`^b~Xw)%D>k}r_j-HFlF`i!fWbKJl5OvWnRFo+qaie&!c_QRBZ|ZTYvJoTXvqF zW~d!{j=F}n1TfB&pbQN}MOR9iC~OcckEzZN#V@nQr$T+k^rX3|mzLE+&l_SYH{BUi zG+C28tsjBcr^vkxXje8jG}qL_#8!m>M|NOU!eLcf?}37y15K&r;4%8rS?i%W^~4@86{jyIZ2! zB6Pc3#9ZB6p))2wpxm{SAseOj^%*hyLJB$khD!<6lQWaNX6?EOe)=|hJ-HWio9Aq+ z22(SFbw=4Z-n*VXlzRv17r@#QJveyOZ!d__fIomau>jdAPzwbIo}}qR3Q5yEe7P0v z=6%)sluM|Y(ns*c*{>h(AZF^l8$?ILo>dx4XHbxnS5`HqTXHRkM*Y$_*BZ895jWdt zI-R-*?UvUZnJ{GGF1%B61GQODPZW)Rj6c;L%&gmAXBLG*9 zIcJIzkbvU8-2ufVI(%uw9#>UHc{;kdJPVSQTX$5=#FcX~c2GrfBlQdn`e*yfkd-wV zWMf8C!>aAyS{8}#7V+L_iit}rtzf~UR#18x04(%injYBGWd#n4HLhK>+StMXT50|znWE3dS_^5 zG?6IMaBsmVY%D;>NB={nScOq>40d>yGVsHCUlLGmlC8*Vl9|4v0a0kF;tix$=E`L$2|hRq4c`Iw4W2UOwD*|qWd>}-pAvdoDL9^1h? z4=lM{SuMHvX7GS*`1$!_<58dYlgD5Kt4O5X2BfAy6P{K&@Q&%?9-c07>rfRx{BYI- zEP8T=cruja*rWBn>tS@4rS)qqw~dKIC@(9QgIPf%Kv13_X1^F~JY$mRSxT)+W5%eV zE4xIG&Zs43JKH(Ujx^NX>k9Cdy*$#D<>g+jQub=-9un-f*Bh>Kue8OG0EWdWiz+z= zNZH2!|Kd16YOeJ4fYv@)CiF($`(lrdjk&mcDWVKL2f;G6V}XiwNbU`%(+zJWWu*>e z!x9uk&gE`aP=qE^{QsX!l5#qgemDC3wq!fQRXaPf*oZ=_^@CH_;lz80k2t_0+{Pkb zLKnL|LhEns9TwyvUX+(dx?Ik@BPWlqpbB;mZ7gXH^=-t*B@SN^Kbzdl&n%Z#QbJxl z)Crd_tE|j=&#ky8elc6i{p^R(BA@k52wG_$Y~2U;vN*j(juyx@EZ)1%f6OL&J}pw@ zIM0Z@IeRW8Rxr?7_KnycJEKvf?-C2bvbxLS zS`qWQR_q&w+euB>fwudbzWbXO;SoAxFsY&o4t*l|=<@Wlj+q3Xt*>@u$Bjd2I5jNj zWt&3*JuqVaaf%@UPeks4`OJ@<@c_ovnME&-r}p!G_$+aY_mWcal(X{kcySUF6G8v< zY{EiwR8j^?nS$(Q;GyQYIiA$gPolwS_L_`enj^1u@>?`t{F+VuZTWMyR%+v3)4ejm z`m_|7u}d6#8$RnVp@gm9ycGB%Qm?z^Nsh{Ldkf*p%8JIozL*aPj!Voo4}JXl@knA! zWRlM#|E?}&LaL^`rv1aF95I>=x;^fw=gSSJPZD(}A6VWxiT6K2I}$N6z*ky*SLFii z;F|vliGwqOWe#6y!ozsieB|4m>vSH=3l@sSx|>~}>Nw1v?DzV`l%-=!@hjHmXaSa~=#ENc8=a_pOtYN@A_;UL_P=Q|U@o z_(^7zT=`SOq3PB@{c9|q57bn2eVp1ntKl~A{L0Efzzduci}!^mRae}ZEYuyT*%reo zj9(Eyr?}KNIzLHTSzjGnY*{(ndk0$}rl<~5LfLb(3!+&rkx57b;)fEdi(}XjLU_-% z#fsu_ZAs~e4(&4^p9V=2SHn`+i}|}Ro5(*p@#XpvlJOcmg`=AGLiS(Z*ZvBn=td$} z<-{+7k-uuXM8b%AHnfdAHGL21FQrqSy5?WEF0bb3gxjyYJuTN830q&sN`_&CEkOoo zV1ZvJH--b$;N~KY)o-mShT$z<>7|@!F{ATpj)YV>G5X$S4MKK!f;3o~cb{4o+--7P z=R@Eaoj^Uwf@NLLTa_jdp4|tg2UD;85o`Ga)b~YHe}Rv8 zMz>w`+!nQ5OsywRPg~<*UsSI&KjE4rlhFxA*aG{CwJ1SVAUZR=%sPAOV)w z^L@;f)uA`A<#MoT8?`^WiW=y}!nYTCI*1BI5 zcBKku_V&KjGny(H{KDokr4?hSXBY=2`dqY)JzAta2lqJ?KB=5Ka!nC(&fexY3Zq8g z7(N}3H)QmBPND>z{kyvgcvo^=a!$kna}TAypnAH0lvePK;*|R-_~0m8e`~n67h=z^ zJiX)-99{i6^y4#m;sx!7505?*DDxhxfD=VAb^!%QD*UOH*@+>kk)ln{UX}s`41FY& zN|?Dxh6rug%`cdYbC7Gay^aaD=V%0F>Wf&5wo$e(p7NT}Qj}z6$uu;GLI)QX>!9;d zz*!5Ftb0GXCjy?@blTYW=~igNfaB>#<&yWgckRwf0e{#D@9NUF>B`2k78qQYn3Qw~ z{gs%yh$d3pw11?Y-{i$aqVAqnLKlvMe`%t?O&qiWlMI(%lbrj!{PYewx?l5OBy<-C zE$oEoPS=#yX2%fubCMhM9mP~^KMeZpyWd{F3hj%ron!#(3P-E8FPJJ8adWILn3{!I z7kVNGU8@Oxb-*w+`^ zUyi!D&h)YD>#(m!cqWP3Z;tFjf__e%Dp3^wtTv_60j_LEWr9dihjgE`xb!VJ;TRLe0H`6Zig0>M=71VC8 zXr0{GeZ7(M<=wpa!X-)VRudjmQSyFrj?wR*cgcC6aJwc;a~J7s19+<}&27V%Iy{YR z{#8}{DWcwLQ_$5_Y9R*+s?`^syF;|+J11;HH;)m(2;%uRF_~e) z*zPgUyvzJ|nll8>0c%D+c++#iD5z)qw#!i zE_Ud;&i3vdF8Veai~g8MJwI^hhNYl3x^*w!pWh3;()n7n&Ud`d?78v}F$DFO=i&o9 zKY&X~o(4#y;8l$FENyQ;YA|tr^jXYR&D*=7)`nAls@5At^O#nJnNnGg&2HpKrhw&P0}AwfF_T=(#JRI1~MsqH~o2VE{u468hQqtPqTB~+lx(q zu8(!~?p7dD+m2TeNg-=%grL1OTxXw zeINlQ9g5yAyG<*UYYECeC1&0GDu-(D7We@ej~?OuMt4m%qszpbx5H7j?Bnzp`mP%h zJVR-LoX@>Iy;MK$+yMdKMi$D5&f6bsxd2+7Q|B!ado`bNB@__@pcq=_xxb&|m$X=%lLNMIIOYTI%?DIdZw+*Yi5+d#Zipuv^T_)0 zgVPiSheopI;0@{J_Kn=tTeoP?kq02ti(^_gt5#rv} zJ9zItu=M&!vUw`g3r zb2hpp+Yb+mtN(e$BkTY!60lMK?^E&J1SVcl zYVgPJ3X|;`3Zawy=6g5&yYWFmQq*ElDT>L9;*&sPpA7@UD{+!2`X99>Zd|TiT6xTV zCP3)7kO07gYzGXD{$P`^1A2N@o&*L3x-8EM8q_)%-Z($kGc*|F6|YUlB_);5>bn(x zprZaViUQANZ*O@kt6-93<#m$H0MWU{m32ILj|J9R&Ip%vl+LD~s4xDpAS*)!EYsf6 za<$A+A>iXJMBV3!uTy*ri=^GrifeSZC z4V-yu+$!3%JUV(zRq1juNWAacx2VSlWA=xU8vNMQFVcQNA63268?^DCTl%ys zy?skSjVzDw%37*=6m&S%i7WP|i;+KTri*yi1AbaVu)_xj77Q_*_NM@}%XrCmS$li@gw>FaU-4$fe>E+E9Ob5rmF*Jn?L1g;s=)yYhrJC8dMew=7rJcA)%K z;O@zYjmdRy&y5n)`i84^wUnJ*EYEF}9LAGQ6XO4N7BnxaHW9j`%}S@vdS`5M%G>Uz z`iuF#hrDKIQWU)XLHN`i*uTs%&Wl<)O{e5o(H3T~`6^xE>&4^lvGT*VMcde_4D%(`+ zC!Fc~_mGykTA<(((15zy8MJU*R@K#3E<*6Ul$*1GE85kAZ2c*#pDQZZj2)EYd>n(@ z%}{!#5?y&Bar~N89D;*#zf-CfBw|T)teagJ9tx8}`dTRh2$}sYa|{BLTie`aZTm?> z@0YvOh|3Tm)r3(Wj;DKf6#;zAjo5za>!fq5H>w-5EkY0_BSG`eNcC12c zO!*XK;mN}~BO=1O%~2;#!Y%yQio$S&dB>S;{H$z;iAjMnr_w;D`clwUy-mIpQver&H8C~ASU!- zUL+8JbL?RG<%(HwMZTE`_C}PFY4w#%k({{GgzlGLh2|ny`kP*PBed%OwwHQwW-#IVPr6wFdu@k1Tk`l8}ChL z-p4Ic%m*sqnum%((|)uw5z<6U<~coB9T^|Db$(>nqdi%Zoyl(|l=90G3e^%nnu)A0 z`DhsCf2OBub>%4mq|6$4ux93hEat(LpV5tin1c z)vfJ%!6Mmuhx1~CcN}&f9UShj6v2I!ER<6;QrF>N_ymx#twbkP-&0|x;xI_bp60=Ip&r9uCFI&i)gkJ`Kc-n}dAFA7Tr z{6Z*N*=8dh$L^Pg0i3HrJ13y%d5TWiF?D>lW?R|lmLcuA(`WEj3$n$1`I|?InCmyG z*0*|KFe=6KaNohC9lXV2DxGsxGG2)}Hx6)il|W+{BV#3;o#Xl;a_x%RnnIIC)&8=9 zoduwLto}#Q+7uDjGCg^Ek8)|Vzcf?M<)HIn%F{QB>$K~MiJ!O0JwGKRYJsRtbN9r; z1!=EL7ZApDD1cY^I6mpZm`d)G>jGv%(egGY7w<&D#JmE!rV;`I+L_>ctU`y)P}iFR z4n?SiO-p;!`+XA;pqGKJlxNZzWK16+JG++WfRN&7r7M^e6!XV9pvCR4hX=sTQYoI8 zps%5sW-LmXnREv^nOeBweGVZQGXBya+FZET_q9dfOiDIUcJ2Bl2;iX2kSIe!XV7Nh_^^% zjc(s%#+Gq~C{?+zb5OnXhVBqKA?4WESmEOAb?@VS-sQ8AC)T9^F0uV?L$~>;_h+hm z1Lcii>8z{d0L>OJHUNyRV@;R92!5XYxgPryanT$zkl}^`YJPubq$0|OFhp@GuVV){ ztB1$zK2W|Fv3eiR;_y1SyuC1JKKjZFw|N7Zq+wmpzG?g?X-A8onHaDFA4{BeOw?9= z>F*BA?3Eu=?IOHnHr074ct^*>tZ2j5Ywmzp}j0(0Z&`-}rdp23E;K$DA{^X0u_OznO}t3(U1Q%>bh zB8(rf1~M$2Q8cZr^CGiS&rokm3(EVGJh$8DLxpTY>uZ1@CB|7}n-!5E_qLSG9e^%7jjXu#uBd<8IL_=)Z$P|rHsU~GK_u=O}0pnH?J zw)ouBGf7rX)@5z!4p{P}gnRFC+QtS?WpyRzCwXgYs1`9BYeU+jkBXybp;Ys`$LHfw z&i^$!lC2b=WwV+14hti@7_eVjsYVPS_TQoR@hdAVjnj;ns;n!(f>8G*zmwCG!LhM9 z?xQH=d_`GVKH?b1etv0xzl5=BSV1WIn6Y}M{9msP&^!NzUc*|&AEVksn3GJ#Mig!=E>h%kZ$Eyg+@#R%>;Y zMsJsHRnGv78XXPHC`}-WLUTvwd6{TW2NKEhT=3k&i%K>AT{;g=>uk%fo7KR)Z zya5hNTL?tW(2OUeM9jgshvv4Z%d}sh?G&;)p_{^X$r<1<^Lpc6SP0O*2Ks;TgtUK0 zFT65<(;vX8wdfAP^*gzmJ;Rejvp8Y#k+vG{7+^NM%(FKzT-fJPEl4XJgg$vwT}?d|Cxt{p7uz50 zyH)`>!!hBY?E!?c0$egb{q>IhHaP`HMA)so^33m8&uPXk+{en^^&)eY7PR$CR2_X@ z^?JT>=6!8@TlP==cg1)2DxjP!w{yqExGPC)Ycfzfxv!%r<-|gu>Sb%CI(5mbfj!H@ zPKu5q?1_nqb!6reGUw^jnz|`-NmKT{8o5kVdFcotrGZL|gL{9V7~EqfgOCy>@NM!N zkH;!0$d${TL-r(ox^HQ!Oqfs>#)AN zV${M;2b$#RQ=br;QV)$cq5==n9n%|^AjSb_Iy3s!AW_Ul3 z`<`de!y0eM;&{s9diR*4u>Ik1m+RW@Bo-GrPpw}sk?DnPw{-Q+?i-aKDxOSY8?i@6 zHFd8ip)}b~bnWLYs!yC3wi{Pt6O=7t6tiL!Sz}9rz=h_X;`93&W;1c!XBJ-x|6`Rv zTZ9L232)SR-lN$wEdaRBzO-JX%+Xxa(I*P7Dv{gN4Hn>!9&GNmrHESwmP?--Oe3ep zj?cOl$9KCB8y>=iUS76~qmWn&Ldpq;g%pWiq&rX*5~n5;I$Fe92=LB!T^xu6dzc%v zS&H6ixYkQ}kNbJW;=r84qh%=jsKwR5#~&||#t#Uq(s8jE!#qvEV{j2s(_VIccy(C6 zJ1n>%C9&zf*|6??8Z+j2dAYpUAia@rZhsoyz2UpDTdY0P^&J-Qa22-nO&Z1Y$n=Ws*Oo0OyRp(tF>Ya(z*O+*cc)JRQHZZ`y8|az>4B z;4d3&{W|ZS@Q?pjhcK$!1n_2m>`lylv@K7wpi_^xvf_n8=TXR?KmT>J7&})6N`cic z>Fk*9Q}ZP7PJHUai}e}BzbSLq1!Nr`JL`;D#FbN`hdqUIU0WM$Sxxkvvje&*CqC?r zy!{_NM$=GY1bpV4zzLIX_-*2xk$~P*RjvpWrwjm7-W$9yS7(U9YOe-zt*_U$X!1-3 zxzQc|R~VH@+XhIZfh*>#`8xf_o z$s%dGUx*<6iwH>|Yq%w^pbmUnn#6-HXkJQGbR zDjRon>sTPv3(w*!tp?)Kk1BB2C!)C}Sy zLuX?FoFtL0e1{J5BQC5pcq#++I&BXtOAEts>BSvm4E|=9#Q%Gb&sn1Ml2f#~?&rPj z(`tNwtf&?oD;LrwntO(GemzaKy%0_=0TQjia=ELd#QWi9&r1tYl8@~xy*?1~QGWd&@78bPc3mbbWxA)_nnwg6lCB84gMo}kBqcauhdf|}16#nBNdLR~tG^zQ zj~=C9v4mjK3RTbR6#TM7-}QVda$Pvgclm}I6$d%K4#gqW5sw#%lDb$j25Y(hw$^L@ z*8uIgnOmC20W44Aay_1td>4n1nxX>Hn6A%CK^diJD_tr_Dla!=7ttMm+5#{p zmIej%c(8my8N*1iI}U{33b~8esUtvVUg40~Wv|gd#cpt0O{vK~^5_d0`^~@Q3`ztn zJ+qR1ALBjTANtoI`)f+;vxl=`;X@t0L&h#7?620xpH~yY6(X-^mvo2b9Ofg}zIWoyhzT-(UbMIe1W0-Ah4=~%) zdG2b0=O!7u-cpSwd%m$KZ74ZMEnVbfIju9$7So3?*}d({i&VYT6avMRJodk3 zk1dzR1r%D&<;7l$D84rb8KXjV0hw}2SCR1u3#*`?wDvUmvY>6}8^zPm$p2zVXq($- zQ2m@%nx`uVZ_IvTkkAc~ z&3iEc%#s`=`L+bAL~5oFkN@eto{+jm@`#OL)_m2`h(E!@zn+vN;Wsg^GTAHhm{5MQtyv;zCgzj6} zYLd=RaBuY>Uc*Ym@CjFZsr0MQv*$=K#P?@&U(9MHDUam$gIi1ldAlqB3a`L2Q+P3a zmM)dlf{uD@aBt1;2Wx@q?7p&zH>gX756cVUv}jH7oQ8x02YddrC724a1C&i7}1vNmQ?JsZLL_9~wi-MmygydtW@=&7Bm_Mf=$)9`f8(+%Q04k& z%yX=}7}w0kvu^3QhVv&T3-u$$9(Py*dVhu78?)rDj-mBt>IctR8y0~fdKZywGZ*zw z&-7(zgphwVKmf|ImC}SH=ScIB{Mx1pHc3+C?6p7>Z01|bI*Rtduwefk@EwM?-du4# zx3c-5J`~~~@6}2-QgN6(=ABYG8Tu}?62h|aKbl!dmJ99C8C!93`%7E?t2ZRM?*Q+} zqJh9<;QzAkk1zo20dV8Dbl$4}Zwi5Nd%z0^0}$l!HUEa+{`&-pW+3k07@F3g_)l2+ z_jBlwAP=NqT2iq#|LZ~i*dxh5K=k$Fdpd|gn*O8Yf5=X|3pm_Z)%nD~toJ_@<6$cT xX^JtCvg`k-=f5=k-|hb8?*ETT*Z-1OD|Rek(Ai%s{kAg$xMFrqg+Jx{P%5Y8{JmhlUhJ0t{W!7CjIts{G+YI8?v(qocDY zCh5a<)X*!8+p}-# ze4Rh1h1b``6_#axn5Q?xeZ@mR{&E|_yk>c4EOe)C(T$=QLXLOKk8c$(|-J3C{eqW%_YVYWEN8VTyvkNL;xJUVW56@1fgh#g5i;!q~( zF)CjpIKx$(g!|SX!?(ZfpD*8nu@+4FnX43mi&dBuC`U2#f!1|iJ&Y)4BvELeav)T0 zs0;IKc~$;&Z6~5B&PhMXNr2K(JcxokxKX53VKhuF#}^KaR8V9r;|x{HY3jBNU}8K(LOkFhO>3tGYZH zHb#X0>zVP6~=2-Ez`}tSs&F+2%|gOvf;Z`=xxC5?d@Lc4jCV`RVS*&V~r(O zqT*G8*U=72p_7eqi>yB#1Kd^2$T#jGs5mGTZIm->XyP_pI3JAn2p@f&!cZwYXi-+U zVttIYapKUC1wJUhnDh?TrkjSo^txZh$b-IE#^OL^@HMc4o%b!wg>8acSmxap!ua-W z1cU3VR~(t*57<>7r?(FxNUsAr$@)ZSBfNjS;$%Wm`GG}V7#`f~kOgy%&FPmU$Up|_ zC0c(q8qg%bmyY-4lf8`YI6hH;OFBIZOt3Ij`Wqt#RWAm?*vxDr&Ia`2&r<2Je+Y~S zZeAa>L*;~gc+Wie>g?CFGE0n4wyvz%OT}-|+8fH)iioLatVL*hzxY-^CWSCt3)lH{ zoWLddZ>`!M>tB6#L)Q#WZ7*F3J+`=`^Zxvvj03|BiSU<`Ac78ldYH7}^e2ul94HW3 z#1-Cf5j_m^A1PLhl$gu`%mD*G5(5x_pmpMWd5% zMRf$1NVCbVNsbAFNxBJ*$=7OllXoVr6Owt=1-x>5cTBw z4oM+0RWxi^{9kz9MKYzze#y^B%AU_{QczN2SAr;#ior?= zdJ=RJF`IfrFhj40Iuevv8>@O%CsoZrC6k23OvSpYwN)-vJF}Tpnbo#cvBpOeEqV9q z{#m-km>C^YDp{36TUC6?XO^Gq`b{tS(SCKpQQvgV3&Gq-YL z^Vl^?#gFPV31D@VnK^>Yx{U4J~cffVTye!0@fyZ>3Ro$`f$ZGL8W5wTZiB&LoKlp2~0sg`J zhOgtgW?u;n=szrKyUo@OeA9Vt6k%L3x&BQwmu6vnNnWpE@;qw?C5Je&YtSHuY50BP zP|)D7p>>0~p@hMkLGwY(LEJc!_nz7U<;N8wwaTV{jQ*G#n{ZCr#OP;lXwX$e$3~Bs zG*37eqEE6-icSU=n--VmA)C>fAI^=M!J65c515zEy*g;xuh?gsW1Y*qJiHXV zWx6eVndj^8+pAM4G=TIA>FCw!s||7sPFW(Akn51>kkBMN$#6-OB$Fh~;3~p+CYy=g zGxAohMs7pyBfA#%FNWiBGAN%Xf?d|W9{sYVv8_M+VvA;Q+dHA9P^02+O61ipDyTzy_ zyhOj$+%haY7laeE$l0(kJRiDOyHGlmx|6!wI@AhkqxT|^CO+mEAqyj^qdR^x5E9)t z+v9@0PDp{qg@5jS(2+7^fz<8O;S=bSC}=16T9D0;2bC3l2&owL;H52k;+shfNu*FD zEo_fK-N6-WT8;%>o}NKsTS_1NSGeULR;{z#vsfxD=(!vQr&)E6gjGHTWSV3Muu!>3 zocrP>#?8kqb-(KA3Zf%`usF!?7fqj8pV!e?yRI$vAa<4hXpPlQB$YA}9~V!GQx3m+ zOT%GoFFSV?zGfKOnq(G7|D{CYZ8k;D{+FG23?`k0Zy^DPm?%_>NqWr2H(7y^XjFz$ ze0-m5ksbS2$l4^t-1|}4X_%8Bp3GPM zX_b^Fs%qnAy=34Z=Cg=nAI1!Yig^mdU4AQBZS*6BXVg)uR?HGN$a;2VXLhV>taPv} zwcM_|(r3g+%V3q+nVG;aekg%|?~mE!{()^6r?D;mmg=AeORcWvbQA9x%~|Eh03*>c*{N)T7!S}Yt_H0G0|U)N zQ&8>x=y0Y7!+pJ{^UY}vHZfgI5k(1BX;VF|_C(6WY$1wbZRwlF92bzS`JY+Gy_}*( zvs}0W>;xw?*oCr%d|1{Wi)>2{Cr}>A|J>hIdwC6N+oaU26R1 znC6Ymyk@TU_4dwvFIPkEh@>1T4|yH~rx>vtQ5~_5ZYtE88qKBlQ<$++u(4f(FH7=1 z(rrX1-%=i$E|N60*7TQ~+(LJIulg>h-7N=d$$2(AQ?E*|>6CUT2p5Hzaed)el@FF5 z&O0o5HCZ)5IaNbQU|UrFyY_I~QnK}+guRfFyTsA0>qURSC#oAMoTPo@Fc!PyevXMn zj_i}gos-a6>gt8{}XNQ=FxV$4S(x)TaI@cr)o`gncM%)k7SAU{=tV55g&t|pw!g;Uf%eQF`jQg0! z46%nbQl=dJ9N1dpjx*M>*Y&lOR#Im@EnM_(cYC$GJvDZSmljS`ZyFwlDryld9b0W( zr=~H-&W_!G-?pHCYDQ>w<#Tc8d8FAHt86h&6-^auop#T^#Xq_5@Ramy{YJO(@(x+M zEPZDOs%Zud3iJkwi>FqGl6u$&)`xny6c*`@s)&d2ZfzdwJ+sqbX`Uz99t|6vPYkn!mW;|GTKjQ_?Bfbu;3%O!2> zq;ID3(byc289;-NiHU{hx&MEA@?RAH15)|FAU`lOz5h?p|9JF&gDTkS+Xz{j12paU z{!3r~0RQL1e*k$HpIHA7QT&zj^S^+g`H*=S|E)AWrIZ3X3~st@u}$)4)JIwQ^oDh^ z`YuUAlGe_P>m?(ZWDL-jcnq^0}KTX_uqfKsgWpNNq-hduKoBw zK8I!mgZsXFLBSxA{`VglOwzOMX3w8_7QP>o`i&e`G@_0X_3sh@h^?7D)e|Qo7^c+@?vKRuQ;+(6P$ni;T`M5 zC=(MsFZUGFnGJ}pbfn@Gg`T^#jR^$>B*&kdYp80Xs!FD581?4K4M`Q@qdp?QfF@-f z`xB&g3QHyv2=+iD)7nF5H!7Z{<`xywYQ67b%2km=P@ejOWwKC6G@2=Rx#ud7)!nm3 zri3ey<*EAmDud?T270F)C&d2o@E`BI!KQ)myXw4Ii>mm$MfHmIuOJH(a_6>b`F*o< zKFD+$zCWk)VmlSV`MII`9l|qd1;&cgt@ESUvK4=Q9D@<21bd@zSE$DF!iKxaJ@C6v z@rf);zc=9KouOX46wdB9Dobyp75N-|u%pgHQ!8X%{}nccw3h97$ib}s1b6Lh0IVyv zY{LW0AC0eMX?6<~H&N*2e{46^B(1f?B$Nh3mV&t(IGVWsMwVE$w(n8tHEgB@`Q;jg zOBI;6kQ=J_*jx8$lBW)B*(g{sXjSQQhAQEv^x=`2I8i0swFDMF;h%$=H^*z~!oD!S zEE5#CqMDmBb5GNNWS%Pi0{9>oaC~^A>Bbu6OjtfMh@4qWw=wG@_BVFn=Wv%s1vfv< zC}5AsU*lLywAj?n-@G3H+2DN+l)o9J`E)AK68Q!yY*DbqbMl+vG7(a>ezuZ51*gtH zFH?>gVv|Z7d-$d6-?DS99?>M+{P-JzCg6AtdA)Z+{&QuNxL5xJfVqTEv0Q(~c zY${fn%;h%Xz~I>-xi1Gn#(9#RcM7)jyR4-!9X5l*ix|0aCCt^j085uk3@7%#qRpUO z7X0!q+QO}0qO>`!WQp6&XlASjv)XIa{TLS=KVvcyv)D~sK`J&8BJ|7}sR10msnpCO z>wx)iL9IP=+6%kCCgLJa%F4UoHx#EEJyvoIqH^62b|(Kz>mMPkav9X3ofHUrdIi9eq7e@4ld=h6t1x>H$eL|Atxpe(;t9hskGM@9+MKiAh)sZ z{Aw*A8 z`<{ZGT_S?qZ&I_8?f2Fp9QWwCj0j@XQU@|q%L-!Pp zEz=K0jM`W$G~1t;QgdM|rea*-DW`qv4TgDP=Cq+Q*J@!OiY}fE?!>}=QXXk*RVx}H z_ix(V-=bD8euh2|r0p6$WPje|cCxf8le;F>^ZUTv6fp3fe1cD1)1om6?exyE*XkAA z&$i6*YP!|97$L`F(FZhSElc+EIda5+^ZgR> zs@+sV31xucRvz9|VWa1j={3ln_rBPac<$+v+LjN*B)31XI7Vjs?uf&$o@Ck#PW!rw zMZjhrvw;oSgBKon`|O>hBWEx}7xs$HritcGCp*N>XTWH;JRb^Ul9jYYMT7Wf$PMGz z1)e-*+aAUn9N6r!G+g|N9iIN#T4J@*Y`O^v`1WYU#D?qcxD7-98d0Y=SWRstX1 zj@Y$K_{-QD^ah&NgI~73-lfQj6Xstxaw%*ZXuSzwotn6u?AWS%GKe@FJWkh?;3Qu5 zoX~LJe>`*+hU)UDS|5F3irilSJVQR%^y04;V=2L4XJgHxU_kcjKcS#EvW?0ao>i8C zj3G_A8=pJ>cRWcrq-pE2PpKUl6&U=6Q|Ab*@_Ur2Y{G{|+ zI3()EuFfyd2wpIN!STzuP+fn+p_f;L>61u)Btb#zuba&50aiZ$j^Taw zr_N9S`YuWA%ilNvRt8{n%FAB?@FO4~#kBZP{_GcE9~3}rSMcByKo`K60HNXkuh9Ni zX#YQ1+PjFVWKO@PwKL85m4~9sU*XY6&qFMrIde(#}olQ(8nVgqdO)LJ- z@)qy22e||Q{TVrBNVeZ|56)tVBP1ji9e%7PnkgUpi72m}dMXg3HogUWaARZccG~+E zg=JF3)&C`1PJYte}4y9=xr-d-&psHcFgY9U{lcalb8V+zw5qiLDJGqvkaG>E_ z6iLHj`or*%lelc!OhO2&R2Kr-Cni)SWzwTjiFNMjg!8>W`kBhL{k7w^TOhD43BUIA zG%`h-4cAaJ>%t6GKKLVqe9C3^tGaf2M0BjE&hwKv)>SqCL;t0@dNxkjK}=NCSJA${ z24@*%XD)Sn#Q3C$)z*lJ2rRu_bXws&(01!^%dI6=lSO%^tAp}bKE5gXcX|->0N=GG zr2FGF2hvl3i-AX?*1g`hG6TZS9Q-pi9qek^kRdD?kgumKXja~UV zj+WrPNs#4Ae0m9Kuzl|Sb?ReVq+(F2iEgQ?_RKZBiTR8+tN-O(4!dS~gRZ~XgJFxd ze#hsTa`#5_o>O-7;aNvujE92jUeAjUpnWlDr4Fpb(P08!OC!KSyKc4~mRA+gC))S) z6sMV`u}(}*(?Ra%B^5}j2p%8y6xI2rWo2JbudOuXpaPM+Z3CEkn&vY;H1SUr91ru~ zDZ#t=o8Pgrcgdsl<9c3@iw*p)4w#~^^6`Kj_mN!_?XOr_w|3o6v2>p3H?A~at!7u# zO!a8d*B41Qy+0wp+?Q&#RGPndL%?Cv#L7NCyI4(UeqkH>O1k^Fx;Oo;7uXDl{N0n+ z%Rt^h+5-3bZJON$>Qv-T_R>Qx8X@l@C1cYVvRMCkVg7=TH_l^pa;jxtA2QX>Dv=g0 zNA}Z9&kzaBr20PlpvLR7$7|e2IOa*1{wfk}6P z`A3Eyo)GY;&T=prT$IIhb~0Ve>|7|nk#Dy|xhVU*1^m1078!5uYNDHAw6V^AZ1+20 zyNncLdk>2%sp4!&Jn2-CG%*^|dd6>#QfZFny(;pG1lKrf3f_IKZqU_Jlk||;x(eN* zX>B|);;>dP#@f4&97e5ep_~z&QV!i>uqa8?Hmz*1PZ}Q^gMQdh9NL_++xr)}ZQ3};Nlsl`;}nF3=Q}bBN`06BTPrH;-`8w#MZhM^zKm=*j8EYy!nDH0(oAz9l^@w$!Vj zVcAqI$xm3$axIB1{H_fAIo#CBjo>-xZD49_R7O7mFU!1G99cIttTF#F6LgU)U)w+W zPx;E zz}nzA5$|fF!PL~a(d98tp{i9Nf6Hv<1TwXh$`_XgRe_kB$%yNl!x)@uw|$r4lG~6& zged5Rpt|-NIawAANI+&Xhw62gbN~;`O}|2 z_w}j`Abd`3rxO?4%v4&CMd)CX)-iT`JXzL-8*~z52{d~Lr#S=Dk#(+vg4{Y6f0Uc? zhf%+vL^Jn(|EpUMb}acu!QRgkGV@n4)&4J4KMQzkl9++)?YTnk3u2Qh9ENC9l;)@W zB$9VvyD8(tyrxd;zTD$_yj~e20aY*1e^S@JH+ri}kI6z^_Jn#0ELgd_T$5{5*Qk3N_b5T@Uh?J6h=tqVW@ieA?Vf z&H9<8afK(_mJ>D3EpNY@MpCA@9dGj^PTviy^X}*w;AB>%9?MGe7M4`#s_Ti zWqLH-lFzZL9E1zCI7SgPE>=4c^5_&uv|diTf?bQABpANE@AwAU-$JH)EQyv>=^ z#mx7Wzbzhi`BlO#aK_`L*(J(?2NggwpS5j{SONh`>D)RPE) zAOiWE6GvbaG&I~-1=1AQeugu)1%5{ND-V+G=+I<6Ig7h6?3kE*c7?)SL^TC|C!v)! z{0Y$Pc^JQ%j&=%(V!lu@g$9xCc9cqsOxNn|VYM7Gg)m)NQr)sawd`Q^X1A)E-Ei%_ zl{mY{PU7qlc!{Y}(>{2}vMKEalM-E!{QH6w>3I0>lS;ufKmk%#=}>R3=3L>?{hrco%GdA6G#c({k{1k0HO+fdc}379oed3wF(E>Ig{;Xu#=ex2)z(T{ zQs5c;^5ds@q|OV-K;X5%-Vc`ybo|VHTvvldIDhNXf!mT^g4t#G(lxt*qcIVR{h_}s zztZfd!Kkg65_qRUI;iPuO9P?!pSb8gkGuXUlB?>J^I|z%e;GEn&1l7Zg6}nxX+)!u z-AYG~@g%sLlcny$?HS!aM0by+UTAqP*S45;O{Cs%+s_c^=4Rz1pIlDoykn$0R^PSc z$yquPB`C4Lw#Xk-jwR4^U#tPS4uxLZ9Bj32s_Eb04qtECAVg_2E@r-Isbx?z6F!fs z6=7$eayz7JnRAFheQCZ_WNoW?0ixA#jEZ;k7^T(UO1W!bSWVP)743N_O8JIRY_dYc zCdn@OoEY#t6%#sCvVa^CqYx$lNDSO1aomsQa(kMG%TJK^yVa|~j?)JYc1wJ8Z&*GC zBVEqCo)CsH`OayvCFK%Pv>)bqL*;s9_7Pk2jrSq zeFhocaQmTIeqmt2DO#Yp#`VBP?PlcYzCq6NA@A^@bVT_c9+{EbKgZ=^@rcHXM<>#v zN$w(grXY2FuAH~gY=#`7BALqPFr?+#XSw&l>AdY_xlk`w%(+k|jk&e-6|+QRTg&s5 zYH4Ec)-ANA;+3xXVGqBdXo)~i3h$(28`$1)SRpx3)aSSMDKJHnS`h)_n6Y*pwVg?N?7B?H?j~H@J1zBH^mMcfhF%<_TJfiLHQeYM(01WETreXZv z+ygnnj2`bhB4)!D&xD-@DNDBl__@o;*8{RBzY|;TK*9H;GhIy@QY2H&=T$8!=f2`v z*X6^iUDE+aoR=k9WUr)&r<>Xx{rStBi&J&14z-&1CevQHu{E70nLF#2r)qD9Sh`I~ zWvu-YtKC@&7&|dtt&dW{?ez*BdT7UJgz6fBe?$7{Q>H#dXE3=~eM6*HT(TfwuRvTd8Nh6L zJM9`$ETn-v565+Qq8-sd+gL6)Z&|U6Qz_p(IU5Pu;zd{Sho@{X|zhjUUUCqf*YST zMo&a%{mRthyz-kPTJ?D>%onBDyovQVPsIU=+9t-daX5ZU(2eh+Zgp_WE$8R>K2sWLYXzm5piUp1g!;`)}&^1sWHHSivVtN@yT1p-CW6eW!$9NK4W2HM?ISkWmPO3Iuy_qYRbbBkI$gI4UF!<1$+h`x;Ns~5TfD=lW z>ay+*olOv%ExORF#D5z{w9u#_#l7Hvf#=SVSnT}pfj>Z;2QJEclTt1B*e+95CP!ay zwjM;igehGh)-PX;um7|rTov&0Vj})crVkKS#s-R+Jj{#_pP{q;u+q~pMWt) zJsCri27Q`c6yeF)8&vcMR;M+M zdyPs6HfRL1shjp9OI$Jor5ndZloFxnqBOtuFA~GYYuA|4DX{_kPeu4x3ZRNDs$O1M zk?3VGgd$~v+P@Z42%S{=(79E-wCva;VlBMepwFJfwPSczGM+Xp>N4(_52E(K@mF?0VGU(I=%&78ca0S&OI&Z zb6=8_=?yXQ?*6RDXFhcq81;9GF!+JO!m6^?r<-8xTHA6tlhmk=draYahxk~;Fyns* z$B`VlZs(Waf!ePxW)^Mm_<9*u!_iy>Hm^Wm4S^kjbY z=2~t~@S7YJ2(UnySfW?&T?!7Y|68xf^l)gFa)W4+3_29IYDKQ^J8ju>FHvw>e0{sr zrB)f#$go)JdGDDTzcOe3xX7?Ll@|!{Z*&;=AL2R1NAQl}n8O-piL_;*DBDI3cX3(O zqwDX%z}D;X1}Dq%bb!y9Nzcx0NYg{iE*tlvheo9Q=B-OG3iSfV%@CUX<*!nY^*vtQ ztp#mgb(H@8a1XU9ADi!#eKSCowwFY)Wg+oR?oi7XU@DczB6Q&_^Z}CCatc~vIvb?m z1hC)Q4;Gr8N1wUl9$iY0T$)5Au`=?cb14=`G+tOp_%Sa4MIAeOQGCrp3EpY^B9|>3 ze&=|R@4Lj$R)B4}kx7Zk+4;OT^`({2K;$Zb#4<+H%D95M#8`K142 zzn`K6cWF^0G>5ZxDDQ<9>uFKFuGB=(My=ZhcZ`;7h6MqQNAiNpmxk*h zrJ~OuVPW+T!v>2kQ}O24Kw6KnJp}k&^Yy;n}|?PEjahVw#t)xp|M$w zD<`@H`uwVZK1#taUNbyVT*&@9zkc?6wRzop>Bei!d>vma=ucf(AI(kzr)z2RjlY(v z2(wveoOLzY`PxdTtgnxq7P|B8F#7E84YA^nl^(-&YnXf#cDGiQPE(2`WmF#Lt@EW0 z_gjww%)aPj4sRYH2Epa6=POHvwbNX{E}lu^d&~3~JVCj9IBB+@}RmI|5S~#!|AyTY$LN8jl#tWY$@J-t^PfwugphRQ5OU(A2-A& ztQ{BC>u?u}Hqs~41ji(3JDB*Vs|heS6NWvyZWN5%(XaT-i@2s(+UzQQH zo=aG6rj!vcHO|#+*UcBX|NgVE%+Wf2F8)|GKD6AtW6yqQ=zB3GH|L!C;Im|D69FTR z*#1=RJeLJTsOhrGVFuU^_ET-J0Rh8e^!H}>XV;UhM;-eD+;s@3nr<8^J@l|Wk~KVt zz@R|E-k-|jim~M(Y%Vu7IN7#1ILdFJ#g~F#n8=FLOh0dLzUG0LR`Iem6YaBM593prH(N} zmYw|1d!e2(US6k+r=1UhpoTXbRrbxrvUS@&0=0FyKE71H%Yf4^1sm%|B=hwjH0GVc zi+8){tM#^UZ_;csV15DVX}l`J;eksZqNRoSz)tOgxeDj^%gKz}122Od+fbyyi*{b8 zJ3ZcPLW}BM*=F^H59(>koY%-=!vobo4d+(Zy3(@|{hZ!@%*xx)!kWZ=q;8W{(^0Sx16WBirP-&q?6o( z8#k$;Y!bAiGQ(zfib{}8kS1Yr@8mT1`FkYQy=h6}XPrmnMC&Y*SB(>Fg|BRBPhV^>$)Pk z7WN99Higt_3*I>_bfnkHK|r&l1{d+!N>*Uw;1m|xd#lPc^sy@OKgJzqCjM?ZJlqLn zS-bdl&2GY!5b$tRJOsj5-F>@cJFsAzTd1V;xS~68aia>KmSBCma_cs-(;(Amv3QU5 zy2R<`?NV==X^*qJm|1Vuj>(AhPDh`HN!_xlV?)=%96BDS;t~7IRIDODq;8k~Xp;4m zb#onwbvZAIO{_V;Vmxm}pZ`uyWbMZB5DaKY|0PIXsTX%O|rdPT{k&&{%<)Vup2 z8<(%K5gC*2hQ+oH#u4NDjG|KH3(8@KzH_|Lysp-u4|3zYv-Z|6P1NHJsw>1NAJm}| z3K(7<3N2Qv+r7;<1;>>z%&E?BjR)U0-+tLeJ+5kXu%C07Yigvprph>UYK$oXPFSh= zDIVUO#UC*!@ADj1)^INPjGDV1;vB{;a3q(&XL}x1UhZ6OsEReE$AhEY_NPAUEcZ2ON8Jn3#tWi1ZSUG01jjzc@;%{5>^nA+V!~VnTTY){Q*u<(6NP4y9QzZ7i865nNL>rrhCMTxe`$bPOet zWvqaVbI&(7?=qC6ytcW3aa1=1mAw4J>K579$`6UtSm+Dp&By;4Qa|BSz&~#6cAw_) z8??XHlVR7hJ|%OlzW3*MMRP5}YE3TuhRX5X(^jaR5Re%Yh&1bCJL)d;r8PE)svlbP zFm&3ITw44w^xVoA{tB_)_dK|n+ljsM0{}=zxPc_pwa0mt8eq>68DQ^C0Q0JgPW>fZ zNqXB%;O$)eZg)J%Z%uL-{ykoIA@~U=u13>FZC0404u6;^idu_oYAyT_(YLZ66m$I{!te7FUT)|5~@rx zRAb$PXgIt0dLP^UBod8=$ zZMF!6R~8n+I6j+EN=alI`CT=EyVcH(=%AfhM_)cP`uVu1Bubq$lZ1|*ra;TZfzsFd z`ufS*s?_MHC{^P}COQzPxU!m^u9MN=c=6MlAh z)nb)Y6z@qkUR;}W{i=`%$fsw&U-o@*t_Qw;1l~k>e597l?+0EC*?M|Y-~f0}Kz+)c z@)%wJy>Gkr2shXV3dx~dNoK+%#_UrJXwF7mzlSCS()n{rbW&|~VQ6My-{SR=sN^b$ zv&NB#vqEoxRxy){2B+MI6v=D5S=WW}wiO)?&PL?b$M_pw6hf=_XN&HwD7KsKXRVMN zY^5S(@}G0}OAnaa=YG`0;raRJxiaoAG;Tx( z=Y-n!{DwK?MU%pes%!--4Iose=iT?9NqE0S!syJ8G9!Qw+yDLj$%p4>Vf`?g zrRWZYXqX+k$Mw8O{^Q>bzG|8Iy|Y%(LV{m$oYmg5^q*t9je!ZREBTVm za_Q%=`--)EscNve1|<_Sa~3GzmNDWEh3>H%=0O`{>?OOT=5EJ!7WP|vDt2UPFBq&e zun*GvH1V*Iugo+6>(Zpx@I_-d;-OOQI^|#B^+jy@^cw3>#Xi4@VC3KTO|}ZUG)>n( zh0qU&!C?JB^uDP!wcaCgT-GINMW>Vtfs1T#GMcQYd5iV3eGh%vZ3<)7KMO{S?|k($ zfEyqu0tbx{6)+-ZM*b{mie|3`lb+7y_el=9-y++y_?Nt<;7zp%=9$*H36H7nuTSA< zz~0lyMH*8-xR0*!ESm2fu&{8uYCgztG;|zv%^Z552B~Q~I%isaB=!Ngd6Fv&Ktk+n zt@4>4FBmZ#B$4U?kw;Sc$T6gTNPb0qZjbh!ssFHktcgrM-p13&wBg|@f6N3gPyb$b2#v?{SPWm3_SJ zeZM6tp_2%6d5Ex`jxs}>IV|o<0-kR{-ug3vcW`WGGeM<~i|pk&=>mTCh9#YES8Y<; zrICo31{RA7zJI)eHJdAkRdKn8Ax=(0 zKe@Tzj_k5o?6( zrn=+H5p7`{TQT&1ywxyprNJnLiH^p;8fd*&Ti=Y&3NSvI9mKX&Ql?~AEOcqLYI-AC z|7-$)asCi~lF2lk8RoN0D4N0VF*?_K@%(P}4nJ8)D@28~GjM#q%@cUCm_8Vj4@rn5 z*Ay*R)ujTK@9CXA16p7eJ~?MJqZhlA2YAq$@&84W4+Yy#aiE-n^L*P`>$Qa2mR2-x zo?O%ID3m$gkhX*Z8K=(S9v0sD!Gj7<9X1H#;!Es#Zn)Hu;(jYrYM=7h?)A0>I8GLIKq4J7Os> z{@#Xp4X+8!)f;^C$!~Ol+#MnhblJ8YboS0TZY>QRJ-HhF7t%SSPX32GL+M&$<9zPN zb^4S9|IwY()qF?Ep~Wt>f8ve$i}z_kg@@X@&+bI304EQ2K4GC#*@QT@?fp8=uiaeg z`UhcKT%>Pq%Hu>vN@9`J=?(1F&RfNND$~c)rsp9x07LwEBv6z3Y-q1#0lU+y{g4*K zvce1Sx(bIU{kh>^w}8O_2Zd3o*K!%BU;hn7ZvkzGCl7fsjedgwZXJlJ4SuuJ{jXaf zGTs4^F(|b~TkP*hzds>#V1w-!!CVvq_>~0cWfA=A7Qk>q4g>~|8y`^mvw32@1`y87 zpi+}dIH3b^iQ|c$#lLO=i2)~iVf(LkP-?#YbsUi=1`L`1A7bE#zZVk-gmy}Tfgrex ze$5yIu&ca#HjO310F5pEu&*>s%1cgeK!x+t|J6(XDo?es(b4djl85%-1wfDvmpn|* z)-$i{1-%g*e1-Ja1llT4I=RxsrKE%dX1rF_$>%-zyNfOAnmpiy%Ef5jNHg4)zHt=s zj>3MAhk7;ec$q4rqJ*BzCq|e-@{-GpEeQ2xfBIOMQdnrj=&3S`?x7=qoe;kDuhcoP z0IB;Y|Du$6p50DSI%(6!_n68Grh_!>vu)~A{N5&FZoHN?(9hBxJp9!bg*oJo`C$hN zA?kz9mHEAG!83A|hcSX?&M^vfs4&)@{pG4|zjR3pHBVTplv5wv=5Bznh()SbR>)W00ypmb>nms9?BcZ#nk`mRs5#!G&h zGpGB5(+(LA8=ad46;owJTI^avpx6eULN8t62ux` zB@#p*y^;R>JsvR~`~@k`>-2W%HUx_?r*BUe=X9VyjH*=WbEUI^Ng%eg^ve2GFLlcO zPN+_$>d7@#OGw73?3+!ZZfQ@FMUQLjIt@v;8#=8|5(oIsykE4u71cdsQK?HUE5lOv zH5-u?y5L{i<)#~&z0RGz#XV)=^LzFK9O^bN8*gbhJivCmjgY^slNr`kq9s#>l3_Ig zFLHej%6`ks46DL4tY~Zx`eL%DO-nsN%s)Bz{ZjWRL%iU#3ESZaLoZ*!eN6aU<tz3GLB*C&u#u6M@x4jD)#X~6n%LTQ znEv2Yt}^REY(ED{udvRnvfQ9EDzWIPejq;Zl2s6!jNa0bvwwwbi(1EG&|ZG|7S31a zz|mMD{>>gOvJ4IM=C_4lAqjV@{;(q>z~eLXhje8~>){Px`)4ZUNec7__Vg`u-XizY zZV0h0?1#o2ID9q3vTQylQ0H0tcHjzGO_Ab56{@-MdXMH12yZA!*prT{6=qfOGSqX8 z;C;O9#?sRE_b62A*vScqg%(w5=DXL@IhpQ8SpJf=Aaj2=wr96ff7|ADiv039^n=|1 zRobLgs|a>GR$+|LM|(CD#nXzg3Z)ekoZs?TNl3k2hO|d%QR}R$j+@PR+tp9YtZa5c zUZ!Vw@S4;feUj9C5KftH>!LibWou7kUyZpX`LpO&NOjfB5agiw3#`UW7`gUdELyKb zK21+=7vuDLrABQfE+uSvG{DRjdh)Pdf);zqZM{6>S}1n#abn61{~ok8Qny7~z-|#; zlWPEu&z#a3DisOH z(R`JPrj%j9<^8ED@AOiss!a;(e?K(2{-TCI|NcA(RII?EUZ|-xl0jdaYBAT`7oi{P&IS1TwR5#>{W=2bnm8(P2!~atKA^inK!g z%$vm~d(ru@zniZ|zYvAoW<$ZtiY%)_XLGr;-jE9A3Y8C{#Ve^&%BATIAbOiXCuf5) zn0Y^V$K+HxUC$U+W1P=D?k=^_pJ^7X4OtZYJf-q{bi{ju*VgWO1aP^;h#k{CLsEKW z?uHmO$|xJ3w<|i)^Yv}KB}JAZxb=6AW~F>Fhg|05WPk3U5JwCo#-QaZy|>0M2qNz(M$9i z&PM*vbKd9ozF*FV^W~gxvwt)8UVGj5D%V=qx`~+kO-lSG8`)qL%!F)x6xH=t zMwQVIyhd9oE$csrX!348Pky_>UhVXi*>g>6L5-a=&hL0BF;o*c?9j9n;~oB3!&|kr zYy<0rb6=SNxYMd}XCajPRi_N+^ibF(j#)KxPe7CxGHj!%tf4E~_-^hmwHde)9-by* z1j-eDmOL~1+n#FmkLU2><>_7n zY={I((St2-Rm>*lr6nAuh{2Y4(Xs1n-@NBv_(hO1g6On>xhqKhY$GW z@30MYK94@_T%+G!Xe?uYxg@tl@@PKl3Sl5A*o%BS-;tjoJ<^R2R@IB(xcXWfosv+S zvnc&!iDo;r(^oAhC~42Tl~LmNzLNB*upZ8Rp*^ytXugj#>q5Ov<8Z~beAdTUM$yz~ z^o1AWa_APKvjVTuZ0bz32@jKVmoFeGleJ7br9tiM(=U)-e%%El>DjX>1uF&TV~9#v z^z5t;zI306Wf)1GNvXvL}$x`yop-B^rSj(dd?xw3wx zH_H#JIWMWqg2Muxb~HI!f%<+=}N#*8&s+cdet z6`baXbd>Dbf5a|#>&CtqYfzyu4?yf2#UY9C^@CeDGj%Z}w*g>Wm)9DB+B3mWh~2Zt z<T{`p1Xkzh{d|ElP9e zPHTN4{eL}koBkCr6dK^!PO(c2hTj>=9E`>P4!1W{r>Gdkj89-{+FMvk>-2u z7~NCjpf)7?F&=AV4ST%K5=QqXwzD^doQT`wLd^5~kBH?jMn9j}Z0(vRUG2Zav36E9m0Mrk$fjF~dM51S|J?_O3Kw%wxIQcP>kl(t-QHL`e>;`BMRl#a_Hlg)&nK zubcHnPd)HwA_cJ&RGf|!?2?0^bm*K4KMT1JXD#g}!(5Wtja-MrTCu%X^C_ZzfK=>} ztRaw$V@h@G57;ygbS8zI>+0#4p7!91G?qV8kPluPwr|o|0Khn_PAoX@A zz(-?K()NYJ8O&CEAS`Kcmy4h{t^(~^IpWfZw{G?s$}d|E!)n&+l8x1&5O`-{n8FsH z!&0jM>rKy9)yLxb#3a7lRZWWlG-`Bi8kPwbKCkrV3$nWRd~u1qdx*s0gJP%U{Y7BC zm&V*Lx7saN++UWS`am8f(zf@-8O?S~&b07P_%Wr(?5AASAk z9NUMq#u;d^Q@%&`hP)-3wCo)_ZycHvaoy2-;=M@l8T7u<2!Y|b>*6Ewi%CCd_Vfc=6j;gKPysTFG9N@T{-B0_DPov%9i|)fQ6mIL zg;JQMRO-G}Y3bK39kQHB)%-uKtfl+xNfnY%wE-J5+EA7 z4X@i!NvPgq?wQNy1zDTMpp0B>#<5fK{?mdtKYjPkoVud3)GSEP(I+y<;;Z+w zI&-iqB~v^sEXpXAY`+x5F}>UrrV2;5j^6hVESe$xV4->_2+c}bM?rSh7W*ZKsQuZ- zRpzr>^)zU|qUhOo1gl$ps~LNNf@CrC;C#7N_u5sjJtp3+a||VyEPf>}h`#O`CB1_C zVpBk6>%RjbxL+wL#ek|*=+F^ogzex|hBnpncuaFXMiqUd)}~|S%h6$IzB}y8YK%-| zmtfrB8F zaUD<+v4La)N@d20ltph1aXdt)ZN)*qm~2v@PNM0CfS<8Amm=1S1#)K=SWxAOo@wWx zIyBYl9DVSs_OO+iNS1ya`Dfv>q*gYP?9)~(^+*g_GpUt%u%5Uo^g$-72$w+uymfS~ zl1`U3n%W_PQEMbKC=t8#_~P-w%ZyQt^8q&2uNp}$Y6)D9{o+tNf)v?k3Y|NmITR1qPc7_dsu&mk(i(K4!-PD2^ zx552-t0bVSp=sV%`?-_5q-fpr-v3XvKdfAnAiwAtt!!7Y>9U`su9Zu=z*Z%(5WN?vP? zFgEad_RAdDY)0196o-g8x4p&!?P}~K!bBlE!16mqfyu&AAY}#O4M|E~UrNQr3-5PxBXl(|s(qFG z`c~dV6E%%FnuWL)wG=5qU%-n^oG5;5H7bZVCDnhZ5n%g$vt4aKNNA;WNxG!Vq61|P3#yRI7iRA$Xyy4igwS|l0 zR276f^2oXCOCDHPou$af$CEu10!<>{i4F3T@2L(`In2onOeUFi(}PP-sdDUtiMt(R zB}XXg^_)6r`4mLukJU^KGG5^ zWM&;B*y$hZn2f&4XqkID#>cpIAJcnxv(&6Hs`jRO%N9-Nh~mAw+i7!l${Y;|Z-;Wf zY-J5!Wqp|`=(fZOAwnLEJ|g3>{zl@xlJcN4U8G%yA#17ja`T*#nJww~?CEYSteGYq zwTBGrp6!R-AT7f`xW zmQl`EtkLe%57ms4%m&1ER%r(gabMd_^OJy|+N`x4sza4t7pu{w|N4FuXo{0{&py;q2x*{gcEwbf=iCs z&nDQZp~qgf_Ssiq?&9CzzeJ#3$S3m^AY@!u@>(x^K`(l#z8VDd)xT-@)D8fq(S= z-r54SHz*S~mjBc{$tZnNA0`GZ39b&ZA6=hvvDM)i3ncR%FIsbYR#Or zd)0p89c0{B(XP%cvovvF&-6q>!l!vYLoMNG(5|wLkmK2BEG|X!Wje&|Yw0NiIkbZ> zU%b>|W=io0**#keLXX|4ecMB@_u#!w>STSv4=Aw$L4!|9P4dZezF=%7%{?cm0O!?p z>mfQ5z@87Q7Jpg+2}eEpGG?rW%{L_%S+1-=XPgP(5`H#J#iHNa=!%6pGx>~*e5Vc= zNTx)yzi=phM@^wk-U`G3uI1)6AjQH{g?~mRZuD-6+Xs$zUhkz^K z#0&=RWIxKEZ~b~Ev0MpZ@ieehM|42rdcIBVq~I{(^cH=uyHZZX9$U|QkwOf9>LEkC zWeyDbiUVH#8GpXMw+6X}_k4M&ylhG~-e8JXMqlH^xC1*9t%t%Xw}7QLKnu=G z4+|PG$k>F8duv)*#O(y{d4B#d#S}uq(M4d}0*UxM`pwrN*QDM68$53c#5{4h(To;G zK+})-E^$7!W|2}dAL``dm6YFp5LM@@syB$5meZLXDZzd=%08gJpiluG(3zZ$0g5ax zhM-={x3M*@*o@=Q1fzUbcXhhB*hOMYZ_m|4M$eN^Inoh13M~b3jbr0z0^Fa<8zh(E zZx_+DCeGLEpFkI20JzJ!Ax8Z z&8gRDJ&1k^ZBgKGQ1f%uox~oxrHca~>nFQ+vxatPz-OL2zoM>t7wzJP^{74X`&d8E zxDbeCP%aWaQ;xvU4|9R2{bgQoa0q*d!Fn5~0r6~-9&LWv zC$fn1?UPmC3e!CQy*`B&h(eU{6k1DA+uk}0J9C-_PJ;?%0`*QY6D7DLZoa&{;!a$J zTJ6jhqLP7K3ipMMj;gN{6rHh`>ytw8x8`vWugi0umYw*G^AMLY8kwtwX-kbl*FQr5 zh1g*${W^rJy)w)~fk~U@9W7|6!m2fd%)8#{9#~VqM-!UiWr4Q1%J)Z`$aL|`RPLTbKM_&b`g4nuIxo+={e-3sti)Kvwi4B!f6O=^SigT;-Rqe^ zkHuhFw$Q4#zTlW*Y@tiM^LR*uil-ag@G-d|1<2c<#9HvWjF5A5M>{sMR#f5u#o~d~ zm?u)`nMd8vtDbmE*f6LGXTI$DB&%cMwB0`@^;;gcCBRnE+8StFA_8&R)Hpr;F$SVc zzWarNUwVk2mx;u8zvRx!(`L}z-6nS240lVI^FT8|FJPjxL-?vOZ;xIKbnKyMe`t~} z3|cICN@w@N(4yhvz>%}ypQt_R@XhlLp92a=m-om@9t9SH-?~HO@^|TTCPzMzixZME z>%pfcdisLfrjgY@JHM%mYSG07rD$lrmXV0Sb-O>mvXj>KI}low6`Me1rK2987r_O( zE1<(n-T9o?2tlE<{(;HMS!4Me3OIOmuK=X=9cUV@^&p%zZh*(WV zqL4L5lw9Rt*&UyQUQnMB$GGO&n;4>s&Ib0cEQsMfSl3jZz*AA@lGCsw0h13Y&S!(ee-*$xO4K{6?x^A6&mDd@o@_%~?-s-A(vE8KdpFCT)9tukvm=e1 z?B}5XubXsi+wgq@%Y@^Kal{)7G9wO5*p=(+R2^ZFPQ7+4Sn^|>dk_O!nffB?S#r8e zRxa}Av^dBnhZ>ogVrz7Iw3^S%(%BGIej#B&N5P6Vhof>9r{2FlGAF$ih`H+sHe(xh zI2oA{XHu2h`vi$My25Wg7CT7ncBlEQX6qkD30_WBfT#No=)IF<+{$W6u2yU>vH2V} zMPkt%6iut6)0zyW%z?ytxL|O2Ipd;zTWJ#0D2?W!>+T78ziuYag~%DgRa1G+wP^hB-+o^PDQ`)rRnLDn#;i3jvOPzhcEak8-qk!U{LTZk zHivhJ@qtDr*pLsv%7s42^2|glt4n~@)(E-ht zy;*~Ot!vx%Rro3r3|_TGS-4Qpg--veQ;yd?J(_sfW$~BYZBp>;&(NrA+5x>?v9DUc zIsmg+OG@I$E3k|G9kRmbS(ge>u&8A)Fn9Y@d~l0CFaKHN@Of-WHjbd`gdDe=T{x0% zu6@lmxFGy7R{<5c6hCUzjd};b-hLh}EAE9OHoP~VnMZNVTa}y}lo0_|a&dFPPOD(lIgM*UMtAQ?;(3 z0cIb!#Xr7TB_!bdN}8TW0k#F6&qIfZ^8IucBd2dplyZ>fpZdNxOAUExC0hL1wV0U^ zYC&@EjLx3blZHDcwK( zq!jGn0SkgaACSezeAm-o5M*c}MJrx``G5{Q5x}9^iIyhszX1I4UmYV#szMFADH6rO z+N?ye7DK6?TFnr=h4{t?u~Q$+8O|6eR%5c>`Vr|qS#f9Rzi!zy0bGDOEx#f(`R4Zo zT^vkO>8$=San^ND?!$fl#5>|xQpQK%;Vp7u(J;WWc*pK@sRonr8NOULoYQl89S|79 zujR=;spE+rYeDNthOH#MIR_5uFY4uD=$G7fk*DHgl=z~eyWTN>QswLt`F{Ini#?u2 z7>+7)_(B1b>5>Q+UbW%|VSJ(7ncWu;f)VH1qb#`Aa;^8TMNGqJ{3UNE$>q!^Ph*1Y zOo_c&I5-!nu>^4(DtF`iDBNl)eQZ9YzSinEPq*G!;zj2je*u&+s>~fVXB&;vATIGe z8*ebQ&tXos^#;~0$M2>-Ftn)eq*}^MeJ9PMpu8`{(LLBQ;O zS-tWXt<(YR2xQ#Ti|cxaUmXE>p8;Oh&lcWf(q*@4^*BsOKygzV4>EY@HVvZ8fqd&G zcoWe58E;KvP~CRPtHJ;Pr#0k6gzLBy+FUt)KPM08Ef-&>*r6(g5W*F3^8*ausQhfFbz?HMeoN> zWFk&=r&%|8AT~QfEo&_XhcE%Awv0MrX$^Mt@3&cRg3PbQEG)b8F{I(n40jVecamC6 zz*Y)LjWKrD6%g@qj;!kb%;p)*PU5GJrG>ZbNt&Y#fx3S~5QqD!3D~Yt5~(FeXmNJ! z#LK~zQHMKiGCogkA0lWR{oIV-?zRI1k=`#RFtBMuTCGG2H5SHBH=|ufuDBVpk#9_VFIIxbm#USUXIiS{5)KP=1GBtYs17TQ#dK9QP>*w zx15L^pqg>ZVF6Rop^uUSYuS6hyR7i7n|k^O_J#STGF2SZW*atK+@9~YOwdvPcEvPZ zs)7#mrT$|l9-?PGj$VXTa3zK!KQq~Tg|l@W&9n?N(>sQTnFQIyG%fc* zc4anlpx|Za`YL%bE|pJbVMt;h6l4h5dL_cj%^*`hVKl_l;+~7$C1{3H7*dqj_Yt4F z5{btB_$76gp{TIQes@Umx)Khe#SL;159ExZ;sD=Bv0(eP@eLo4O6%?~>df~%3INmV z2aOdzI-zDO)!3=X#Z-%!s#Kikn_T~|rx|s0+iq;RNMKxt9oclEdxQ67?*o9Ldnif} z=k}5lxcorzFTPOtL(ZPm7!{$bq7ETGxr`29keon#zSMO|S`G-W^l~zLFR#-gFjYBl zDSbrp&l>!{z$5xUB0`-DDZfwk7TCjV3c1exm9POWirJu0_`$(Jil=FXupn-fi0_rh zs$@kv)nNDybp)6J08V9ep-Q0 z$RkcdGA>EoPTgb`6m<433B52E>`1v2a8z16xQA4Nw(r5FVVTB523kgQEHS;aTA(GlhvuE+Q_+}9VUwVvtg$US#5TX*`afWm94l(R+M$~FfIbb@qgTYE)=q z?=ihF_H*_Xh`wowkKC z+^zIz-wKj+CU)W~hZdvh7wBp_^Oh}FO4HusdW?+BlF1hwaW!%&4`*l=d1-K#>~7e_ zfC!bq265e{sEN4Q;cDWoEa4g)*;U0KrBL<0X}S_hnfQz>7m9 zjI8W!wU;MyRt+$m3cTP|9x7>>gR?(x*2sr~T|AmDNvr)s0M5s?I#?9}!P`<#ZfPx< ztzp=TD%zaGc06^Gh1RtdwSQph3pQZ#NOjXV*Yw(;~g?|QR z&V^J}jgmPe9i;U>%n^Npos(}Si;iTgJD+W|AOCaQ+ah59vkPXWranlZ?Ga+==tiJi zZnV|g)ung4yB`60vGjwKf7tt;v7(Fwfil4!Q>@&IQITI)luCNUs~N$f#BJsHPOV&A zB~WEh>P5laz03DN?@QTFG3~xoP|(kEGoGiXo5qZ#pI;5kbb1_aZ5s7H( zjxUI7$lqc=h*UB%Y{M>sD4juhlUhs3dE{C{ZY`Yfnziq*yu@_vL^4J9umYF-M>Y=I zkalewyVR>VUCeW0fhNzBd;=4+e5d833*qb%YDuKMY^+;YMKwVe_X@*b*W>jxeKgX_ z6sy+6TfFbC`@7ys8y&_v)nk193^3~B$Bzp>7fLTSIBC2YT+N=1VQM?H=m~cvm+=~Yz?Qf9YlxBn zJ2NS?`5X7`TgYSGT@r_&`>gxFWF+|{mSNB)C*nz{jp3!wR;G&`3UdXccF=wP#Aak6 zTdg222W5MF;I^dkCC8fjkWM6F)PYH9$?-a@e@^tJ79c-GKjkEgaM1B>`y_tK{KEz( zEG*i(PrBi5a`?>qWlxh8B-_#2-k=$&FxIoQy{tIxh$(7=lHR#SXk25G4je0*ctucT3&7S5Ni&ZwuIH$dBQjkgX_%kSGC zm(1N(3J0Z+ODy|+>72GV83$1OV9Lx>OkdymI+X9@5HqMdjTi}I(U3aKZWd_S<%p)q zc$JsC-{1PH;r-z4txQOM*Xi+I#87@+ETcOw+`G6o({{;Bn`4xhn~h4rVdSqJJfFti zI0Qz59aQhf4>*U$gVYEA2r?^0xQo{Bt7pip!QD+(LD>%eg70SHJC;(*b~R8hbL$dC z3GXS&54DT#^BoxQlE+oPa~CydXX{K?@j}7SdiRfc`J#S6-MQLV;S~DG5YB1$AVrqq znr;m?Ttjt_!Gaw|)FEe8*uBiAZzmVPR9NWlgK6U9h1qt>O47*9Pfx*lW~Q%K5E)`d zV`QrbTB>|3NfKAw zCswEVS7v`~-h2kyRKdv0eKP`VjBE#DReZ)V;M}`v63d#Mfae?{%naQDH&%EDoluO5 z^mq1t08QQ7P0lt|cbe#X>^Gw>esKg{+$-kebWQ?CrS04GDu3_Zh7G79zz;_WAO*jh z|=kb?s$CHBr*OhAJIvTKccwd0}NRwHj5Gk)GUO9~Z=X@}2P3{}UgG9`gPrTe zjjFYd85ePj%%3jFThV~93OHI^^tS8LmCrsOuAU%%br{d>7**&OUu>og=Pj8(={i{> zW|h&PGrd-t+duhycl50~z%lu8D%_y_B`Q-Q>OfZ&MN-m}ca1uWP z6}<1TMU9fXiI=KGb~^b(BX70oGq(L5Efj@waU~B=1g}ZaDA>A8(MfSZZBVCzsRo?o zJ!}(LZ?x?{K9&|3c*@Oje2tqxo0=LeWsfRs&^N$+1U%3QDwm|`J3Q(BNTXO>Uy2Tw z{sjp1!WaXAcC-3-(Bt()P1BqOtjqB5jT|yn;0)*U70T4}hpgvWbrLt~s&hke!c%(% z4QSevPgIcqpreK%p}gI{6FPXEqF%eHa^Jx%-;vjTUY@uk5`Pj`w}Pi^BFw`VX);sk zqBARGQF|(at2v3{%n>Xg5Ga~mEcYlbYec;FK(U@f2+e%$38An;=k2gaD83(07&o|l@C5T?4xXd*R(DtDu_e;jh*>RKWM9B}92*F)3(_ zQ_Bz!b@u_B`lwaV2kLR!wa04?LeFaXo%B9>Bll1LnSXnaE)H^nbd{Efq2BAR4sBq^ z>gEbNQ=_R(tzmi_PSX^PGrm@%vpTw}V^2smA)_Uc&f-&g9eFEKPe%Ih{z~@wGr1jg_OHR=+E? zK|h+?7q4~ys?4`RcZ9scsH-WQ@`=W$Z)X37pZBC*nRTun<1LNj_G=3{`Jvs={gFh z{^_|LtNP!*`TJ2+{5rb`wRuhRH-guOIp^ zuL%5ziuyWDljJGC88Q3MZvla1m9GK)M5!Rlzg6?^R|H;!HV{a?16S#}KmHFgb~6Do z@}0+BLxum8@A_^10$OqHp9u);x{;#_J|!j R@Q>2&$Vn+nmWUhr|1Sc_55@oh literal 0 HcmV?d00001 diff --git a/Svc/Framer/docs/img/top/tlm.txt b/Svc/Framer/docs/img/top/tlm.txt new file mode 100644 index 0000000000..11ed0e9ff0 --- /dev/null +++ b/Svc/Framer/docs/img/top/tlm.txt @@ -0,0 +1,6 @@ +chanTlm +PktSend +0 +framer +comIn +0 diff --git a/Svc/Framer/docs/sdd.md b/Svc/Framer/docs/sdd.md index 128ac8e56c..569fe1c408 100644 --- a/Svc/Framer/docs/sdd.md +++ b/Svc/Framer/docs/sdd.md @@ -1,46 +1,317 @@ \page SvcFramerComponent Svc::Framer Component -# Svc::Framer Framer Component +# Svc::Framer (Passive Component) -The Framer component is used to frame packets for downlink. It translates between the service layer (typically TlmChan, ActiveLogger, and FileDownlink) and the driver layer (Drv), where service typically deals with F´ types and the driver layer deals in streams of bytes. Framer serializes the F´ types into a stream of bytes and adds header/footer information to ensure transmission integrity. As an argument to `setup()` function Framer accepts a reference to a `FramingProtocol` to do the actual header/data/footer serialization. Users may substitute the framing protocol without changing the F´ topology hook-ups. +## 1. Introduction -## Usage Examples -When using Framer component, the manager component (typically a service layer or a generic hub) initiates the transfer of data by calling bufferIn port. The Framer component will perform the serialization per `FramingProtocol` and will transfer the stream via bufferOut port. +`Svc::Framer` is a passive component. +It is part of the standard path for F Prime data downlink. +It accepts data packets from service layer components, for example +instances of [`Svc::TlmChan`](../../TlmChan/docs/sdd.md), +[`Svc::ActiveLogger`](../../ActiveLogger/docs/sdd.md), +or [`Svc::FileDownlink`](../../FileDownlink/docs/sdd.md). +For each packet _P_ received, it wraps _P_ in a frame _F_ +and sends _F_ to a byte stream driver that downlinks frames, +for example, [`Drv::TcpClient`](../../../Drv/TcpClient/docs/sdd.md). -The following diagram is an example of framer usage with chanTlm and eventLogger: +When instantiating `Framer`, you must provide an implementation +of [`Svc::FramingProtocol`](../../FramingProtocol/docs/sdd.md). +This implementation specifies exactly what is +in each frame; typically it is a frame header, a data packet, and a hash value. +You can use the standard F Prime downlink protocol implementation. +This implementation works with the F Prime ground data system (GDS). -![framer_example](./img/framer_example_1.png) +## 2. Assumptions -The following diagram is an example of framer usage with a generic hub and TcpClient: +1. For any deployment _D_ that uses an instance _I_ of `Framer`, the + framing protocol used with _I_ matches the downlink protocol of + any ground system that receives frames from _I_. -![framer_example](./img/framer_example_2.png) +## 3. Requirements -The following is a typical example of Framer usage: +Requirement | Description | Rationale | Verification Method +----------- | ----------- | ----------| ------------------- +SVC-FRAMER-001 | `Svc::Framer` shall accept data packets of any type stored in `Fw::Com` buffers. | `Svc::ActiveLogger` and `Svc::ChanTlm` emit packets as `Fw::Com` buffers.| Unit test +SVC-FRAMER-002 | `Svc::Framer` shall accept file packets stored in `Fw::Buffer` objects. | `Svc::FileDownlink` emits packets as `Fw::Buffer` objects. | Unit test +SVC-FRAMER-003 | `Svc::Framer` shall use an instance of `Svc::FramingProtocol`, supplied when the component is instantiated, to wrap packets in frames. | The purpose of `Svc::Framer` is to frame data packets. Using the `Svc::FramingProtocol` interface allows the same Framer component to operate with different protocols. | Unit test -```c++ -Svc::FprimeFraming framing_obj; // Framing protocol obj; -Svc::FramerComponentImpl downlink_obj("Framer"); // Framer obj +## 4. Design -downlink_obj.init(0); -downlink_obj.setup(framing_obj); +### 4.1. Component Diagram -... +The diagram below shows the `Framer` component. -Fw::Buffer buf; // This could be data from bufferIn port -downlink_obj.send(buf); // Send framed buffer to a port connected to bufferOut +

+ +### 4.2. Ports + +| Kind | Name | Port Type | Usage | +|------|------|-----------|-------| +| `guarded input` | `comIn` | `Fw.Com` | Port for receiving data packets of any type stored in statically-sized Fw::Com buffers | +| `guarded input` | `bufferIn` | `Fw.BufferSend` | Port for receiving file packets stored in dynamically-sized Fw::Buffer objects | +| `output` | `bufferDeallocate` | `Fw.BufferSend` | Port for deallocating buffers received on bufferIn, after copying packet data to the frame buffer | +| `output` | `framedAllocate` | `Fw.BufferGet` | Port for allocating buffers to hold framed data | +| `output` | `framedOut` | `Drv.ByteStreamSend` | Port for sending buffers containing framed data. Ownership of the buffer passes to the receiver. | + + +### 4.3. Derived Classes + +`Framer` is derived from `FramerComponentBase` as usual. +It is also derived (via C++ multiple inheritance) from +[`Svc::FramingProtocolInterface`](../../FramingProtocol/docs/sdd.md). +The multiple inheritance makes the `Framer` instance into the +instance of `Svc::FramingProtocolInterface` that is required +to use `Svc::FramingProtocol`. +See below for a description of how `Framer` implements +`FramingProtocolInterface`. + +Here is a class diagram for `Framer`: + +```mermaid +classDiagram + ObjBase <|-- PassiveComponentBase + PassiveComponentBase <|-- FramerComponentBase + FramerComponentBase <|-- Framer + FramingProtocolInterface <|-- Framer ``` -## Class Diagram +### 4.4. State + +`Framer` maintains the following state: + +1. `m_protocol`: A pointer to the implementation of `FramingProtocol` + used for framing. + +### 4.5. Header File Configuration + +None. + + +### 4.6. Runtime Setup + +To set up an instance of `Framer`, you do the following: + +1. Call the constructor and the `init` method in the usual way +for an F Prime passive component. + +1. Call the `setup` method, passing in an instance _P_ of `Svc::FramingProtocol`. +The `setup` method does the following: + + 1. Store a pointer to _P_ in `m_protocol`. + + 1. Pass `*this` into the setup method for _P_. + As noted above, `*this` + is the instance of `Svc::FramingProtocolInterface` + used by _P_. + +For an example of setting up a `Framer` instance, see the +`downlink` instance in [`Ref/Top/instances.fpp`](../../../Ref/Top/instances.fpp). + +### 4.7. Port Handlers + +#### 4.7.1. comIn + +The `comIn` port handler receive a reference to an `Fw::Com` buffer _B_ +and an integer context value. +It calls the `frame` method of `m_protocol`, passing in the +address and length of _B_ and the packet type +`Fw::ComPacket::FW_PACKET_UNKNOWN`. + +#### 4.7.2. bufferIn + +The `bufferIn` port handler receives a reference to an `Fw::Buffer` +object _B_. +It calls the `frame` method of `m_protocol`, passing in the +data address and size of _B_ and the packet type +`Fw::ComPacket::FW_PACKET_FILE`. + + +### 4.8. Implementation of Svc::FramingProtocolInterface + + +#### 4.8.1. allocate + +The implementation of `allocate` invokes `framedAllocate`. + + +#### 4.8.2. send + +The implementation of `send` takes a reference to an `Fw::Buffer` +_B_ representing framed data and does the following: + +1. Invoke `framedOut`, passing in _B_ as the argument. + +1. Check the return status of the invocation. +If the return status is not `Drv::SendStatus::SEND_OK`, then +use `Fw::Logger::logMsg` to log an error message. +Don't send an event report in this case, because downlink is +apparently not working. + +## 5. Ground Interface + +None. + +If an error occurs, `Framer` writes to the system log. +The rationale is that if something is wrong with the framing, then +downlink of events is unlikely to work. + +## 6. Example Uses + + +### 6.1. Topology Diagrams + +The following topology diagrams show how to connect `Svc::Framer` +to a telemetry database, an event collector, a file downlink component, +and a byte stream driver. +The diagrams use the following instances: -![classdiagram](./img/class_diagram_framer.png) +* `comm`: An instance of +[`Drv::ByteStreamDriverModel`](../../../Drv/ByteStreamDriverModel/docs/sdd.md), for example +[`Drv::TcpClient`](../../../Drv/TcpClient/docs/sdd.md). -## Requirements +* `buffMgr`: An instance of [`Svc::BufferManager`](../../BufferManager/docs/sdd.md) -| Name | Description | Validation | -|---|---|---| -| TBD | TBD | TBD | +* `fileDownlink`: An instance of [`Svc::FileDownlink`](../../FileDownlink/docs/sdd.md). + +* `framer`: An instance of `Svc::Framer`. + +* `chanTlm`: An instance of [`Svc::TlmChan`](../../TlmChan/docs/sdd.md). + +* `eventLogger`: An instance of [`Svc::ActiveLogger`](../../ActiveLogger/docs/sdd.md). + +**Topology 1: Telemetry packets:** + +
+ +
+ +The `chanTlm` instance sends telemetry packets to the `framer` instance. + +**Topology 2: Event packets:** + +
+ +
+ +The `eventLogger` instance sends event packets to the `framer` instance. + +**Topology 3: File packets:** + +
+ +
+ +The `fileDownlink` instance sends a sequence of file packets, +representing a complete file, to the `framer` instance. +The sending happens in the following sequence: + +1. `fileDownlink` sends a buffer _PB_ containing a file packet. + +1. `framer` receives and processes _PB_. +When it is done, it returns _PB_ to `fileDownlink`. + +1. Upon receipt of _PB_, if another file packet is available, +`fileDownlink` sends it. + +Exchanging the buffer controls the rate at which +`fileDownlink` sends file packets. +It ensures that the rate does not exceed the rate at which `framer` +can handle the packets. + +**Topology 4: Framed data:** + +
+ +
+ +`framer` allocates frame buffers from `buffMgr`. +It sends buffers containing frames to `comm`. +`comm` processes the buffers and sends them to +`buffMgr` for deallocation. + +### 6.2. Sequence Diagrams + +In the following diagrams, open vertical rectangles represent threads. +Vertical dashed lines represent component code. +Solid horizontal arrows represent synchronous port invocations, and open +horizontal arrows represent asynchronous port invocations. + +These diagrams assume that, in the +implementation of `Svc::FramingProtocol` +passed in at initialization, +each downlink frame contains a single packet. +This is a common use case; for example, the F Prime standard downlink protocol +is implemented this way. + +#### 6.2.1. Sending a Telemetry Packet + +The following diagram shows what happens when `chanTlm` +sends a telemetry packet to `framer`. + +```mermaid +sequenceDiagram + activate chanTlm + chanTlm->>framer: Send telemetry packet P [comIn] + framer->>buffMgr: Allocate frame buffer B [framedAllocate] + buffMgr-->>framer: Return B + framer->>framer: Frame P into B + framer-)comm: Send B [framedOut] + comm->>comm: Downlink frame + comm->>buffMgr: Deallocate B + buffMgr-->>comm: + comm-->>framer: + framer-->>chanTlm: + deactivate chanTlm +``` + +#### 6.2.2. Sending an Event Packet + +The following diagram shows what happens when `eventLogger` +sends an event packet to `framer`. + +```mermaid +sequenceDiagram + activate eventLogger + eventLogger->>framer: Send event packet P [comIn] + framer->>buffMgr: Allocate frame buffer B [framedAllocate] + buffMgr-->>framer: Return B + framer->>framer: Frame P into B + framer-)comm: Send B [framedOut] + comm->>comm: Downlink frame + comm->>buffMgr: Deallocate B + buffMgr-->>comm: + comm-->>framer: + framer-->>eventLogger: + deactivate eventLogger +``` + +#### 6.2.3. Sending a File Packet + +The following diagram shows what happens when `fileDownlink` +sends a file packet to `framer`. + +```mermaid +sequenceDiagram + activate fileDownlink + fileDownlink->>framer: Send file packet buffer PB [bufferIn] + framer->>buffMgr: Allocate frame buffer B [framedAllocate] + buffMgr-->>framer: Return B + framer->>framer: Frame P into B + framer-)comm: Send B [framedOut] + comm->>comm: Downlink frame + comm->>buffMgr: Deallocate B + buffMgr-->>comm: + comm-->>framer: + framer->>fileDownlink: Return PB [bufferDeallocate] + fileDownlink-->>framer: + framer-->>fileDownlink: + deactivate fileDownlink +``` -## Change Log +## 7. Change Log | Date | Description | |---|---| -| 2021-01-29 | Initial Draft | \ No newline at end of file +| 2021-01-29 | Initial Draft | +| 2022-07-18 | Revised | diff --git a/Svc/Framer/test/ut/Tester.cpp b/Svc/Framer/test/ut/Tester.cpp index e03f6aa2b1..9b903dfe36 100644 --- a/Svc/Framer/test/ut/Tester.cpp +++ b/Svc/Framer/test/ut/Tester.cpp @@ -125,8 +125,6 @@ void Tester ::connectPorts() { // framedOut this->component.set_framedOut_OutputPort(0, this->get_from_framedOut(0)); - // timeGet - this->component.set_timeGet_OutputPort(0, this->get_from_timeGet(0)); } void Tester ::initComponents() { diff --git a/Svc/Framer/test/ut/Tester.hpp b/Svc/Framer/test/ut/Tester.hpp index 446edf6656..16a36ce7dd 100644 --- a/Svc/Framer/test/ut/Tester.hpp +++ b/Svc/Framer/test/ut/Tester.hpp @@ -14,7 +14,7 @@ #define TESTER_HPP #include "GTestBase.hpp" -#include "Svc/Framer/FramerComponentImpl.hpp" +#include "Svc/Framer/Framer.hpp" namespace Svc { @@ -95,7 +95,7 @@ class Tester : public FramerGTestBase { //! The component under test //! - FramerComponentImpl component; + Framer component; Fw::Buffer m_buffer; MockFramer m_mock; From e3433569f1ca21cad94f9ef6d0d3a902a65dc871 Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Tue, 26 Jul 2022 18:58:37 +0200 Subject: [PATCH 038/169] Switch BufferManager seq diagram to mermaid (#1587) --- Svc/BufferManager/docs/img/SendingABuffer.jpg | Bin 58709 -> 0 bytes Svc/BufferManager/docs/sdd.md | 13 ++++++++++++- 2 files changed, 12 insertions(+), 1 deletion(-) delete mode 100644 Svc/BufferManager/docs/img/SendingABuffer.jpg diff --git a/Svc/BufferManager/docs/img/SendingABuffer.jpg b/Svc/BufferManager/docs/img/SendingABuffer.jpg deleted file mode 100644 index f7c1c9ba2893345ce4b2c8e58256a6a008eea906..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 58709 zcmeFZX;f3`wk_p_(p z-uprRLC!;{x;PzlLM&Oj1aScVL&%2_4u~cHhp(TD{2wl{WQn{Lp|*1AZwkv5mTW{U zRa>HpSE_8x$7Xq3-|D0&x}daQml;}k(Lj=ks}T)NEu|H zPMU;Ww62s^kU!Uw+c4y*8Dgj$abHaw<;P(Hhr5Pn*tAF1oi)n7X~XQ&9RMzc%%jN> zjr8fG0#wRwb;x8NFwb`L6NNm1lrP>Mnjr1&m1qj0)Z|8+0G9h|E< zIn#mB1&v3k6!)9O6Fql$_uhDAmt|Fsp^{YFPC4yIDfPx!4Bk7w0Z+|TJ zNTCCFhO1M`b)MQA^zC>uwHv=L#yiin1MRe}z>;p$x&2H2unTGm1%=|Xxj(41p?Nt% z8TY|Rjwnx{{))(4M-F2`7P#pG9(izHlzY7m{|HARt(EnV714fTM3^l$m3Ru|wj(tp zd+tlLrOz?HjSw8#p0O84D14gAIK~jF55Et^`$35Uq|!l^?56d+lJFxB!M=hl(k3YQ zz|)>M@t@Qr*LweA>%Z^!CdMh#Lp+;vS>LUETSL~D~H>fEb<8v}xp zzpdfl{ezl@3PDbRcRq#b#j{>_Q4{Fw9OPj`OJ+kfP(|E2#;$HY;F4F}etWcv!uDhN z+-Y8zeqW=v^X+z>u#s0@rAU2$8}xqDlg3IhuY5M>I_@q$mBu>Rcfe)W zok}6*=~nY%-sh?&M}xISnv}88T%%QrnXFeeI^M-tXDq*hw2R!0A%}A%7TDudSpyP*NZ0%|$jx{%8f&1%`lmSugUjSx)~3B~id zij)2{s-+5oV8UZ$wQLB2sspZfXrDjxY`GkfY)PZ&Xg7zjezjA%=+bj)WbzO^~by zPu17=*8=o?-RKA&Rt4(e=sB}j5#v`d9&lgsx>871J+bDmMQ^KPeXU+?!)>GcKG?l| z^g63OCxlXER)g`6K9WBdbn%s??6J^+HuTc*)8^_+0awLOo^Ija?aec9)QiKOpB8gJ z_S4f{3X3b!qSQ6b)bbtY{Unx*&ZtG_uIWTMB9%U+CP%z)cK#I+pG>ReNVLj@CA6t= zv7xLV-(W(Si&7ac-7CF}jg%vXCIu)KD)}7IreCrP#2$jwK^0zP5o~X^&Z2%wln|)^ zB_Hm={Pw0Ca&EgSam;e;**X_!PtJJOm}wPo3FZ4<_7IGcXi)?M?PNt_M7PXJ)`~F( z@Y6eh+)0sXUtQGYQhjN;%mA9)2bJ(thKq!U@Cq`$un|3ogG`lR%g>bV1_rWf(9RWv z*KMWSftJ*=fXM`_CR=Crdaw4v`=s4OAxqviy+juZ0@g@4r{CKJ*YowU$UiVu{1EJU3bj-5Y+IA$rd6QIK~OuHwDAMv z*IFAsw6>WylP=S3Ix~k`4n=u&#|2l7YioH`ai7=1R>-Rv7=q!bxeB0=3 zx^HZ_*|oyE6$##9eH8S`r_A5wh=0w>=K&RoR>(n++YzYU9;6EGHR&KHdlGtD$tzIU zGuX6vt_JE3sM3MdldJ;@I$creBf3y{1mMLsRPJV;+FOYZ=Xb4PcF?p)@BQO*W3j4X zNp=o=<1R|XZSZtiVjCIoWn_++KoP)XryhMOG~^akBq{*3r!qhV(LUfKx$eTvdk|S* zMVU^05T>V{YT1>8*$x}lLHZ}6N*~EE2P<1gPJcx3YA3HhPHmeXij}Q>0+O>Uo&t8I zvt|C8q3>fSV*ENspI$I@&-XvapuP=#)!>m_VfK(t3_4}6X?`52aaQ*)F?*b2?os`+ z%j_zhQj_^WNGVTi_u-tJ@U3#O1PF)h$oB-*g0Rl>Ipi9Z_CS_q6_RCH9lXO zlOxucgGI8dv*I9FvZ3N--xA!(B0yFGVJG|0M{>l7Jq&k33`b#p_oci z&mx&ZROcg?%ifk^nxKonL0Hf}DrqQnzGG&c#ya4!}8Ov9t!}@$1lT zz^uQX)0LW8+dTe_(VI1)?P)5zU)QegQTDCl>ydq5ZSn5-GS4=3UFCn&cWq(kY4!G# zJ1n<<@b5KuZ!|t*-Dj)0A%lJ5X}}GnB|UG?lUI3W!f2gWA69GHn1L0(#gCw8np=*K zpA0<#T7?_idv6H5=RC~(g^~Zt@GqjKmBkmskSk>hvNu>wi7qh7A4_lY660R;Z6ruO zISX$X(Xxi%=X{-wSB{IyoE`ia?ytfkXJfUSEUl z$u0mnX=~Fy!L;%icL*yQf^LG&vQ=d9URl2!QJc^0h)QZPm)=ER5-SIUinwc=b^t{J zTqjBy@)Bi8Z^_gkBaWdS;GPB6vh*6;oAI5yAY8}Lx2#)XBx|6_Hm>BeXy}dTX2r+h z`kF@Xhkg8Pg02_YKP|f8vrnjr?yKD3o57~Mhd<~#dt46sR91Mx$#vCT9(|8j%EFoc z3j7*pUH3bu(%7SYG5(tM9@R+|P8A_On;D8*JPWp(Rl0xM=CYm08K(V?P( zofdnAosYyDW$%K86lzoGeNvyV9I>iN;XdiTY$aq4P(_&lv%NV=vuDC)2^8;?LW1v98fSv%GsC`xm@ z0bZ#|lg|nfXaFdd@)jegwgyrWwp0mhWZDG#Q%-f!x~H`)D{KerZ8gtjZrh%fyZL%P zGQzgILdjsR_ncp);D*^9^)RZ{nK>_3UlmT%$I;0KTm4M({b1$E=(=;>bdBPt3ni!0 zb8KXyik0;)#glLIm1s=zzbedQ0dhp!IWHDT6?!hT2oRltk_C)3L z#)E-l*`(hln2*9C>H$z7Iah}t9B74QgHg2ZROT)t(0w3_YJ#(%fGtL94Gx<@6c%!| zRn}h;qfimHvnz{MCx(V)t5W$EcrV!8@t_H3X6Sk6$a-jjM@wCtXLaQ?JY!sLSx@>K zUpK&6kK#Wj+Cw)1f15O_Fv5?IO7iL~O=38!Sux1hb92@xMJv}`R%IHET< zsuF_y*q7sy2YPv>8CK|-HBI)@P4~IqV|BB7tAp~l;M82!W|nB8-Ssq|E);(8O5uB| zv7dV7MQ!O?<)UfsIYzbG7B{`YU0qb#S>Yb1^fEI?DYbDZwf4Xr$Yegqo^)(?ocu-!LI|GxkK{1H2Vh@0Y$aSHoUKcp_Rq;RxLvl z=!yVkAXx=<0JNY1B37`n#ek>_TBT*25c@z#;XwP$63E%338ZDVXzr^SZ?Fxdr_Yrb z3F2}at7FV!@-F5Dsk>B)W{DKoc23vvr6*&1NVrfYL{H9I7 zU=H~qV_F|{<&8W7-o6$nrbvtgM&cc?M$PBOU2GF^nv}F}gIjGF>N3jCK zeS63aGNUt#cAYiCHQFqUF>Qac>qGGEqX$qk+Cj)vB`)D3p)K4_)Swnh`wYI$ITIU> z%4BL0y();my>HQ$y+JmNwIQ$2R>-!}GD^`9r%a;TD~aJp4XKOtplAVdaE60_{H>@O z8fz=0upM|RDG7I9?Mo1I5#%ib48kUIh)>9ye6YhQlny~!v>P-i$$C-~C z+1PBok>tBXH6|1w2-J55mIZBp0+>+Fk~VU{gx4Hx%+`1HuBV|ml`E0_0m;79u!&Tg z-eNO4UR1;ulo#ivM4R1+LJ3|Hz!u_N3^u*)T;w6^odju8^47=yb+BhYhjQqWQW za0D|`FYgeQ@CKy6ThyiZNjj4WCY(fMw#t2?4cM6J#TxQULq}H(6RiL}0!olZiHNz2 zhq|2J&Eb%cUi+jc1qV>sWP`S-OZWU2b+V0*?LLwDYQkn~Gh7m7B!dRkc`(4XFEJoss@|Pd{XtiC;CaRtU}xCt+1J~V}&OkJKH#I zb3aEf3f}(oQo^5K=nm@X1e1)dNCT@qCnw(1okxyjulw7y@8H{lzMzO3pI_biWVNU5Qj8^Q z(#CkI+%x`*XnS@20T)_bmS452`kb|sh3$3rCA?;aDE3p|o{`dZ_dK%~PMNIr6^w3? z^^;jHlGAd;9inW23Hg)SkW&5LU(os%X2qW5Hcyh#SMFoQ4pce~AyXebBS&aQVphX+ zv>VS{j?jm?hb+|Fp3x=h&jlCCfn;AW_02;-F(X3aW0Ee(fVp#SZ!8SV&97=G3g$J( z2h=|9e}MM7E6D-qG9_K{1z8tfUAB#&BD&u22;vK$$}ATuFEvQ4W&#xT-S@TjMDZWKGX6WP|%KCN5JDjmCQOk#h1IhMemGE zsZX|x&}?5kibqn;#g5)+-__v~X{L7mKJd0=_nlGy3iKhMF03=}^eyno#m1={8!MDc zlpeC)u`5lx+32X+&w0mcE|;#ex%s4lwkbF>&d6rg@xI-WK;NpAicBfP|HYv2N?mVq*yuPGE$jjEeQrgI=H$Mh6qrOV7bZ>a8U<_#cF&i zVjRCB4wcqb12GR%I+?Z1%$hj6C|^+J@|1e}vj&Qw2E+BZHXgfMgk1@Z2~zNY2R28J zP_n{h*mk93RLQK(lBG~RUnOm^fYP))oKD1mEzKZSSa7)spU9t4KSNUQM#oi$%FMeZ ziu@Y;*+U>RLvmCr|Gq<|D}Ow;WVbZ7`e2RTUqoMR#h`o_A24o5?0Dy$iw1@&Oa40T zW9+-L{($`h{cR6`p2K<3N_P!wb_0F5CRK=|o+zB5B~+TPmHv6lh;&ps@VS z(zLo6lMb4aj9~OlSv^ zf0-CfImi*4LON-pc(^VbC5<8v`L;CQIrv@sm!JL>5g+vacjSg&*vv2OXl`0#$$u^W zKf9d1{}Ri8Y0G~Z(f?B6{(s!JXokrV^>F-ZGD4+3AZ?U&z;973sxm|qVBz+HiZDtQ zN*3+uuTxP8mm_p!#t@Egos6=2gM~50bc7JEd$9ba5T*B3>sd+X6~5aAQTr=F;w=63 z^12REALCDE#LR*bMj5UcHNyabC`U{t%HH_QO(Qfs91+A+v5Oq>5>9S@-WeQ$dgO>B zMxv1#+K__CLV8n<2y?R+`asjbfK0tw%!Esbx^Qx)oJEBW5y^boE*@ukC3+)MTcSTo z*xM0gn2P0ZGh7DTk|R+kwjbphx$m3}-j{PR{mHq}CdcVzGWBqDpA+0%N$ zLwz;h?m!H%kgPZYah#zTY`fiF0VN%y(*-Kw(nzMzYekl82GM}4+vLi(2oU5g`W1+1 zT5sZ4TYJpofmGRu9P#5k^Rc#UgGy(V>@O?iFKEY_7rcw5<34$GU(fjp-}7!RKAXOc znVKGS@rTMiSn#9($tfU&!-PU!yVBA} zmXaw0i_4xBuyI-bjmeQ{FM!@=0SNg_Hd&Lny$_vu5$NL3v?RK`3x@08$xwu`cFabo zC_Gg2{#ZxUrQlQXQIr3wguIQ-BG1!J?S0H_`;1rFJj)LZgDAd{7JGW*z$5p*oo^~R z>y}V6+h1k6zsj?q_Dh9(&?`z`Rg67q@WfM7&&B4w^q0#nM$rJE$4mm5}L3+ z5V3GMg=Erg4A3&S$&ir4l&#~NV$q0d@`2qg%6OH43IC>q6y#bg@0uL(P`jO>0MYpK zDJ?6wFK-jNIAjHq5rOUv#&@D}nW~b+8YoM28Z@C01AwL7^8zYWwwX{M@PhX8cR%L` zYE8Cr*Iw_)0K~XVJEu z)Rq>1)uumsKDP^uvsg~!+=4Y(d5^rcdZX9nhY{;HeIBN}b>0cIvFXnb^~uUU7WP_A zDfZF2%EG$Qpb|ar$vvAV+VgF2h1)ZOIKXQjzMYv|IM%7MjtCcXBu0e;9A?HmR+qFD z*7gV}%MW%n41pUr1#QIJOI>%VD6ntN)lKK;!w;C4&+az+vk$PjgkENjE7ivSl+A&i{7v z4&=<@uKU)a`$pKT?fl+yWh_@U;2>YRE?|uup$Y@v$K(u>7QvPGwgPB4KwJ*Dc=!eF z)D*l*L~N9y#08j7hgH;?7sR*=CG&oiE(gD)3fJ%DkW@h$D<|H$dk%&phv08zz_t1e zy-50rsD#q3p*yGGCkwur_LrxpuGa?2(pmh; zPFidA;c}mC35W9tWMy*OPV7nY%6-6uoi%@RZB?Me48%Ma;#Y*X?0{Z^T>`~S9!SZM zBjCm(x!x~bf@45T4t`yeqkyV6SvWSW03`Ce*foBh-~)z0zvz<}i#b^PLWbB2P28TVLb)&SM3TJ#EWAGx}{(akG3a)1)Nu2K!%>!u5jT@ed7{Ai4U#gsIDXB}@ zxzIgrh0Ti-+ov1TSUrD-_Ry(x*R?ZF8sMMh4wI_c8ezRGe)Yk`v)c?SEHqs*Yg{JI zi{_#=qT|dzi9-bs=fe8SGfD!)2mMlAAnJ&VyH}ctwo9aU^pV22SeY@Y6T6hO4Kn9( zlF(6ff^1}%w{%>{4}sg-#M2N5(B_bI#mM9eK=V^`BNd}SnB_CFxXuGjCehL51S-pO z634GO-@V_>`QVe?4G~dA)o{<{@wa;Mb_gfhQ`8#tTMssbxg-eE_X4a_nk>K=p>;C) zAn%hazaTfZD+8+%hg6dI!o{}rDuNlxj6`1;sDH4(Y4625(6?@(tL)9=o|-?XE)AI- zUcXYXUuqrQw%*LQbmRHR`a|A3daCP2vnxEULQg);FJ!pf5BALW3GFTpHjA{_{IJ}m z)Ud?N@_1EGIc2eCOSSl~NLc!UYlU8g7TXJ|@HR7J`xr5BGn;6TN;)AXsCxF>b!>z!2I^{ETZ)AM~ z5T7wOv!?A1=gvgqjmL{f3OpZ0dyGtx>@6d>vY0DR_MrFjX)9%amo9r(_o68p+OMV+1`|0>Z4K;zEoEb{b1M8 z!CehywGI_@l5-oGN)qf{BKgVF=MWdwPELtOuKNs~0<8U^M;8+-M+mcQ=5mP%52XfW z&iM9!i>g1mdBBR&@`F6&DvAZ^owy9_qXBl;63KpmdAS}xh!>@_Ky8&r2#tJMjZnIm z)3Of4w&AjnOVOdc=f>}48;Iy<04@E2#0ZS>?kIg0)^$98 z|Lry$l29Ue9IQNF`X>`y2~RcsXoKrq|0}WDSLs#FGi4gSTzFGr5B6Fm`aS`(H}-GS-pvfJwrrw_=Zj)pBzW8;bZj!2wl8JHg_#N9OSRaMh#la)>Y4_ z6B5WelLg?Uo^cuQw0pYAt&DJep7Sp&*!^--$B~`U31KCr*F61ed@3}00xbWsEFH(< zEqf&T&X-ASq@qj-suhJopTyW>!)K7X7zG?-9J?F^E56#BGU&AfICeRfIvB;%z8tq^ z7ds~O2JqGP^@LtripX~C!~JOsxA~!deb>!7$0-lGnY?^C;t{3@o(!>X0aVyrJ)9uW zx?K;A*#%XIak5^fHp!fzeF(ZFsKIiAme)ahzyblKldMfV0_n>UE2%kkIr^QpYdCFO zUC8h|r^A0UMWFG-wk79okpCj}U-sJ`8f9L?`?mDeY1e0tR*9M6Q_{Im(zM_GGRBi? zACJdXn2=3(ZrypBzh_U6XPu{>$3H#lSOW0h%t?R=#e6~M|1G^H!Z4Sp)F+BnuLLVQ(c5-tU zk?jkZ-;PR9Pasom_NM?|S`N6A!{elrOb-HuqfJZV!Ch>_C4K0)ME;A2tus~&L$A6I zBrqU26^J4)?!gbj!BdqYgvS&Q=}~`4EtVrLuJkJOO0`vO?@1Z3+>ln0$;hpsq?{sj zrlKRw)wAg?re100YIrrBdwpT#q3Ryd|dNt>&_v|=yJM5yiEN9229eoSMyH*X8Wr@s<7 zQy$=6fk_8LpXdWbv2kip0gu}bSGh5(-;)dpSYiCn?l_r(TrJrrL}}DK$SRXWOX+e% zsF=Dkbg1Q#0Gj@RO=YgK!lvPuk#q_1tReSg9-eX`)cDh9TEM@Wx%a&Tj}+k5GD;Ha zqjf6bB6D--t9t*;T&1HCn4)XZUYc`LccnDS$^H+7}=sG5DsjP6f zPPur3N-wluqnDICZq+f%8qi=EK26a~RPjkY16O%eIb_^)X0jFGqy2 z1E#qh`V7UAM9~##nIwwGpa8_MKJ{Y|y_{$b9TieDOE*G+z$DAiYT#tUfK`+d!Mtrq zJ57#gIBQwrKH%EW^u8|R?8O;BZp{*WrNb&b!1pHYa&UeuK_VnAPFAm zl58rqX@Q*iv}IuljT!cYlo8H-M@>P3A{+m~TyzX7Gs!?n9C=Y1p%`P(xg*d-7&kzb zt(TmHdVm7Bi3z$o!O)O7DB^asEQcz9=K}3yI0)K2X@)HL7TWwy=3PjE-J!nb6b;~BAS+?K;tD+6v= zZRsv_@#ghEsP`Q;@hy)bWVk(j`4oNZ#A>hW5wqw+rafsJo{P`)q=dz6>DVUZ6--qD z3ZnB(P4J*KFwxaIP)KFb(wM8}l(PcE*^70Blq)2)Fq)cG*OKu@4qI>JKFZ2s?=h$r z)DP%u@;Yw}hGf;#w8H!u*>P{khs9PM%oIq}bx2xD4xPy$*LQVbGyHw4%Zcug9XyB> z4ebDSwISEkzwXNN7cpT$N?gI|w?*Z+C}AK;C}_+g2GkJu^}dCnRZMH?>PG-MEjFeS zD)M;NbGDwk&VT+_f{G)r!iI$7mJ_Nypr@dD$1Y+p-05Z|WlQk~0@dAsM#{Da z>&7KZfS5K#?|~YOCeb$cOwGt8!`DX#&>n)stN=Hhz$AwlT{GlA@n`XTbePP$hd zb29X)aH?^+UVM9!7riIKJu=kF1FeNpvp2haEvc|rBh0>7nCA%(BBs!FdRQknq|$x! zjC7p5fg>Naf>V=554KxAx=31k-`gNc&n%DO*#a>Y-BVBLdvl+~E?k+K05+cGkax=pp0I@>?{u z(4pI3{afnGYi`se{;1dR)bViCK>T06;Lg)DTuN-Bd9 z{uwpoCv&xysE^6s&Uexl+mH=&mlA(puHo_jg?B5K2h;6xbKF31u6^U}iV z$)N>h5nPkGwu{FU@8v=!U9v{zR3AR*-4aKQ!-_BPbqvXkD3~lQnaRP}W6Hn^h(75Sx1Z+kZFTko;rrxRWWw-G9;Bbqg@hyO^(l+56>Y4vJy#LX_A zDvWWg32C-z9$1N~+|o9D(3S-_g=jNbr;psVR8TCl#WJJ+^mAOz?=d zDJ*|K(E)pfGi}i(`6>dYQBTP?T{8g{AIi_w;MCCyNqmoA!C+H|GMHb8&bBH6FNf>i%N}?iH;B=RrM9WWvRqof1|Ep_?W0rKloMS+jHe>-Y%&=D8vn= zwi*dcT6gL!T?s7*S0-P*nuHB~d)_v9&vYw&+VA^oIRZ`zKR15=SkL~;uR(o1oB;CC z%!yrZE{zSx`gK$Zx`r|+lDw$P!Ln&NLa+fzlUR=ZkebDT*3|Kl0 zp~Ua4dqnhU?f<@L)={ZqgR;TQXtEsfg*EleT-Y(d4BIS66czxh$)8$?`;7oB&?Cgs zE8n<3<4o`8&U%rSjM)f9iBLMZV0xdVQk1oD3N~yx;=AMhZ$-ljxpKs7lq>?%bi3tH zpo8dkBvS*kgeq>NrH8;>k?Xg|d$7m8@2T>g5#5ejxQB;#ZkWT~wLpc!(6hq`Il|WN zw(KbRGgETabx+ptl3X!>lzhAt=t!(%h&`+&efZ14*ttlq+78&ausjpM#UEep-^bUh zli&D3D`2JZ9S2v-$Y9<_uQBFe0ar!lx|pE1^?mbWNxW=%fgCY=@yDpAKr?1pC1yA$D8vef<`tf4X;bm zC+>y1gp4%XZ&@IoWoScQ9Y{d&t#gT*_u7QiHH2#ZZp!Vi1L}Bq@UJ>F=EQ>`;=aC3 zHxjcf)~&$^57u9d^IFepcaH?G`MJy#R6iba`zF?$TX19z@uFi-*ydFw9(}!hi&Naa z_8iQa_nkgfq25(1M=VDp!(YAk44-t_a=Y@!(oFL&%ptshOeN`sB3JkDKenjW_e(B< zdu6K6tK|qiLgG=-DW5)mPGSXJ7vB74@gqm2V`SCyqQiwVZM%1?xo&>a@Gf8^@PMds zUHS#ngN}Rb3ZkBjb_&LiZ?BJzTli#Vw#}v3`|bi=$I;PRV>s`2{WX{Qh)tJF9Z45Z zo#dZJ77eY~!;$>SO}_|BzvwDw{eqNGbzP`3z5lZcfc9u^e_3w)@ca?7EEMZ-hS60ICls)5yygD%0}Oc4aj{FBNMZ|mI)Hdl zDQz>>kcc>U|3wF8xy1h51N!P5>X0ABtIg{LdiNT`k@Xexs9B5Xpe5534pvNo6Xh@E zu$&-MlCkWkmh9rTZpTg~6X8*puQ#Mi_AK_LKpA2WtfcFo2jbJo1ERkSO1TfV{D*hh zjyk&=Ms)}ldG_dhgeK5Um>1n9FH|BC9NfY!nrhd8EHb3A|GtVosn;0^o@;?kEd2$CjD}a`l11OtVQHx}o?&EO?|@su@VhsT|0YS5 z^pFAUY|LN6NlypZA0))7XtSAvvi)Z-gYd*s(uB)3`WO6AqT*_$V)dkzHox)3j*`c) zE|V8F4yc|O`GAi9l#DOkE_TX(f#0L_gDu;6v_7ee>$nmqkji|SRK!W8_ZvX zlS<~JDFvePNHRb4=a(Y6s$DXv$%2rndBX1>m-2H@h8gT#Kj5d_HBjR|;?3e{0q1|Z z(Zp#{*3s(3Q_vV(J~)nDXj&v?E|f)(!!~myfwarPCdluRWL0q->1hX5@(~%>d zpMxkg5|)3D`8y6BCwLN-QMwyi0Prj=yc#+jG~tyt@;+H}@XD4rtq-C2rI-x_vbUiw z$YjeAijaO#ujQve=9ws+ELSPg1vDOc6hc!DPZE6T-0N@xMf;xXX8z=*aW&~%)~I>z z#q9C+xUf;^t7pY3?`n_NON`x%)$_gxaqIWg>(Dos=^m^&)9L!D{&)D~Ly@0HYN^k!QmJ|F4#8yc8+UjE|EuBOdiXe;!g@VA7@fqY|o zRoZh(tdFyaZC>|)n)^`0w~-7a{fFP!HR1_4TY%MJ6}{ECi_zMZP8$$iHIyD0_bq@A zEbadwM`Ut&NbH<_%Z5^{%8(bM@~d5#UDICIZ}=}4tFz9JM^HF+5fU^;jzD`XDmoIC zXd2is6L@?fWsIi^*Oyb(z}0i(a)h;+BGdmNZ5@2m2EIA_b5EbG0ar`OUq;38Kj!{D zIXRt`c@E{62B#A`QL=E%_uDO6_;h5wdaw*GZv2c_`!E~hr&J`Ctz+Lg4w((5*3wFv zEKIv~J9+8~(E-jh-l5}#nWUlJ%@vW07s-i#*R!8E!=aurzn%F21!6{Sx0q7@F?rg; z7AAtjlx#t!hy473Hnvots-S~hH+x_M{JRSPgv;RPegfQo3|_N5w$DD`IM_9sERCiNY4~w67^L1qJ4wd>m?G? z(0zY19C|TW!5C2i7EyH~l=k}~4GLTPNsd6W|Ht_M{omt1QWi0bd49Xa4K6YLW8Ops z1M>SOiGz$;uPS6EVTQS{oGHF^=6_u7lifp|u>qnY%qG(N zJ%0N}SuYN@tbl(kD;AsFPV!QaG+B{V3(SU$zfz_~2^c@3Lz@O0^&Xi~y3rpra zex?Bj-k&~yp&<~C8zZnQfKA^&bKy-ab13IBJYe$_Sh>!Y%(9UcRrZFfdlrKx z>H#L~1Ka8r=9;}&hT3Gkp>f*_jJx9r&bcU}d0BYrruTIptjaAu7LsW3_g7Ah1x$Nt zH}1GSQP9oV%K2nUk1d4fKV~229Pul6Y2N!RuB!dMzArI2d0C!avA16u+>Q3u9dvx9O25myw3yVZ(n0gnkYQ{g0RCf*tR@ zn48{2TR_q37&x&FKBJj1_x0k$xm|_Q6O5N~#0vNjKa?d$oSGNqw<1O7XzI`A#(+IS zbg;n(>Z1wR>1h#Bdeb+^S=z9n(W8-34Ej@a@$utvoHB(L%iD?yMiS8r*-<<9=;Hna z6=3{B@Q1|M&Yde?)NE;M6#_bw1Ap!vE8~o3wn8r=rOF<2$T7MRI_C1l&#@eX!tU(j zYj0f{FI_N{&T=6N8?XOT3-_GxnpRKaE+w{3-;*2$xA)Xh)1HlG zPodqyqfhahH;y(PeE=o09=#M4Jz>^VQUuu6F|=?zchA_LZutG4uZH)w5jhh0OADd8NA&RY0U%AA!3>@>4Vi2GyR>rQPmuF~ll^V#537X~iZ6^Gi_8B4FH zO55{3j*B01JW39stNEw=H82nQ_VgdL+6Q!(*o>q|OU!;eA=T);cO7ym4bP-c=c%Vg z33^0aX%R6-$kZmcg~&|9k%m^G5_dVm0IqTuGZk_xVt{box2pTpBsl%FLJoEvYk?et z1^P3qU*Gp9?(P02ImHjPqOSB03>XhW)A;=*al&+~EUFgtat>dIwiAcT`k9JM-YsA9 zqsA1p4-dOsVhy>1G4L6esLRYh79Xbebx%u9ixN_3y|KsTh(!+bU1Guo^nAU6$3jwI`l-Ru zs8&?%1!+;MMQ!|>#{8FE$JER}(s64XzaLK3>4_cA>!stA3p~mLZXWc>uIgib@nL3! zlFth63xjeDTqcfu=)YAKlvEwG!z0(|rt=M)ihIh??W$)UULu=|gU+SJ=ROeaY_GD~ zy(=W2>6vg%pPb1BA_t}qiucKS$#t7(hLU)(qpX#tf!RI|?gJS7vGzCGd{U}_d8IJ* z6Z3Lx0Cq{}g>_Kw-lKZ1QfGFlQK3L4_ImzYOKZp}_eO$Gqkz_SNn03_h7H4iaBf4c zLv}>)sn90Wv^5_$sKUSTShQo3E=a*5n>58Z(z```hW@_V>j!9udtsTQCAQL1A~yWi z_~PAcl%ZhKdb|HbLgG<5g7p4}VexlG1;wwn(I3{1<*s=_FD5;ob5fS$K(=6}P|O;Nq-cMxvoCs)I~` zVF9I$i6jjU!3P+-6kz9jNRlWvAq0r-G(&sDI|)ed0m+g(q*pCE(sJ~!TM}nbJE!g@ zIfR>LTRSN;B`XaRiuS{Y_BTN^&LS!Q1RuFdf~^A|z)ojXAZ>1+(x&5PX1A06UizT# z^^OZ?&92-yfAood(bjz*-2xBv0qZp{pE|zYC+XStKhAAG_o`Lnw?7P>cDO_pt?^ph zJYW^nca74JGFJ5YuPL<9b9?qc-(v|wH{UkQgPxunk-_%Ky zg~)Vr*rmOq)6f+d04$q@a9|^EJ_SBI8q8wCQ(EFbh=gAF|B>{x;p+_i(-;iMm5l__ zUIPg|?WFZt9soCa4ykxlf@XsCGdY+Ip+k)+mMh-z#6tL-Z_;(rM=dVkZ9(Sg5oX(4 zkifT_;(g=zl|N8};c%w`2&~~|Gf!932H)Z`5@68IPwQz~!yqQ~qH&=@tKKLJViZ{r zp(w&&$=hxUv1`IrCrr(bOx%_u z-0Ev<8^v#jMpia4%~qCwza2nmaMoKmw{5q5k#|JKx!q3X#}TUKn)P9SJ}53<$sa{K zMO)j$10&w!!L`O&ZMJc@D+R|M{^kA9rTFew&vM%=MV#`M?&7%Q3cc7WdxP&sh?`EO z6M?Gf&{Krf>+zr5A8alzL!U-!QseYRb72Ets;%|%&oKU;fsB}0BP0eU#`)0-5T|x=S>~&#dfCzYo6cnqV>nv9EZ1~G&y@o zZ-3r#q2fC^V(uA95&h@IdumH@XOXXy2X2WBmL%=smT2g3kd*ZaGUVmCPQ;5h0Riz6 z@&j&3ms8>JON#;e$AI*h9y%G0OMgyWg3049OU5crb{ed|mZR)>>JsCCBt{e^{sl`L{_}a0KM4LJ4l|n^{FAEXD5x=TlhW^=xk`A>+BI?BUw?~L^X|~{XITrn(h_VKPF3~_qb0qgIE6bQ z-WxumM{C7D4v}m|Hejdl<6S;H16wiYbjn5)#_>zuP=I$aLebDI|9cs?(F%kX&T zxb99-)~)?Yqn!rNQdzo+s{>}%BJIMyx_!ba2d(EnkSh$ChYT%Z7nHt^T|5{7g@Hth_2B+)vL0PHsHzkJ=rIK?=R1Nr>Bs*ueHbXX7ysj zdMbg~;quIqgtdlmQ(dBOSi^4M&ZOt9d)^}a;D;v5@PpzrhyR{z&vC)LNyL3AI10TK z?}y!3J*@+oOs<{jSg$Th?3G!Q+k9JeB&*@l$t7(*_A)UJ&L1f(*{T3OH*2wk{fwOR z8ro?7<;y-QHyG%{glFdl?#?2o0YLjky6qDjp~d-Ttsx#j)|pJJiML3iL2NrViM(Qts=(qi)d+s=g;X{} zkq~nP%3(mkd>M_8RVNG_0j9rP0p^bYeYLMoWAATq+8fWoF(NPWqG`b&{9eKTajS94 zL5w90Xvth>?8BmpSKKp7(j5SB9*E-8%>vwc=2WU*QOb(b_P$*3tvVNaKZ} zz&3V<5y7w6$NhkA(#!hfurMos@tmTv8T}b2+H7w^#KXu-C2!6gi>dlc*;CSChpye# zytDgFL-T#yJ_MH%V0aOHBD zjGMkYY=??ng=(tu^dgODRIW4%_BO!1e9`d~*`Euri{kY|Aj$c0F-zWI7*iIXQx6Exh70P8;T^CM-w_myDFZo(C>evX&0Uz*JSK9)#w*OVwyqm zqS5NAde12;vxHiu1y9Z~tTe9%aS-1kb&y54i;x?`)UZ!}z@6lOa2CAZ;&S@+4QS}yKDQe*B64S0$Nrl2DfGE* zUw3nd;={8trk)QzE2f~gSasZ2?mOB4=e~VbM?OEiU9|bj8zq6OkFsz1HHzp8zpc@? z5Pw#5iS_hZRqc_L#c0By0a@w=Q9@VvR&kpCajA}M*e)CJC!zgHm2JQ+c6`S0uGoOr zmyeJN@=_TS9LK;D`NUF>hYNRNtGisULv923?u zS{FMh2po_&BuHP2)I7X=wk!BQr7;tq26L1nqfIGi-riHV9O!!c{r-nj;H)FBd0Q*1Uw`gmhO zc@>SrQ*-N=260&9%X*1Xqk_vtF6-HzWdkCrf1N7nvd(imqZ&MIn(u9KD@jbMJ4!25 zRMxWeLlW@$enV8&{$k5Lue2~|Pm7E!%QE8+t#swieT%9eBJ$^G`OkAKh}BVtHwyio zlr2;o>~7i+Q*YU(USSUStM!&1*5x~M)dA7Vj8~pM<+W%Y_}$ca z;MqFXiAd~e-XGo#hS4zvKBF2>cSKn9A3nS?rtEHVL-z23`ju)@veQgxxrV!*_ravX zmyewac09crqLB61K3mm;B?m$Bu&G4gcu9%Crn@f%1VjY{Z|Hj36YASckFZlq7y53K##1Q(~qktjHSR z6fwrsYN)3ZzMJBO-ZM*((f7Y|BL~vbj8R`H&D=q*eaWk%Oyw@J2ptsBVASa5b4&+7 zEJ8A^Dj+5J0-+rDrfzZz4(^*R-OQX^^kIgvFO#9(LSIl(CM|9@gBoQfL_il#xS2EL z7wV%Ky*e&$(@#=E?LQG;tL|XT?1}gxP;^@K*7b>aj;!0RT=Iy-w}x*vG48jkpCvx? z&?%O<9oC!tr0e*&3Ul4i+am3x5lK39LPWd$vWI2bha4IE zZBf_LGm^G<3Prpi8f855J1g>auvnVpX9hFB>^)fU#M)Lu9qlP&zmvRwJIy{nyw>-U zmPlSwlJ|QZ-@!ap>`L+A{XEDG9QZ@5kT&&@Ry^|}Y&X}9m#=Tf8U`s6Wh#$Al89dI z5rXE;`mgIdF{$S(S>H_`dKWP?;2RtW{R)H&m$YsZvf zOF?erJcH)STe<-qcLZ*Q2j&`Dx7%)7kou@PJ?8E9E^6x&)q~&fY?T!dD~6w5`D!Fs z?GSH3_-Na8j#)ZOm!t5?V8x(|2Xd?JXNxRvVuJ1r|@hs7;o&l}aWXW=jE zh~jhfl14n~i_>ERLnAF)#*=H3&w{*1_a#c_$eejjl(b14)X_10m|hcA^qSGXzS22d zwetG&?knW;JhCzO3MCo2fQI1Nlgn;=sbnr^^RU#r@IcAWH}CK)j0I0_5$TtgH(2ib z`P-DwgWQ15%>cpQ%mYLM2?mW|)$;jH04UXxq|1ECeJXaWMwq3f2VTp-JRS!&`u=1 zlPf)krw?NF7CX7|x_`_t8PD#YoN`!D$04v=H}ggDEqTLybq8t>ksB|45X}I zq||IiQ=r1I^ZWEtj8Xr^N0z)}b>Myfj!{shjY&`iHY3(u=W%f76FuS^n5qa zkxJ=|l!g9q&I!%7MI^hBnOz3r4?#bqj84y9D5Y)UT8;;6J486k%Pjb?purW=sm19w z)eauwKc%@tGRem#Wp17~2<;@E(Y1pZDQ|^CeZDMyR2Xe+yA-X`xb^_yCeZU?dFfG(=0AKtGSBRCnD(ik)S1PpjBxiuRF0-IR&zkdi9*}{0U={1*cK{1^ZJK?aIj_+ z4y3eEZuGEb#AL_ho*U1r6VCZ*&gCk5>|}H&?lAHB!>}!JZeL=A)0|N*j}MVhKF-;PnjLlF_7f+&Tn7qd6g7M?FEkET7d@Y)&(h}lOLZmV zwTrC^q%luztcopR(xUQ`t+roPCx%F<>3LeuVk4`Y-8D?P(lff$hLA>W$HcW{ic9 zu8^Ju0X5vmke^yxoCePI7_;;B(oXD!LBvrf+#q}}!T@}=atIaNC%LWAO}rOn6BMBT z8;d~eOu&hHJB!svg6uo0P8S)cAAGq4@}grK(i8RdDqQC%V`Mev%qUmPZ|dDH$COra z_+X^G!c{geRJIdmd}As(?Hv$L4w#xugv0dxnWc2OKS4qMF8?6p;=)8FtT>VkP=@I? z%$eAg`6MNW>Ii2hkDXTGBO&5Ae&J8wj6=l2xzV68P3^IHvyYcwp0QKxPPQ%XyV=%3 ztfF?0C+Vg{vz!zTm9`>=vW%bDwRokKey}ZhPu`R!`MvWYNp4}!p(uSrnEz?p)_%6= zv~=oMy4Eh(*;pj0m^#`es$|u<*=ApwU17dMeRu#sg}RzRWw=*6WH#YU9jH5ygkE~j9^DLH}a~rVWTJ7C`?C3%2biu zv51yCA=J#2I8el`O(Wj@hSSD8?3pUhn<@?t_dCNJrz}Vn;(FE|r)MAY*SiSc@dXNn z$I+6MM$=oyVI47T_oa62jqr#n<@ z88aHpelVrEo07=agt|K>4puV>5!#D3Hg(LNXzfL#o-=(CR+NXsmL}z2()bPW%5O_G zA4j{99skUIx&>Gq3a~i8#WQnWeO_HGvrl+;1ll-~s$xYgIa(mun`iyKeHwbxm1L@& zrh5$FPZ(pn55=cw0b&fBi~+NPxy;-8BhhAJ zE>bR9S(1Y}TVs>-lq+r{-^RSAK!A+9h-SdX^r*-^BxK4c5JU8#695qS7ldN<^LMPl z7FIoT<|);%*YNwGfYhtE^J4#VZJ3 zjNNmeZm_i=ftH@QqNh~~F`QocRm6gFh0hXS29rP|##rfV!Px1-%2#M&SAz|&?c98{ z{Pyoy&->r}b6&c=6_7euI|b*zSdr{J{pj`lip<6`?U{FLl5Q_1$`W?w*{6)i0{iIA z+Bwpd#ge*RB5wnp93Fb1B^F>eZ>AX@36Ubx$&I?tGy+yd2gH*2Y2Z!MAokL`Dr|YqEOUm4j1Y zn1|zJDcH_N>_vhb6P?r~kvrQ=d`*B8>8T~xjXP!hv?PmZ0Sp*!)A z(hFn_>2Xv!zY{Y&3U-=VWb~A77nLOB?4{a8%tZT+K<@5Oo^yV5So=q z>q#c>!FZVRO>t`qHpJ&n>24~i}1 zNcKm{TgJ1VuB3Wc9Eo(hkSTID+VkWY9Yk?d@*$gyj8>buThC^D*|(Bp%uhN5mKRy2 zst%S>A=lhv*V?^6<>}ZJ+%~a{xexnus(;qVxaeV&!8%iV<0V@7&`0FIh5vDAZ9ZUjecA= z9vLaIDsb3m4?1lQ7wkqzz?6rwaAd>7H#Eh}Z&|mSMi$fRlchyf4g(nfnXTBl zN{~X>mGnPWE%UZ5MeVZ}$uSmMp8@F&I4FWEXLt(Y@SHR%R%cRj9?AT3PGYD*1|=HgCP57y`nLMc)X#sH zWnE3ft07NxO>5nUV$S1u3$65aF*X07Eb?-?$h{U1TlvHmT0lVISYg%4J9Y#6NuR_V z%?%sXUXC=XE#R)eASH`BU0na9SZ6;9Dnzc;+H`V7YTRX!zVL*zvvhbog}b4)LXRhS zS@OfFKLmbDS(hPvbW-B&_+G(1K|`)vK13cB1PXa=n~96Ytm{Fubj|oYqUCy-L8A=_ zekTwL;9BT}Nyr-O@IzpxA61xYwE(iJo|pJ3tserv19$ql^g03XU8p#b9|Ea_rv&B_ zQe+Q-WZVw$fxr{(Dg1C-kXvkFv;LUn*kLcjEk(FaaL#DyN=Ljw7V>ipe>40$oP7vv zfisCUV3!}EaErJAXoFM@cb2(1)O22LHnJWm9-JDFf?Ioilj-oTX7Kd$`{$Q_=4 zhkM*>Tod#CEVwf$)voqghJL51uaKA834z4RYM1R5z(~_ zB2Qd9eBUY%Ky>XR!A4UUNomCUxZi!qk{`;if$B+nihW->UzDrG${&r&flI1~xU`pJ z8lC!{tZyW1taPVwuK4qNs(5}CrK2*>YwZfDf86=&%2*e_I8+)w6a37-`8eZaLId~;J349^L495*1NVj%_ zudfhbQOFGSG=0 zKLo;}aLK*K3do1ZpP%Od|4kPl1G@molO_kk-L!T2rT5fnhKX{1BL+ zfn+RN97_5jV4T2W0GOGONa1q*R(#`6{my;xL*TW;I*g-s7<``Fo53z({t)24;LgA+ zd)glKvpb;`M7AFE7Mb2D-At?a=-|>v{v9JihsEK&E#cVHWTtq%XNeC;kzTPn6R?@* zSDOW027?wg(BfPxmW-|v`_qI>pGR|3b@fro$1*wZZ{i~dkvX)R#C?g=%*+N~r--P)5rv>wNc!s?IR6kJ(8}> zZR_1I5X~@m%I_c73F2RPPm(?vAD9P50j&6{S)};}lv?;`_hp?bHZsx9%J7{v=v@aW z=AN%Zl&>>na8v<_gH8a40Dsv6&a@~C3gQ(Z4yO=f5vpLl#5MvAEo+G2zrm@!+sRGQ zNNFjd({hx` zII@AMpnn86GvbbCSbikXkKdzPM&7Z{;#gsCHr0X(nYtNOdhxBC8uZemFR0Wq3NF&* zwI}B`o_5o9u|C~}nVghgyu7lsQf4uN`$(hIEKyw4-eb`Wzlxoh%qeyh+5;T|Yoo-D z67Hjk879K!M~A31C7^0L8}42F{at|K5|v}1lb5+K!R^c!E6&&4t)_eHsbVi~$Md~s zm#f{gV-RXeZ}LoqrlFl`^CuOEmcPX`qNPq7J(?~gD2D17U;w43od548gSR-iVQ7drk5|Am#rW>$ zk<~}j>YUOwIS>CfJb1q3iO$KD5Q+?iSqlM3uZQvx*stGN0zte=gf6flWG%3cs~ZM} zGJo>VgRQH^jp02?!+)p&Z`gYH#18?rpYx7rk$m8adTCf-zFH?4NDhq{!FB&_dL^TnwQNF4|<0}BjfP+@p4J%19@2A|Lv`tYWPtf;amkO*mgBfnGP{X8jOjK zY?5d9EW#nfCavcH6Fj>BKub;t`%s!sVR+3#cKGlJZjg;af~S36eh*o9$Btn;W{Yx* zzWp0?xy(x8icGc+*WbB-+>KBH=EjodCV#rJw~VWFnY9^^iWaUsY&FY|rgw!K(^vC+ zhT;nA2!$>_$14@n@^yXnf4lH4VMEH$EYb6ZcZYp*`6JRAX(+v#lJh41^`(IF%#Nwb zC-o-g)|eMMGG_}*ZiN||4@Ry7|8i>G|J|ECe&0)R9>5ydH|XL9;Nsv2BgMc8jt}AL z)&F~xf&bLba`?H?h+w0g$W8wTYmk8+Lsr9UCe$1mA5ZcjOp`$;eiO38&3UiGPv}0uL^c`4%3w6#F zkysPvBa`0R^-R9RW;(;BhDB}+xK0@r&&lh%(erVsZha$U-YxV!k>OVgOTcZ1ZazN# z-3e1c>uJ~A@9Jx=aDT3E9+>4gGR)il_K`N^E%rtvQh15@>Os#_(G1Vr_Oy)aDmFxP zv>G5xQJy;a*L<95zq+pNbGnK0n=y~LEtPhc`sz3<6*Qtd`+RqJWb3Opawh-Tqj(># zKJt>KbTWZd-%+)~!ncFBX|8*Qyo8ql!CYrY?+PpBXGGWBKr!(qF3`At{_S!@HDAv0 zJG<~-9n$eM@t@uso=IS~xa$HlQ<22r&uAvXxtwAKTZqM+<+yWi!7Zh+SHKrGzj8kw z`yWTT30$oDXvK!O=MMqM5O4~o-OqDr@XDCBef{j$&{qUt7jgzi#*?{WEg<^G)%}|Ju(>xF8DBU2a2(m2tH^*=~NOEOypqmN34?M39}Hcoir~ zjM-K-FT0JP^(iqM>Gy(`YTK$hD3>_DpH+YH&}7nKGmwSw!O5~D+Wk?MfQeCC&JATO z>b2jQ&YlMbJQ8nP^YbFFKg>$r8?{}owcO^t!5(XoZQ+ki6!}XJj_b|VZLF&qG%cai z-l`UJE}T&C=~8XVa?pO211r5EoTgSgXl&IV5n#?y8L*%BFW-n)F1+!N^!oqmvDj;< z10c{txPy=lnjWS}@^h|8A?=671oARW0Cx=Q0dHN3(=AwC%1AEt`hrFFV}ps|g?0~* zbMPaZcHGE&h}d`umxOH0SQ4>h(YcN23SMT&6cX->Q2Vg3=2F2`kS>@3mq2XGJm2=M zn(_z;2s#eejl^kyxQ2b&yWS$+C1^qq9CH+|Zmh@uf|lxyXW`F$-n&ok94*SFKd-WN zGtsz~UK@o7?ZXR~N}eRDDNTah_+9J2yoRzy;1+wiR?OS!;htZxe>4Hv9pJNe`y#JB zAa_qKf=Mhp{kg%O>`J;aVzSJavS)^KtfS8je{H?0$Ug>oEZA4{m?w>2{5V!Rr*_yJ->WQ2sp!{#Rs%x+|M zf)44Wp|Q}#;%G(l{*;=eQ{7`U7duf`TXEHdV#T+8>_3S;x|Vc14?)rCtDHII+@~*p zfdTxgsr>&eF7PYKflyE>+&+)k&kE`E_p&hys)p{d9E@2ZG0sv$K8n3B$lI~|nKDZu zk^-ZjV0$r2Zb_G}ydA0tmi%2Q zd19FQ2)h+hEOR@Z-)M9{+@Q&&6e|2;VpVv$#MSrW)6K1{b6FL#YyHEIUDlm{2<8H_BnL`u;gaA5`pJoHTBjj9u>v zw{J?ITNKj`kR7O+)xtPL&Yq{`Sht~CilniZ$QyJp?JwLWuK!TkrNJzZfNj}i^*(*| zK$-FnIfLpeAJ0X7IbZP9dGv>XHjeKJ5MB9nsRdr5LGH7>)fYl(dMaU-i`46O$KD>Lwq|0g!>+!-01ISG&ybRInrn6AuzEBXMjE4>+dxn(dr!2 zs+rVKSnn@m5%j9bI3Lr^#?>-w*B))}GA?qN&6r7)@4w<>^`*XHFiSr5kHy_xL&NKN zYs+dly>*$FJzfi!7e%MxWtXlOkC=^yhrkvx$kE-^g7kpg@>X3sQ|^_J_`7yG>}5Q1JTerctJCZ$gebB zY(}{Q&-5z^ioe~`-!baX68nGkvrO268J%y(9fGJiu8w1)XPN!<<4>nDrDzY0AK8#7 zkO{M%t~cpc%B}ol9LCzTZ0<;Vdu`aVE|tIG^v8`Q|lZJ zj%hRDzf*vZx@$e6g;4#iJJ#NXcs70K!{^+$_LKXCJEeIM3sJl4s!a}tmHAgp=Jn!m zaZl`T*&Qj-@i5o@ZWCDs8sy6rOD;CxzGp;vT_Y$;&HEAm_v~)dOb7pX1C#i70LMPQ zc9UxcB^5)5HbV0sDD>=cab^lEL+nKgkssT4kr8Vaz&&`~;N@v;H&Z@(k-S^mDDtj?!=&tv-*9`iX z)l>ePQR^L@o4Vk5MdSg8vZ%4q{T8|x3I-jW;7bnR-pPljw~V5JGaZBGx)(3ET@0r< z58`Bd*j`Eb4g7b@9+;u`b`Q+_7hm943Wz=Er#*4EZ0R(6ZPd__xc4{Sw9|`<`<#(? znq-PvT$~2tn?l@HMXfG;{V#XnKkQHtO#Q0e?`JU8{0j-2zvC#_pOjy9`~5Q|@QMoW zf90_L{X6A?Efb=BTs?r*j*Hqz?v<@9N7t}UMN z&feX-x>$c-4=@UwFOKSzQo`Nsn9HrYJ<(h@)|k^k-}qtj0jymw*Nrw59h_kj^{#Vc4)J=)fZtRIi z>|wnfr93KwLS7?QT^nFw#VA zBu;PcdznY8?z<%rnZ{)6-&602;htcYGL#~NPe}*66yKhFM>s|_U; zVh(j+u0HrYu!!ahW7VPLwP64Y9X_#dg8N5Pzx~NTDN_Gp0h0XqqR52q7>Z(?$K_eQ zbL$+PdR5YuiFvAgMup^zvT3h3y?xv2qVyF6{LFv^Wr$@={tx{m*`1NlEa zb~gkDo+U?MXpU_3pCeq1xiE~-n0H1c%Gbnwu5Vy|M*fC7K5t*?`@ZUBge6LRR!;m? zvV-@3@02Q!g zHOs^hPUQ;C5ZHt>p;Uy*AUGF#)J)ESwKdLuyBhe#@X%B5D$i?~BI@<^ z&ETB)EPwpc{+**7Xq%?E`b?}~%h)YU*G|z^Xv0lDV zpN*pO%w9Kyj9zhMpen=v%y~RyqOeqYj~NoBP1yq_(CaFQb3mQI0jCe30DAMSp5R7& zE3(9i3$8Kc9hCUTqH5@y5Q{#&$K!2>2{n7leVTZ}x{%7Vd4Sw|WB)cZDTl zRSF<58Eq$+zUaVz*T{sYklIHBJ3>U+KL8@t|?zL_Hu zcA(aUXsF(R28_S93W|&WOkJU5+6fE9d+ixbbd-yV`igg0CfWyXO}2r zllEw-2uKmoezjb`dd_uE9)9X8Um4OfBUdjY4!C0k>E@tHrUS1zKk3Q5ok`b>I?mUv z<~Rn3!qI@v2Ox~63?B_j4ff-NPEFcXu!aNR4kxfy%#h@3gWN1MmHZp@h-QvFJ$?gO zTT79G5@;3`FMK&t?PK^WZV>Ej&G;sr1^}|3P9U1Nzdc`2Z_c1VX>0TTP3!@xaN%s{ zNXN73MP^w^yoTy7F~fm}Uwp#O+stGsu~e%f;%`-l{|vl7{jV6;Kl}Ip+pw>uQrZm2 za)rRC*SebGf(9q-9}wVSH&V-X&uc&YI)vJS5Q6rEG$so8-w=$|7b)+k)Vk*9xLAIA z>{f{Z$Z~0QAj>`5fvOcMtViS=f11N}>kXm^c7}>{qWx%ZfU=qJQ2Fydx4hGc>?0mO6w+x?^>}p)Yekq4}*FA5;wh*6AvMlz{R81d# zG!k~c)NfJIvfyVPsFHR1|Jph@YYhA%j~Ij+>*w#3r5Tv9<3Y%`8TS{m2G$N6VYKq~ znEn$nOiea!0H`Fu*>ooPsaFZ+ES0QXJB0PvGS8fE8SQMZkog4FpJk;af2ny@)vp8F z3Ync}BBPpQ{rJ1K(&4dpBo;h!+nGSlI4U1g+CE7NS&(PWE%C(!+b6}jn^+ZbL9jS@ z9lQm;1w(CdhJm`zR=);VJQ+R)EmJeTmC^Jj_xjvfOlwb0fAOg{{gCFd;FD&25&9$c z(`b1$>Y2|ZkrncXoY54bS9}HT*?EF~eOhn1-yYHrs@tAA844zdk=4>cY@yn(BQS!$&nZ~1yns%`Ja&cns%||*>S8d6q^58_Ujs!W*a{C z0~FCVSwn2=*^Q}aX$S$;#K?(#yu#nBSu<^fh-?Hi>Dw#j{?1{XN_EVqd{D2<#f>&h z#*pPP4(80Yg*+yaKC>{+jA3^`-7GI>XplI63vyr_isPuxlLdRP2jRB>26q_8XnuII zCWxqD%f*+cpVCY7ViPT$tOiqZZaP9@o_v8?aWcdm1w=ba^2*Tg zen+OmT_t}J_H-}h+R57R<7+l4?!)>*NUlgal~UJHS~APF@k>8?no$9ntjgN74qfaP z>d1se`5zci>MPd>nG@y)Pgz20UW+qyunMw+`Oxo7YrHHL59x7EV8fv8Oh>RO3Ctvn zA7i*pc0V;^nA)sH(@doJH!HPI))~h)3DL}N!S_L$?fmVmiiPGv?(Kov=8)D2>7NBQ zOHa?7IcFfBZ~qvcW?Jj_`H8!suCJz8o73Tw5lT6WMCFT#RZcc#v1ulQQM(T_pClqQ zNV|)&P-UG{t1?J4~@qgZijE{Wc0+_ z>rURosrtB^`E%Srxoj)mXL5ALp^;VJni5B-spsnF(S{eO`P>66vHG@f8^+}Qadft-Wc>PA*FolvrhmtcNZ%1aZeac-I89>t^g(E`AQqUe^6dB zz_0jg-b8tzg`s6Ty=6}6FjD;T$+JSH=<(0|{%M@&kXqT*jPkUoUm}Td-{Si5^-7C+ z9BY0TK~Vp9W?m~3Ga21tN_8N z8^h5QZ)7~c{qF&TbOemKv;+k9*y9vg!~u-&7!AH)$gxE(bkdOb-1jhhI*?-ovtGWS zk1nD(X)~lts4CmSsGpS*6yPzdWC0VD20%MQJ4K3-|D0tJz_HUdy*`CQ)e#|6Z2FD2QJ59@bk{`+yPz`#g~$TCsEoo zNB4tH_pS@!z3pkc;xc<(N$RjZDV4G3|C9 ztxUR;K_*TW1ubod&Mf$aWXPt+Ei}1iT<RX?=b1eMq(08Yy1lED5LS?LcI61uMM2`3JFDO(T>QbRMM40l$2 z&P`xZyvX6GMR6z zacqPm8D@COc;0cp>TPQ_!Hvo}v_w?!{ccKhFgH=tJ2vc{8=qJ7KVuk*FxNW!Fe`*B znqb-sItD>#yo(*pT1z3rv6nyS+i>hYO#&^ZO93T$w#?P}SrsedsWb6kX4-6%R7pOxS%d@J zKQ2o#imGz5g|2!HiZB-d*xBOidfAR*;%(WB3v*#a2w=gsjU&*7Z@%n8mF_ zRbej-J%aT?aB2@H#Q+ooQsP$?VGqlRK<_DV@(FKv&HDsq_iKtU#UBr3=FRb*<3{*c zP#Z)?kT*~8`zCfmS*(~2ln_9>%8<@=_;~mI>DE9s$E1iWz!dCI`>VF>7!4VBom6(L zldRoeo+u}Og!tHsBP3FRJHI z7O)bEJaSW@&Keaa2xb^~GtnLBX#9>J0yiq+@Ow%4xCu!Xf=DC8KE$>2Px7*Ag_I1L zOVr6|WGy~^6@9lMro&u~G2SHI5y#q0k7-*H(B%@Q z%FJ3C-q+JXH%twriEPO_^BFqZ+5m4i;U9F<8NkVY_>$`7HpNSnp(VFYKh2UZXGKLv;FXnfat(T)W-pJmjRW8uJnRIj

x5Gvz*}c5Vrtm4G z3|E~6dyT&fiU$&aviL(lmfu4VR_7m_N9eF3@%wPcaf7(+tP9AR@h?#<2}5QIRWmkQ zxnKL8^hA%hJe2#4Mkt^y$0N(c9Apud!su zzvcK$Rm7ce7Jtzo#?CDKgt4>@ra3>}Q>c-p>B~6TOFRRHVGR0NB$o8mYM$zZS@oBS z#eNP*^fAq+iK+UAO%<8#Ps+O=nIkn+VHATr8jx6OI54E%;oq8J^U&(%tyG_m{E`!r zfD5zY@ZFC|1hTC?93^fjl*f#w(#r{~WjYG9{-9{+g(xP`g@t&^am9KujaxOhaWz2% z83?+TtMo(4W(mLHj)J>8Q~r&t1ZC3qV;mPDJC>o#rJ7dw~yYq!ZeZTW0yf z5Rzs&0Q=~|p8YxD;yNKo_jX(U(QW2|biod!3~004 zZDR-pfF&b{YVyUuX76JH??}1!5o@m4zM9e|WWQ#_($5ypc2jfhzoFyZFcVR_t9F1P zEs3=)OwALE>bSV^UcBZ@{6mYh3p&zk@kxingQJN0hMJ!7Wq%Ph&fDI!5IeG>wfE+; ztDn>c3St}*Un%XUd)nDFi55f^$e25R2+lFYwF5}0!}~vwmjAyp7xr)Uw||$0|9`eJ zcM2|zJNZQ$|x3G`afw+1tS|tBIe(tQ2v(0i)6f zDBFN?{e2ZMSxSqSkK4r`_}Pxc<`ICls46rF3Zv}$d`RScZ6+AeiG=>p_Xo5miSb$I zn0w^GLMM!a!%*%Aqo;zgSox5GS@tnsiHxBt8cNi6j~T9Y`1G3BUnnLM{ZXEu6885< zz%=L>&>Aj)|LV!`u%Cl$K?!^t?>_SD8s(}c*8~-T zuq@&?zYU8_I(pOmhF3gSgsvu}XU8%h&&qC`S`zhcI1#6>RyszN%b_jeP5O0`4$^z9 zDoL*rzWJ&YGL*a2i@|sqDJ37Hplfs1sm_C@X+|>^Cd3`}%A`Xd%_jW2CvIp6b=yzP zwmynLJ4l#j>E6&Zw%8ltS{09aM%jz>MnMYr_BgI#Fw2aQ&J`ih&4&}Xf=aCvaW~8w z9lg-Y*hLWGYGpcE?&}8gEhXd*46W`U5jL67B^kqnR^5b8-a=)@awS2_xP+SsEYy<+ z1Yr;-aqm&gZiEs9)?mwRXgPY>id0ZJ4*&tbiSE~nGUAW zUzC?#2@uO&OY&VUX)hjlmYwSRKKkHejYn2(Rz)TKB@C&qW42#=8)vMoEt2=c&IDwn zdVz%ZSYokFqQo>Vi6z3{{wAMm1QMh-2z7jm4hf%a_TGqg~r`YQ}E7yxma2-J9LnIw{%&^8`iCmO~3% z309|Ff^*K#KVT(bhTGTD#mMrw4H-uWxAD-pP%K3R~LvG zY0H~39ldF^)5T^Pi8pJf&2|^RsaNK?KbzU9uGgRVCAaTc#d<{!_7*st2*?cqGo)1{ z;+f_ZFk_B>OW7!Qleq|8X`#J9vt<`rcvi$)PN5z;cQ`l}NpoqT3+<$b?{`gTnf%y0 zH|pB=(RWvX@8Z59@+W8p;zB{8rTWV%*tB?Mz-^QvNrb9Y&;sz&vLe zRSaepN3iMUBTb1_Rg09%=-dn1#md(l4Wluc0aNz)xCb%Q=R ze@-f~PUR8xpEcK{mMovp^i%0elj14B22X^k=?oGo$CVzuZi_yQ2B7bIb-zLR;YMgj!v?>#z;D8|F-mjl;m` z{6)82)Qv-bYHTAEIJ&feXr0D_)@dK75-j z$^3*8YQod!HHF^=dRBD%p}oTBC?Sj=b)Vbh8?nfGIVDnE{548LWi-01lvOe1z6}^`GwITrF~t$X}wBRyKDMztLLv5=qwv_8CY@7;YY9}P=E`AHlwcD|Cz3Bn?YKF zj#JK#b_LYDJ<2_PG+*8#I1hnoso$y^>}B$D*{winkEi%&IzcV9>@EKcfc7GAE%24F zNiaBEp`wMr_gDVKb87RWswwBzck$(fI9u?&OE@qH`XOZ-e!VvDKR*RnBhLZRgf=x< zY0Q&b`#B3aPK^lwhfLFT|0ZMLCywG1)j4Mojo@K6KBb2)&hq2l^0#6CflgGX*TuF@ zD52w`0~toFU1u(sm&snAGdk#TLhoe7khF?ID#J>ltEQ#ES(7|ShC4_HQRhyPsK2>g;QPYb+VM0|GDlFrIjqps{(HSDS0pRcnXu+iYHkv zsL=4yWLaiA;XW40T&7ZFa01@h+dec&5q;uvXZibjxr&8Q?${sw`dXLs+T|X3J$Le9 z`q(#I^|`z?*EzQhfoHmxfxA!!0uHEH0{DLB;Y^dBO`tg6?CALv5`)0q z$Dx(qdycW84R;`+L&JBuS~S!)sDd^et*u!Y;z~Egifi0-Pfmru{IB$PqkuyfFn2Oyw+_i(wD4wH*Qf<))5fo zte&d=XGWMtRtT-dtKq-Cq{LD62@pE`uMQa&&Z zd}6G(M140}wMW^{o9~IyUl~nHwMhO5WLZV8HuQocV2BG@NL#I0tNIv0{Kv6E2+!W zO0*dpiPQE{{=STek@tdDkauIDGBIdpT+o`{-B3vgKQ(QlbWxgA=Azs73e%;jp`+uw zJvcMEw4_*5uPCuxc)$M0umgMj-KpbRl?Pt=T3fr1mYLYQkJb>63^}<3v{vU?S9{w# zOF9c3PY(sCLBF!Ym_YU_1~1Rh1G(TuVrLi__TSpzpTQp;hEr=J`*K;bBvCWF@!utHbG0{x#*q4frO6b?bm;u%JTIM>)Gxpm(rm}p2!7cGu19xZC!nIvU zc8}UXS^66=iDgofSWZHBKw{g;iRAs&D?U)|b1Ap^*|?Q)1ZuHN*dWsC2&oAY~q z%lVE2f=8Q!-Wx1TGMtbD{LE_6258V)ybiSSXpf!mVNLZML17-}_a_cfUFuV%Epmu&U!7@+8mokjpDc`k>v$_q~I?hvLmP>PpBJB1P!Q zk`hq&%ohQwz_^9jnVzrZg7a#!TUYaR^rs`5QyN_f z$Ii30-FuyVd$g)RD*wRwg+S!~QmyWQ)DZ6`k|n$V{`gM;pvl5V!Ay-IJPv@KmRyV^ zju}Rn2^*UhS}tT%BY{iJ1d_$}pQP79k69qNrmq63%8PG`G|X2yd(XfN#zt`okLaH^ z;-&EuiQ*lzs7}j0^d4(55neqvuYqAOuTbVp*y!rku-D4*;sHuvGiGwTp@h^5O}#x3 zd{d+dbnhgY_=y^jPZ-}J{)&EIi;I8BmRRz@D|`HX_blq*Jbns@R)_V$>Zq&;-afDW4KZK#A$!b|C5d*u;8Nyl zI9MHQ<<@~H;rZaMV`bU<6XyNKC(y+HWN1ujIRL@4T>iZ(^EtEX_n-a6P$uXokdysG zPK()00Gki;#9;S<~LL!gE#XdHwM=S!V5)w%G=IO`wSgU7N z*>%?~6q?IaKo&tyt|6fm*ORR8mP9E z&rR%;pKu!>+Q@ZG>Ac?VLHLVX$oAR?8Lx(x7!PUmKKMV5Jann*fXKK!F=z( zSctd&Yw;SSxcEL5iRHxP+<63!+k=zbX|kW78|-@%9_;&a=CoYb_(bdi21PKN@#eFr z?5y|8z6UR5x+ky%P%<4`sv>lVP`}eL&CgsIISNH@VqPY^-%VKt^=QFCz<0*nB$On6 zZjPyPj2&v99*IB1;9sBhn-QeUqDFts6RFH&W6n*`Jtk-%s)9Tnq9ga&j}$~(%V=UF z@hoa8C)jW)^f+E>Gz>WT0)PZ{3a$KSFUIdbBVp!sZ^7XrC+Nu?q@5uA0oekLF$Am0 z7u?Gb17!85`yV{Ob>wCe26^NSmd0Y!%(;2(%=szk1SGx@i4|#5OZ|{izs8F*aTU2@ zV`v~294w`e@o&rl*ZyU$E|{|M2J=;p>30|6r~iaJ^FP-A8M6-Q!HnTOArUs201hKe zAs32ag00^IU=LbzN%y=MI^ieEe>}+D5!pV2m8fEFoCy_2eZbEM?7(^8jVVd6H$P9M zFXTqNXpTfeF%Zju7hi>c4tYYTXG?bbM@SOpF-Z59(VS8IGwI>9GsuT{s5=T==4_8! z_Fz6Uvl=}K@E@I&HjI#<15KwRsP3M`Vl1b5cos#|8+||oeK0UTS|T)O;66%sJYT?D zBJ~JV^*{G-6L!7#fv}elSVoDoAaWMvI2=~UtsJ5Y=zMxBHAO%bN8JU|kWyf29JZ)+ zP(Qb^8aGKa^Ubw`P|pEL7Brnj(dzC@tj2RXKm-m=B?RZ}1os2&WTbKX1tg;lOt@(J z%0is<4W{qpCl#FR9BC08-DGem1tG1D)4V@{=>JB{0xZe-x{Cvjma68K|u;@kt1L`;c1oYet|tA>C)|>8OXtiP76zJ(ed- z8tu21I~RZ3_SBv{^X*mdTX^Pqv_Snb9GqE0kIAj?)z2E_3>HES>Ma_gg}FjbD-s7+R)*BCCXNI6VY5Lx8nztNiREP#i&bH_ ztdZoJEqCvBlI8P8p*4){0(>)s5_@No%5`>W>8S1F8#Yo`7?f8p0%ElReZiPUweFL+&2F;H~ra=J%wyCYr<@<$A6Ry9QBSx$7ANeE^ zR{HP2H=HG9)mEk#nL?TP(Bc3kDTQmN$I$xaM-`#6_k$Sb+OeT;oN|q_Uu8JNWoX__ za5%Mdspb#Pjid?L=p>ioquztUS`U-}74B)BUvQtfyzB_N{DkBvmOk}pVZO-0KOf^4?z-HL9q2EUykO+G7N%;aP!y;c07 zBjB;=j$(MY{-dj5ELoaHO63d#Ao5_f+q}C(&s> zUKO;(Y)o@z3|o*~U4|Sq4m~JRx@h$Cbcn)@e1o;6EVuM+sfnD4G3!KghppKh2cw?{ zUa2WWY>i6SOydhG-KURomU(+!JhaN*Vc&mn8~GA3f;-oIT;+f0Nc#ItbH1UZV&bkBL8*K0oE)mGh&UU!*H>w%D88w9 zh5MslRc$rd|CZPwJyc6MVO6$jq}|q5Xf=@U^J#x#(z_>BCsUtGu6K#e0U!olo{%DZ zm^Bi8$LB@L;;_n^+~Yar_wKO6m&QcWWS?-1uNPn3kkIS>;tKKU%~jXe5{?}^%KRIE zT5gw=Q84856%Qr3h=%wZs8_3@^4a}Nu@?LZ&_68TGQoXLP9e>w_^hx-2F8P001zAd zRxHQYbE;|Qiq>QdxUsKc7L(1mLAP8@fZkSdBO|2`Ne1W^c@c;v+FB4$-n)ih$DBFb z)k|Rjh|L_rW(k1@f*?z+xjg!E@d*%0T(zI~=|1W1QfC0+2|<8n!_-+Os4Q+kH~AsA z3^4ONLw))9f4Vq?sA1s_$(;aJ@34cUfK1>|3e_LLA^b^>JWqw6TaQ`6*a8mI*XsrH zyjTE!98|4)E&di(677Yz4ueZkn7`juprL~UC4h8=PBNi*1h-j23-EPrGS)}5`PdM~ zIvNpC;oBAp+2RdQ1yiz~K3B30Gn*5d%UNnU-^1PR8TJRFhSpgmZB7V0nMNrK%@4`9 zx59em!VCMLE zd=Kvwta%N}_PP6>n{MZ}%Jj~nc9sg>MT5V0#W+Q(>qI-_kS7Pb;`U|&kmimAJteI% zy~9>rrr!wc9#ulM*lSLZbd7;GdpQn`)Iw<%jd?z`Afk{dwn znfchrUIIuLiSX@gpIlDvW&Cj(Y(g8MpcFR8=Xk$Xfv*lS*Efo=^S%r7zajREMalt2(a?uj|N&Zs=}!rp?>A-Kt>KxPyIlmXUKt zSbgW)DBrc630n+Sjkg`RxB7^Ji%*x&z^K``OamN{u--&I&abK^EH~XgxDDP=uy>Gf z33K;CJ#$IV&LRM93!q+Rc#5!;PJAhbw_)(*NmF})p{>9&Mwg*Q^B}wM1Cr}^oSJk_ zb?Tai7De0G^PB6(WrJ5*m%u8*C6agwPOR4jG9j(R#`N`)v`pBH@5eFZ$<(ZYZ-TW4 zxOu;5rktWM8?=qbX?qLc+((9NS$#-`r0r#MB#6jOt-?nt??`RNX;gHG-8`j3k3Fbr zJBoxcIkFNE_lyid0Km5k6UCN%?;}o!^*Get7k0pYWq#_wZ9|?VT_lPP_*$bv;H*l9 z8>%g4UNkbWv@%-t+YCR^Veiv~{@Sl%v?3qtw;C(vCk{u{wJP~?)6Q=U7&nd+o(|ca zJ+f;Xji+JO(_WA|Tr}3STJyuRfa97U@--h&eH|^%z#h8sxz1Wqf>r%iNA9Z|zr59% z=uP)b`qlBVv-H}!ccv7IOIm?Nfs6 zC$xh~+uji6m*(}1DctHx>f2x5u1_tRZwHHNiun3>Z`8MR-hD7pp?Bb?hodikEjd|` zvone7^C4&~M_#qi8G9hFC1y>jW@qEk@2AhapXr?;$5sDmv42;9k40hOwd-H=9ioj6 z-+c(;^7nNe*Rs%O@0_zR8tc-mBgJ}yUUe^MSEyaA$Am~K-^#An8hH<`Aju35(4+kr zcHs8C$O!fxjQwhyim5T8u+rC+fNnD+651FW>46e}@Xr31 zX8J2qG(&cP(4!(GNT?a@47UQ(!!rDeS(Mk_LDprUzP-BU_JzS&lw#P_Z9l6jrobYX z{%Y(k29z?dVTB(7$To2fWV?i-2Tj%H&G)b{YiW3X2rWFz^5*`A0oA0v)-twhH9Q># z7g?uXY&zXaJVvamdfT9R@H%$!*weq=eMvSfj7$(bh%M?)qwOERl?G{6+;=HDuHZs8 z-?K9Z7(IELOu}gU>0E3cXY4`cq?{A;KXZ1U3!4!}094R&W*-}gasCagy8&*UMRhFB zn(yH+Xu21;*3I*-nZ)NH7bXSJ%hFT+WK{{Q^OO!pxnFhDbkY5 zQ=CN=D+)Ynvgt{)sAGPgHmo5C9r0dli5EL!dRo=b4)zC#91KW9df$K^N2<=E?%5s! zNlbrG$tc`$cp<61znU@_PES&T@1%hAh>)Pm1nEn>GpOq*L2tt5&`2fD0+7?QSMsQN zyr5wZ3dQH92s76B@3`ns>)t}sgH+^~cKmUW731Lv3#p&{HfEk0yhwu(4Smf7(^@|_ zEk1BK_DUNc-czh^htkk2Bd%n4Ge82Yqa$f8u_gFp&@`sh5)c>&fWUCcKzJO)Q($-h zSgv;^)W@=BQP!Rvr@O`B-{Wq@O04gIaLg+xVF=I>frQMbYWWY(<|)5_frNa4g!}^+>I)%o7`2NQd zeDeTDzCc1uzCc12aQmE-x|Dhgv=fK}p5cfI>|EQ6ze-Vq>SzMBE8<{3ZnR+|#19!o zOrNnA!yUEBDFoq~!om@u6fa3xuM#R}>2&uXta2?oW3P9`5MCQP3ia9y+5ibi45$~K zG>JSU^@Bi`Z1^yc>4{#HP0@Q!Hs@D7s?q5zGqKVU+vU9Se!&q3<-ztLA=7Wd1AcLT z-I(9kZ!1)|FmXGOb;Z;-V34^IC_3EH_T_DWy#^?`4ZO!EOSj$va($ z%PEy=AZD6Vbo#9xF}Kee3fBJRIMChM^yYS7d0dL^lacl~H!XHc^RI7T8OFVJX)%fl zFf}U<&!0Gvf9!+iD#4cPE0=d^bkq%ww1s5Y^%@t*oD*)LX&9K`fp(zQ{?RK7D0+WA zH)bBd)L#|E_eku-$BVTmL)a@QijWW3y1F_(kYhtj%7j=Rb|MzGF*V5>!S_;o*hByb zD8=6g|KPfX*ovOu!YA)>-M()FpL~KK(FRIqIYCaWF|b>5|CFva!)kyUrmXWouoY?b zka9b;alFyHZ|~uJ1YVK(Gpjuj$mu4Yp{vA&IdU);qag>EDa{c}DWDX$!79 zko!$f%ST(yF$dS}Iy-uFCW+N_e=>66=Fq{ctgz;$%6!`#d9+NzmRn+z(}j_Mgt)JE z(96Q7sKD5x-Nzxbpyl+Ldn^izDHDLdLY2`+hq|((AkJZ;F`#|=`ZByCL$j)^*^?lU-+kk*pp-BI?=vULgTK($&rO| z9$;Rk_AJWmH$LW+mfONrRXjvg?6+zrL~JXgzW_ai8hVy#86|yvM}D1|tf@+|^%?rL zq|F8zT;kz`Vfpo^&^;~JzJH%`RTxv{lNP9Y0$IMP-CxjlcE~hvS&nOpqAA`{G(6IpNN#4;9ru1z(e8yS)>rQ*uU8XnfPYG+v z%ii_%zGDaNU=&JeS77T8=ein&Kac7hw}{VBh`Vjo86U0YRF$jPN|SfWvLbG-i%>7v zu^>_AJJR+{zCW~ztVClU45Ti{no0>kfM2f=+mr2A0)v*_@^z_@(!t;&qX=}xxGNo~ zQ2r_?O(yizob*%ZX(<6lHHKT&K8XWbj?H>Lh;0RjjS^e&bEv<(tHAUEeOIwLKiBz% zL2%R{k9kj5ES=Hw?y^EZ#QCnVBb$C=lS5yQfGxHbO_#q8@;MT|-=90dwLL3@ox05B zS1*dl9J4y7U!AS-;aNPK=u+Fb{UGi?)f3}SkWs`xOA!5ciByF*KboQjow@W#|5#b~X01~70Gr@#avK8UG)_2`Gg~ptpWOuP$3sm)_+x0V zTy+Ui>bPx-N5}XB=%@avH_;we2gXM8RXtB!naVMjrHopD;UadA5lx9vCS?p=F)!}<*vNd(Y~w_ESJtnVhLn|C*lS_5UTHDv{) z7)&f-X{p=6=|%jc41Of{RDN-v<;vT-esZJATP4(DQ=J`e>bBk-TQhUwA$Q5t%aj9w z#qY{I_Y5sJG5gn)z5bj-G6$vmi}6T)yYnsdZutLT9QrQ>y!;&d_|G@@zkB?Dt?>+F zRs#6SM!5f%gYbSXzK#`&ktbtw$JZbm?(*3{B1H=JZ0=nY!}LC$=UrYolpZ@+jdkiM zE{pUvaq2p$Gi~G>Csfq2+gBD700_F#5X zBtzF6`TSNTo-@zGe=9P5_BmN!KKdUQ_RE6&!P34g$d?8A-;U*r5BYK54_S8dJa-De;S~5O^i4bdufMkfrTENOMh}LTW zz4FvTnV#%xmAXuz)Mj3N)uC;=746bNR`JanHExOr>Oh3il-nV#)w~cML*D6rqpAI4 Yro+OUU@V|+{?(T;`~H>BufferManager: Request buffer + activate Sending Component + activate BufferManager + Sending Component->>Receiving Component: Send buffer + activate Receiving Component + deactivate Sending Component + Receiving Component->>BufferManager: Send buffer + deactivate BufferManager + deactivate Receiving Component +``` ### 3.8 Assertions From d2c71acd2d7cad2f722fdae957edf812ef2b7759 Mon Sep 17 00:00:00 2001 From: Ani Date: Tue, 26 Jul 2022 09:59:00 -0700 Subject: [PATCH 039/169] Replace NULL with nullptr (#1590) --- STest/STest/Scenario/ConditionalIteratedScenario.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/STest/STest/Scenario/ConditionalIteratedScenario.hpp b/STest/STest/Scenario/ConditionalIteratedScenario.hpp index 89823ca2c9..1be1bf1e57 100644 --- a/STest/STest/Scenario/ConditionalIteratedScenario.hpp +++ b/STest/STest/Scenario/ConditionalIteratedScenario.hpp @@ -61,7 +61,7 @@ namespace STest { Scenario* nextScenario_IteratedScenario( State& state //!< The system state ) { - Scenario* scenario = NULL; + Scenario* scenario = nullptr; if (!this->condition_ConditionalIteratedScenario(state)) { this->done = true; } From 540f2b704e035c97439f0629db5082420a019da5 Mon Sep 17 00:00:00 2001 From: Kai <2644614+Schweinepriester@users.noreply.github.com> Date: Tue, 26 Jul 2022 23:34:22 +0200 Subject: [PATCH 040/169] Update link to CFDP PDF in sdd.md (#1591) --- Svc/FileUplink/docs/sdd.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Svc/FileUplink/docs/sdd.md b/Svc/FileUplink/docs/sdd.md index c7185e452b..bef295dba0 100644 --- a/Svc/FileUplink/docs/sdd.md +++ b/Svc/FileUplink/docs/sdd.md @@ -137,7 +137,7 @@ then issue a *PacketOutOfOrder* warning reporting b. Use *writeFileDescriptor* to do the following: 1. Use the method described in § 4.1.2 of the -[CCSDS File Delivery Protocol (CFDP) Recommended Standard](http://public.ccsds.org/publications/archive/727x0b4.pdf) +[CCSDS File Delivery Protocol (CFDP) Recommended Standard](https://public.ccsds.org/Pubs/727x0b4s.pdf) to compute the checksum value for the file. 2. Compare the value computed in the previous step against the From 1f7b07da365bc23e10df4184c35d83147b4f1a1e Mon Sep 17 00:00:00 2001 From: Josh Soref <2119212+jsoref@users.noreply.github.com> Date: Tue, 26 Jul 2022 17:35:01 -0400 Subject: [PATCH 041/169] Update check-spelling to v0.0.20 (#1583) * spelling: and Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: command Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: cycle Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: dependent Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: github Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: nonexistent Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: pass Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: preexisting Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: that Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: the Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * Update check-spelling --- .github/actions/spelling/README.md | 15 ++ .github/actions/spelling/advice.md | 25 +++ .github/actions/spelling/allow.txt | 0 .github/actions/spelling/excludes.txt | 51 ++++- .github/actions/spelling/expect.txt | 204 ++++-------------- .../actions/spelling/line_forbidden.patterns | 39 ++++ .github/actions/spelling/patterns.txt | 14 ++ .github/actions/spelling/reject.txt | 10 + .github/workflows/spelling.yml | 48 ++++- Autocoders/Python/test/pass_by_kind/main.cpp | 2 +- .../Python/test/testgen/test/ut/Tester.cpp | 8 +- CONTRIBUTING.md | 2 +- Fw/Buffer/docs/sdd.md | 2 +- Svc/ActiveRateGroup/ActiveRateGroup.cpp | 2 +- Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp | 2 +- Svc/PrmDb/test/ut/PrmDbTester.cpp | 2 +- Svc/TlmChan/docs/sdd.md | 2 +- cmake/API.cmake | 2 +- cmake/autocoder/ai_xml.cmake | 2 +- cmake/target/default.cmake | 2 +- cmake/utilities.cmake | 2 +- .../MathSender/test/ut/Tester.cpp | 2 +- docs/Tutorials/MathComponent/Tutorial.md | 2 +- docs/Tutorials/MathComponent/md/Tutorial.md | 2 +- docs/UsersGuide/best/ground-interface.md | 2 +- docs/UsersGuide/gds/gds-introduction.md | 2 +- docs/doxygen/Doxyfile | 2 +- 27 files changed, 245 insertions(+), 203 deletions(-) create mode 100644 .github/actions/spelling/README.md create mode 100644 .github/actions/spelling/advice.md create mode 100644 .github/actions/spelling/allow.txt create mode 100644 .github/actions/spelling/line_forbidden.patterns create mode 100644 .github/actions/spelling/reject.txt diff --git a/.github/actions/spelling/README.md b/.github/actions/spelling/README.md new file mode 100644 index 0000000000..ca5ca67d08 --- /dev/null +++ b/.github/actions/spelling/README.md @@ -0,0 +1,15 @@ +# check-spelling/check-spelling configuration + +File | Purpose | Format | Info +-|-|-|- +[allow.txt](allow.txt) | Add words to the dictionary | one word per line (only letters and `'`s allowed) | [allow](https://github.com/check-spelling/check-spelling/wiki/Configuration#allow) +[reject.txt](reject.txt) | Remove words from the dictionary (after allow) | grep pattern matching whole dictionary words | [reject](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-reject) +[excludes.txt](excludes.txt) | Files to ignore entirely | perl regular expression | [excludes](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-excludes) +[only.txt](only.txt) | Only check matching files (applied after excludes) | perl regular expression | [only](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-only) +[patterns.txt](patterns.txt) | Patterns to ignore from checked lines | perl regular expression (order matters, first match wins) | [patterns](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-patterns) +[line_forbidden.patterns](line_forbidden.patterns) | Patterns to flag in checked lines | perl regular expression (order matters, first match wins) | [patterns](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-patterns) +[expect.txt](expect.txt) | Expected words that aren't in the dictionary | one word per line (sorted, alphabetically) | [expect](https://github.com/check-spelling/check-spelling/wiki/Configuration#expect) +[advice.md](advice.md) | Supplement for GitHub comment when unrecognized words are found | GitHub Markdown | [advice](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-advice) + +Note: you can replace any of these files with a directory by the same name (minus the suffix) +and then include multiple files inside that directory (with that suffix) to merge multiple files together. diff --git a/.github/actions/spelling/advice.md b/.github/actions/spelling/advice.md new file mode 100644 index 0000000000..54f0c9b5e5 --- /dev/null +++ b/.github/actions/spelling/advice.md @@ -0,0 +1,25 @@ + +

If the flagged items are false positives + +If items relate to a ... +* binary file (or some other file you wouldn't want to check at all). + + Please add a file path to the `excludes.txt` file matching the containing file. + + File paths are Perl 5 Regular Expressions - you can [test]( +https://www.regexplanet.com/advanced/perl/) yours before committing to verify it will match your files. + + `^` refers to the file's path from the root of the repository, so `^README\.md$` would exclude [README.md]( +../tree/HEAD/README.md) (on whichever branch you're using). + +* well-formed pattern. + + If you can write a [pattern](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples:-patterns) that would match it, + try adding it to the `patterns.txt` file. + + Patterns are Perl 5 Regular Expressions - you can [test]( +https://www.regexplanet.com/advanced/perl/) yours before committing to verify it will match your lines. + + Note that patterns can't match multiline strings. + +
diff --git a/.github/actions/spelling/allow.txt b/.github/actions/spelling/allow.txt new file mode 100644 index 0000000000..e69de29bb2 diff --git a/.github/actions/spelling/excludes.txt b/.github/actions/spelling/excludes.txt index fa3ed7c050..1200e9ad0c 100644 --- a/.github/actions/spelling/excludes.txt +++ b/.github/actions/spelling/excludes.txt @@ -1,29 +1,50 @@ +# See https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples:-excludes (?:^|/)(?i)COPYRIGHT (?:^|/)(?i)LICEN[CS]E +(?:^|/)go\.sum$ +(?:^|/)package(?:-lock|)\.json$ (?:^|/)vendor/ /doc/xml/ /html/ /third-party/ ignore$ +\.ai$ +\.avi$ \.bak$ \.bin$ +\.bmp$ +\.bz2$ +\.crt$ \.dat$ \.doc$ \.docx$ +\.DS_Store$ \.eot$ \.gif$ +\.gitattributes$ +\.graffle$ +\.gz$ +\.icns$ +\.ico$ \.inv$ \.jar$ -\.jpg$ +\.jpe?g$ +\.key$ +\.lock$ \.log$ \.map$ \.md5$ \.mdzip$ -\.min\. +\.min\.. +\.mod$ +\.mp[34]$ +\.ocf$ \.otf$ \.pdf$ +\.pem$ \.png$ \.pptx$ +\.psd$ \.rtf$ \.ser$ \.sty$ @@ -31,15 +52,37 @@ ignore$ \.tex$ \.ttf$ \.vm$ +\.vsdx$ +\.wav$ \.woff$ \.woff2$ +\.woff2?$ \.xls$ \.xlsx$ \.xsd$ -\.vsdx$ +\.zip$ ^Autocoders/Python/test/.*\.xml$ ^Autocoders/Python/test/param1/test/ut/Tester\.hpp$ ^config/PolyDbImplCfg\.hpp$ ^config/PrmDbImplTesterCfg\.hpp$ +^Drv/BlockDriver/BlockDriver\.hpp$ +^Drv/LinuxGpioDriver/LinuxGpioDriver\.hpp$ +^Drv/LinuxSpiDriver/LinuxSpiDriver\.hpp$ +^Drv/TcpClient/TcpClient\.hpp$ +^Fw/Types/Linux/StandardTypes\.hpp$ +^requirements\.txt$ ^RPI/settings\.ini$ -^\.github/ +^Svc/LinuxTime/LinuxTime\.hpp$ +^Svc/PrmDb/PrmDb\.hpp$ +^Svc/TlmChan/TlmChan\.hpp$ +^\.github/actions/spelling/ +^\Q.github/workflows/spelling.yml\E$ +^\QDrv/BlockDriver/BlockDriver.hpp\E$ +^\QDrv/LinuxGpioDriver/LinuxGpioDriver.hpp\E$ +^\QDrv/LinuxSpiDriver/LinuxSpiDriver.hpp\E$ +^\QDrv/TcpClient/TcpClient.hpp\E$ +^\QFw/Types/Linux/StandardTypes.hpp\E$ +^\Qrequirements.txt\E$ +^\QSvc/LinuxTime/LinuxTime.hpp\E$ +^\QSvc/PrmDb/PrmDb.hpp\E$ +^\QSvc/TlmChan/TlmChan.hpp\E$ diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index ace6521020..4a985b8e32 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -1,6 +1,4 @@ Aadil -aadl -aarondou abcd ABCDE ABCDEF @@ -9,7 +7,6 @@ ablack abspath ABuffer acconstantsini -Accu accurev AClass ACTIVELOGGER @@ -25,14 +22,10 @@ acxz addoffset addon adminlist -adoc aeiouy afterstatinfo agg aheared -alignedallocator -AlignedAllocator -ALIGNEDALLOCATOR ALLEXTERNALS alloc Alltypes @@ -70,7 +63,6 @@ arijitdas arinc arity arpa -asciidoctor asm aspx ASTRING @@ -91,8 +83,8 @@ autocoders autocoding autocomplete autocompletion -autodetect autodoc +Autodocumentation autogen Autogenerate autogenerated @@ -100,8 +92,6 @@ autogenerator AUTOLINK autoload automodule -autonumbering -awt AYYYY backend backslashreplace @@ -112,9 +102,6 @@ basestring bashcompinit Bassic batchmode -bavail -bbd -bc bcm BDV bfree @@ -122,12 +109,10 @@ bibtex Bies bindir Bitfields -bithacks bitmaps bitset ble blog -BLSP BLSPSERIALDRIVERCOMPONENTIMPLCFG bocchino bodychars @@ -135,7 +120,6 @@ bodytext bools boolt bootlin -bootup brc bre bsd @@ -160,7 +144,6 @@ callergraph callgraph caltech Campuzano -capout carg caselessmatch cassert @@ -190,7 +173,6 @@ cheetahtemplate CHK chmod CHNG -chown chr chrono ci @@ -199,10 +181,8 @@ cinttypes CIRCULARSTATE classdiagram classdoc -Classloader classmethod classname -classpath classtype climits clion @@ -230,27 +210,24 @@ colno COLORSTYLE colorwheel comlogger -compat COMMANDDISPATCHERIMPL COMMANDDISPATCHERIMPLCFG commandline commasepitem commonpath COMPACKET -componentaction COMPONENTTESTERIMPL -compositestructures -compxml COMSPLITTER -concat +Concat config configparser +configs configurability -configurator cookiecutter cooldown coor coravy +coreutils cosmosgen cout cov @@ -272,7 +249,6 @@ crckermit CRCs crcstat CREATEDIRECTORY -creatingdocsetswithdoxygen cron Crosscompiling crt @@ -281,6 +257,7 @@ cryptsoft Csharp csignal CSIZE +cspell css cstat cstdarg @@ -337,10 +314,10 @@ deque deregistration deser Deserial -deserializer deserialization deserialize deserialized +deserializes deserializing dest DEVNULL @@ -357,18 +334,16 @@ difflib diffs diles dinkel -Dinstall dirent dirname dirpath dirs DISF Divs -dll +django dlog dnp DNs -doall docblocks docbook dockerfile @@ -376,8 +351,6 @@ docset docstring doctag doinit -Donatas -donsim dontcare dontinclude DONTNEED @@ -385,7 +358,6 @@ doodie DOTALL dotfile DOTFONTPATH -Doubek downcall downcase downfiles @@ -428,7 +400,6 @@ EBADF EBUSY ECLIPSEHELP ECONNRESET -ecore ect EDQUOT edu @@ -475,7 +446,6 @@ enumparam eobj eol EPERM -eps EROFS errfile errmsg @@ -483,9 +453,7 @@ errno ERRORCHECK errorlevel errornum -errstr ert -esac etime ETIMEDOUT etree @@ -513,6 +481,7 @@ fcheck fclose fcntl fd +fds fdset featuredarticles FEEDNAME @@ -533,6 +502,8 @@ filepath filesize FILESTUBS filesystem +filesystems +filetypes finalizer findall fio @@ -551,18 +522,14 @@ foodoodiehoo fopen foreach formatline -foundin fpconfighpp FPGA fpi fpl -FPL fpp fppi FPport -fprim fprime -FPRIMEPROTOCOL fprintf fprofile fptr @@ -579,6 +546,7 @@ fstrength fsw fsync ftest +fullstack func functools fus @@ -604,26 +572,21 @@ getcontext getcwd getdata getdefaultencoding -getenv getextern -gethostbyname gethostname getinput getitem getline -getmtime getopt getoutput getpass getpid -getppid getquaternion getroot getsize getsockname getstate getstatus -gettempdir gettime gettimeofday getty @@ -634,11 +597,9 @@ github gjslint glibc globals -gmail gmtime Gnc -Gnd -GNDIF +gnd GNUC gnueabihf google @@ -652,14 +613,11 @@ grayscales grep grnd GROUNDINTERFACERULES -groupadd groupdict -groupmod gse gsub gtags gtest -GTestbase gui Guire gz @@ -668,7 +626,6 @@ hardtoaccess hasattr hashlib hashvalue -hdp Heade HEADERSIZE headlessly @@ -689,8 +646,6 @@ hideinitializer hlp HLTH Hofman -HOMEPAGE -hostent hostname hpp href @@ -707,9 +662,9 @@ hu huey Huynh HVisitor -HWriter hxx hyperlink +hyperlinks hypermail hz iadd @@ -718,7 +673,6 @@ idl idx ieeetr iface -ifchange ifcomment ifdef iflag @@ -726,10 +680,8 @@ ifname ifndef ifstr ifstream -IFXML ignorables iif -IJET imap ime img @@ -740,7 +692,6 @@ importables INADDR iname inbool -includefile inet ini inin @@ -751,20 +702,16 @@ inkscape inl ino inode -inorder INPCK Inputline installable -INSTALLDIR -instanceof instantiator instring instrlen integertypename -interoperability intlimits ints -Inttype +inttype invisi ioc ioctl @@ -787,10 +734,7 @@ isdigit isdir isequal isf -isfgen isfile -isfpluginexec -isfxmlwriter isgenerator ishii isinstance @@ -802,7 +746,6 @@ isspace issubclass isupper ITAR -itcl itimerspec itle itr @@ -814,24 +757,15 @@ ixor ixx janamian jasonduley -javabuilder -javac javadoc -javanature javascript -javax Jax jdk jdperez -jdt jenkins jenkinsci -jf -JFile jishii -jmi jobrestrictions -JOption joshuaa jpg jpl @@ -841,10 +775,8 @@ jsdelivr JSO json jsonable -junit keepalive kermit -kevensen kevin kislyuk kitware @@ -900,7 +832,6 @@ loglvl LOGPACKET logpath lon -longdesc Lps lpthread lrt @@ -914,8 +845,8 @@ LTIMER LTLT LVL lxml +macos MACROFILE -magicdraw mailto maincpp mainpage @@ -937,16 +868,8 @@ maxspew mccabe mcomment MCT -mcternan mday -mdbasiccomponents MDFILE -mdinternalstructures -mdkernel -mdports -mdprofiles -mdxml -mdzip Mehran MEMALLOCATOR memb @@ -956,15 +879,12 @@ memcmp memcpy meminfo memname -memoization -memoize memoizing memset MEMTEST mentations mereweth Merewether -metadata methoddoc methodname methodstub @@ -982,11 +902,9 @@ MMAPALLOCATOR MMD MML mname -mngr modbus MOSI MOVEFILE -mpmcs mq mqd mqueue @@ -994,7 +912,6 @@ Mrf Msap msc mscfile -mscgen mseconds msecs msgs @@ -1024,27 +941,22 @@ namespace nano nanosleep nargs -nasafprime nathan nbits nbsp ncsl NDELAY ndiffs -netdb Netscape -Netscape's newloc newroot newself newstring newtio nfds -NGAT -nh +Nh Nicolich ninjaaron -nio NMEA nmsgs noargport @@ -1053,12 +965,11 @@ NOCTTY nodemon nogen nolog -nomagic nonblock noncomma -nondetached NONINFRINGEMENT Nop +noreply noreturn normalwidths normpath @@ -1073,7 +984,6 @@ NOTYPE Nowicki npm nproc -nroff NSHUFF NSPACES nukenewlines @@ -1092,13 +1002,11 @@ oflag okidocki oldeol OMG -OMG's onchange onlinepubs OPCODEBASE opcodes opendir -openjdk opengroup openmct openpyxl @@ -1115,7 +1023,6 @@ ORhex origfile origstatinfo ortega -OS'es OSAL osaves osets @@ -1131,7 +1038,6 @@ outdir outout overridable ovr -ovrTrace packetization packetize packetized @@ -1152,7 +1058,6 @@ pcomp pdb pdf pdflatex -peeker Peet perl PERLMOD @@ -1164,13 +1069,12 @@ PINGSEND pinit pkill pkts -placeholders plainnat plantuml plugin -PLUGINDIR pname png +PNGs pollerr pollfd POLLIN @@ -1186,7 +1090,6 @@ PORTSELECTOR PORTSOUT posix ppandian -ppid pport PQueue Prashanth @@ -1196,13 +1099,11 @@ preds pregen preloc preparse -Prepends prepeneding pri PRId printables printf -println prioritization PRIu prm @@ -1220,9 +1121,7 @@ projectname projectnumber propget propput -propvals PROT -PROTOCOLINTERFACE protothreading prototypetext pstr @@ -1247,10 +1146,10 @@ pyflakes pylama pylint pymod -Pymodule pyparsing -PYPI +PYS pytest +pytests PYTHONPATH pyw qch @@ -1298,10 +1197,10 @@ recvfrom reder refactor refactoring -refman refspec regex regexp +regexs relaxng relpath REMOVEDIRECTORY @@ -1318,7 +1217,6 @@ rewinddir rfind RGD RGDRV -RHEL RHH ridgerun riverbankcomputing @@ -1328,11 +1226,11 @@ rmtree rng rootdir ror +rp rpaetz rpi RPIDEMO RPIDEMOCOMPONENTIMPLCFG -RPISCHEDCONTEXTS rptr RSend rstrip @@ -1348,7 +1246,6 @@ RXD rxor saddr Saikiran -saikiranra Sanchit sats savelist @@ -1368,7 +1265,6 @@ scons scp scrollbars sdd -seander searchdata SEARCHENGINE segfault @@ -1419,7 +1315,6 @@ sighandler SIGINT SIGSEGV SIGTERM -Simkunas SIMPLEQUEUEREGISTRY sinc Sinha @@ -1433,7 +1328,6 @@ sockaddr SOCKETHELPER SOCKETIPDRIVER SOCKETIPDRIVERCFG -SOCKETIPDRIVERTYPES SOCKETREADTASK socklen somechan @@ -1457,8 +1351,6 @@ splitext splitlines sprintf Sqlite -SQL's -sramanan srand srandom srange @@ -1478,9 +1370,8 @@ standardpipeline startloc startswith startuml -startword -staticmethod statfs +staticmethod statvfs STDC stddef @@ -1491,9 +1382,7 @@ stdio stdlib stdout stest -strcat strcmp -strcpy STREQ STREQUAL strerror @@ -1503,7 +1392,6 @@ stri stringbuffer stringchan stringified -Stringify Stringpacket stringparam STRINGUTILS @@ -1523,7 +1411,6 @@ subfolder subgrouping subhist subhistory -submenu subpage subseconds subtargets @@ -1553,7 +1440,6 @@ tcanham tcflush tcgetattr TCIFLUSH -tcl tclist tcomp tcp @@ -1571,7 +1457,6 @@ TELEMCHANIMPL TELEMSTORECOMPONENTCOMP tempfile templated -templating termios testcase testcmd @@ -1583,11 +1468,9 @@ testdata testdir testerbase testgen -testhpp testimpl TESTLIST TESTLOGRECVIMPL -Testname TESTPARAMIMPL TESTPARAMRECVIMPL TESTPTSOURCEIMPL @@ -1598,7 +1481,6 @@ TESTTEXTLOGIMPL TESTTIMEIMPL testutdir TESTUTILS -textui tfile tflat tfn @@ -1622,7 +1504,6 @@ timothycanham tions tjh TKC -tkgui tl tlc tlist @@ -1639,15 +1520,12 @@ tlmval TLOG TML tmp -tmpd -tmpdir tmpl tmptokens tmptree tname tnum toc -toclevels toctree todo TODOLIST @@ -1658,8 +1536,8 @@ tokenized tokenlist toklist TOLOWER -toolbar toolchain +toolchains tooltip topologyapp Torvalds @@ -1676,11 +1554,12 @@ trinomials TRUNC truncstring tt +tts ttype Tuszynski TXD -typedef typedef'ed +typedef typeid typeinfo typelist @@ -1701,10 +1580,8 @@ UDPSENDER UDPSENDERCOMPONENTIMPLCFG UDPSOCKET uint -uk -ul ulimit -uml +UML uname uncomment undef @@ -1732,8 +1609,6 @@ usb usec usecond usepackage -useradd -usermod usleep usr ustr @@ -1746,7 +1621,6 @@ valgrind validator vals valud -ve venv VERSIONED versioning @@ -1759,16 +1633,13 @@ VID viewforum virt virtualbox -virtualenv virtualization virtualized vla vlist vm -vmstat -vmsize VMIN -vn +vmstat vsnprintf VTIME vtype @@ -1779,37 +1650,36 @@ vx vxworks VXWORKSLOGASSERT WAITALL -watney +Watney +Wconversion Wdog weakref website Werror Wextra +Wformat wget whitebox whitelist +Whitelisted wiki wikipedia wildcards WLE Wno Wnon -workaround WORKDIR workflow worklist -workspaces +Woverloaded wp writelines WRONLY -Wconversion -Wformat -Woverloaded +wrs Wshadow Wsign -Wundef -wrs WSL +Wundef www wx wxgui @@ -1827,14 +1697,12 @@ xlsx xml xmlfile xmlns -Xmx +xmls xoff xon xor XPath xsh -Xss -Xvfb xxxx XYZZY yacc diff --git a/.github/actions/spelling/line_forbidden.patterns b/.github/actions/spelling/line_forbidden.patterns new file mode 100644 index 0000000000..4ca15837cc --- /dev/null +++ b/.github/actions/spelling/line_forbidden.patterns @@ -0,0 +1,39 @@ +# reject `m_data` as there's a certain OS which has evil defines that break things if it's used elsewhere +# \bm_data\b + +# s.b. GitHub +\bGithub\b + +# s.b. GitLab +\bGitlab\b + +# s.b. JavaScript +\bJavascript\b + +# s.b. Microsoft +\bMicroSoft\b + +# s.b. another +\ban[- ]other\b + +# s.b. greater than +\bgreater then\b + +# s.b. less than +\bless then\b + +# s.b. otherwise +\bother[- ]wise\b + +# s.b. nonexistent +\bnon existing\b +\b[Nn]o[nt][- ]existent\b + +# s.b. preexisting +[Pp]re-existing + +# s.b. preemptively +[Pp]re-emptively + +# Reject duplicate words +\s([A-Z]{3,}|[A-Z][a-z]{2,}|[a-z]{3,})\s\g{-1}\s diff --git a/.github/actions/spelling/patterns.txt b/.github/actions/spelling/patterns.txt index dff41acb2b..6241a7b50b 100644 --- a/.github/actions/spelling/patterns.txt +++ b/.github/actions/spelling/patterns.txt @@ -52,3 +52,17 @@ value="(?:[0-9a-f]{1,2} )*" # slashes after spaces are not in paths LaTeX \\.* \\ + +# acceptable duplicates +# ls directory listings +[-bcdlpsw](?:[-r][-w][-sx]){3}\s+\d+\s+(\S+)\s+\g{-1}\s+\d+\s+ +# C types +\s(expr|long|LONG|Time)(?:\s+\g{-1})+\s +# javadoc / .net +(?:[\\@](?:groupname|page|param)|(?:public|private)(?:\s+static|\s+readonly)*)\s+(\w+)\s+\g{-1}\s + +# Jenkins library +GithubProjectProperty + +# ignore long runs of a single character: +\b([A-Za-z])\g{-1}{3,}\b diff --git a/.github/actions/spelling/reject.txt b/.github/actions/spelling/reject.txt new file mode 100644 index 0000000000..b5a6d36809 --- /dev/null +++ b/.github/actions/spelling/reject.txt @@ -0,0 +1,10 @@ +^attache$ +benefitting +occurences? +^dependan.* +^oer$ +Sorce +^[Ss]pae.* +^untill$ +^untilling$ +^wether.* diff --git a/.github/workflows/spelling.yml b/.github/workflows/spelling.yml index bed7f151c1..07147842a2 100644 --- a/.github/workflows/spelling.yml +++ b/.github/workflows/spelling.yml @@ -15,17 +15,45 @@ on: jobs: spelling: name: Spell checking + permissions: + contents: read + pull-requests: read + actions: read + outputs: + followup: ${{ steps.spelling.outputs.followup }} runs-on: ubuntu-latest + if: "contains(github.event_name, 'pull_request') || github.event_name == 'push'" + concurrency: + group: spelling-${{ github.event.pull_request.number || github.ref }} + # note: If you use only_check_changed_files, you do not want cancel-in-progress + cancel-in-progress: true steps: - - name: checkout-merge - if: "contains(github.event_name, 'pull_request')" - uses: actions/checkout@v2 - with: - ref: refs/pull/${{github.event.pull_request.number}}/merge - - name: checkout - if: ${{ github.event_name == 'push' }} - uses: actions/checkout@v2 - - uses: check-spelling/check-spelling@v0.0.19 + - name: check-spelling id: spelling + uses: check-spelling/check-spelling@v0.0.20 + with: + suppress_push_for_open_pull_request: 1 + checkout: true + post_comment: 0 + extra_dictionaries: + cspell:filetypes/filetypes.txt + cspell:python/python.txt + cspell:django/django.txt + cspell:html/html.txt + cspell:fullstack/fullstack.txt + check_extra_dictionaries: '' + + comment: + name: Report + runs-on: ubuntu-latest + needs: spelling + permissions: + contents: write + pull-requests: write + if: (success() || failure()) && needs.spelling.outputs.followup + steps: + - name: comment + uses: check-spelling/check-spelling@v0.0.20 with: - shortest_word: 2 + checkout: true + task: ${{ needs.spelling.outputs.followup }} diff --git a/Autocoders/Python/test/pass_by_kind/main.cpp b/Autocoders/Python/test/pass_by_kind/main.cpp index 0bec05e48b..7e50086902 100644 --- a/Autocoders/Python/test/pass_by_kind/main.cpp +++ b/Autocoders/Python/test/pass_by_kind/main.cpp @@ -26,7 +26,7 @@ TEST(PassByTest, OK) { Example::AllTypes async_args(true); Example::AllTypes sync_args(false); - // Invoke sync and async ports and pass pass arguments + // Invoke sync and async ports and pass arguments inst1.get_AsyncPort_InputPort(0)->invoke( &async_args.arg1, async_args.arg2, diff --git a/Autocoders/Python/test/testgen/test/ut/Tester.cpp b/Autocoders/Python/test/testgen/test/ut/Tester.cpp index a41b0f45f0..b39af3ba10 100644 --- a/Autocoders/Python/test/testgen/test/ut/Tester.cpp +++ b/Autocoders/Python/test/testgen/test/ut/Tester.cpp @@ -35,7 +35,7 @@ namespace Ref { this->sendCmd_MS_DO_MATH(0,10,1.0,2.0,MathSenderComponentBase::ADD); // retrieve the message from the message queue and dispatch the command to the handler this->component.doDispatch(); - // verify that that only one output port was called + // verify that only one output port was called ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was only called once ASSERT_from_mathOut_SIZE(1); @@ -89,7 +89,7 @@ namespace Ref { this->sendCmd_MS_DO_MATH(0,10,1.0,2.0,MathSenderComponentBase::SUBTRACT); // retrieve the message from the message queue and dispatch the command to the handler this->component.doDispatch(); - // verify that that only one output port was called + // verify that only one output port was called ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was only called once ASSERT_from_mathOut_SIZE(1); @@ -143,7 +143,7 @@ namespace Ref { this->sendCmd_MS_DO_MATH(0,10,1.0,2.0,MathSenderComponentBase::MULTIPLY); // retrieve the message from the message queue and dispatch the command to the handler this->component.doDispatch(); - // verify that that only one output port was called + // verify that only one output port was called ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was only called once ASSERT_from_mathOut_SIZE(1); @@ -197,7 +197,7 @@ namespace Ref { this->sendCmd_MS_DO_MATH(0,10,1.0,2.0,MathSenderComponentBase::DIVIDE); // retrieve the message from the message queue and dispatch the command to the handler this->component.doDispatch(); - // verify that that only one output port was called + // verify that only one output port was called ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was only called once ASSERT_from_mathOut_SIZE(1); diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 9080ceb8ac..f0841a259f 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -125,7 +125,7 @@ Large submissions are difficult to review. Incredibly large pull requests can be to be broken up. Try to keep submissions small, focus on one issue or change in a pull request, and avoid lots of minor changes across many files. -Keep in mind that editors that fix whitespace automatically can cause many small changes. Even with advanced Github +Keep in mind that editors that fix whitespace automatically can cause many small changes. Even with advanced GitHub tools this can increase the effort required to review a submission. Be careful with the changes you are submitting. ## Run Tests diff --git a/Fw/Buffer/docs/sdd.md b/Fw/Buffer/docs/sdd.md index fa32ec3a3a..4dba905ea1 100644 --- a/Fw/Buffer/docs/sdd.md +++ b/Fw/Buffer/docs/sdd.md @@ -30,7 +30,7 @@ Name | Type | Accessors | Purpose `m_context` | `U32` | `getContext()`/`setContext()` | Context of buffer's origin. Used to track buffers created by [`BufferManager`](../../../Svc/BufferManager/docs/sdd.md) `m_serialize_repr` | `Fw::ExternalSerializeBuffer` | `getSerializeRepr()` | Interface for serialization to internal buffer -If the size of the data is set to 0, the pointer returned by `getData()` and the the serialization interface returned by +If the size of the data is set to 0, the pointer returned by `getData()` and the serialization interface returned by `getSerializeRepr()` are considered invalid and should not be used. The `getSerializeRepr()` function may be used to interact with the wrapped data buffer by serializing types to and from diff --git a/Svc/ActiveRateGroup/ActiveRateGroup.cpp b/Svc/ActiveRateGroup/ActiveRateGroup.cpp index 5d996dac42..42a9b82b42 100644 --- a/Svc/ActiveRateGroup/ActiveRateGroup.cpp +++ b/Svc/ActiveRateGroup/ActiveRateGroup.cpp @@ -94,7 +94,7 @@ namespace Svc { this->log_WARNING_HI_RateGroupCycleSlip(this->m_cycles); this->m_overrunThrottle++; } - // update cycle cycle slips + // update cycle slips this->tlmWrite_RgCycleSlips(this->m_cycleSlips); } else { // if cycle is okay start decrementing throttle value if (this->m_overrunThrottle > 0) { diff --git a/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp b/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp index 36e5f32c18..2cbea4117b 100644 --- a/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp +++ b/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp @@ -86,7 +86,7 @@ namespace Svc { this->log_WARNING_HI_RateGroupCycleSlip(this->m_cycles); this->m_overrunThrottle++; } - // update cycle cycle slips + // update cycle slips this->tlmWrite_RgCycleSlips(this->m_cycleSlips); } else { // if cycle is okay start decrementing throttle value if (this->m_overrunThrottle > 0) { diff --git a/Svc/PrmDb/test/ut/PrmDbTester.cpp b/Svc/PrmDb/test/ut/PrmDbTester.cpp index c5d52a31d5..8c41e92d72 100644 --- a/Svc/PrmDb/test/ut/PrmDbTester.cpp +++ b/Svc/PrmDb/test/ut/PrmDbTester.cpp @@ -123,7 +123,7 @@ TEST(ParameterDbTest,NominalFileLoadTest) { TEST(ParameterDbTest,PrmMissingExtraParamsTest) { TEST_CASE(105.2.1,"Missing and too many parameters test"); - COMMENT("Attempt to read a non-existent parameter and write too many parameters"); + COMMENT("Attempt to read a nonexistent parameter and write too many parameters"); Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); diff --git a/Svc/TlmChan/docs/sdd.md b/Svc/TlmChan/docs/sdd.md index d8cf3ccc1a..31c612a0f4 100644 --- a/Svc/TlmChan/docs/sdd.md +++ b/Svc/TlmChan/docs/sdd.md @@ -44,7 +44,7 @@ Port Data Type | Name | Direction | Kind | Usage The `Svc::TlmChan` component has an input port `TlmRecv` that receives channel updates from other components in the system. These calls from the other components are made by the component implementation classes, but the generated code in the base classes takes the type specific channel value and serializes it, then makes the call to the output port. The `Svc::TlmChan` component can then store the channel value as generic data. The channel values are stored in an internal double-buffered table, and a flag is set when a new value is written to the channel entry. -When a request is made for a non-existent channel, the call will return with an empty buffer in the Fw::TlmBuffer value argument. This is to cover the case where a channel is defined in the system, but has not been written yet. If the channel has not ever been defined, there is no way to programmatically determine that from the TlmGet port call. +When a request is made for a nonexistent channel, the call will return with an empty buffer in the Fw::TlmBuffer value argument. This is to cover the case where a channel is defined in the system, but has not been written yet. If the channel has not ever been defined, there is no way to programmatically determine that from the TlmGet port call. The implementation uses a hashing function that is tuned in the configuration file `TlmChanImplCfg.hpp`. See section 3.5 for description. diff --git a/cmake/API.cmake b/cmake/API.cmake index a7688192e1..9621bf807d 100644 --- a/cmake/API.cmake +++ b/cmake/API.cmake @@ -386,7 +386,7 @@ function(register_fprime_ut) message(FATAL_ERROR "register_fprime_ut accepts only one optional argument: test name") endif() get_module_name(${CMAKE_CURRENT_LIST_DIR}) - # UT name is passed in or is the the module name with _ut_exe added + # UT name is passed in or is the module name with _ut_exe added if (${ARGC} GREATER 0) set(UT_NAME "${ARGV0}") elseif (NOT DEFINED UT_NAME) diff --git a/cmake/autocoder/ai_xml.cmake b/cmake/autocoder/ai_xml.cmake index c9579a570d..007ddf344b 100644 --- a/cmake/autocoder/ai_xml.cmake +++ b/cmake/autocoder/ai_xml.cmake @@ -2,7 +2,7 @@ # autocoder/ai-xml.cmake # # Primary Ai XML autocoder that sets up the C++ file generation. This is a implementation of the singular autocoder -# setup of the the original CMake system. It process AI XML files and produces the autocoder output files Ac.hpp and +# setup of the original CMake system. It process AI XML files and produces the autocoder output files Ac.hpp and # Ac.cpp files. ##### include(utilities) diff --git a/cmake/target/default.cmake b/cmake/target/default.cmake index 9e21936a68..79a64ed69d 100644 --- a/cmake/target/default.cmake +++ b/cmake/target/default.cmake @@ -20,7 +20,7 @@ endfunction(add_global_target) #### # `add_deployment_target`: # -# The default deployment target is a target which rolls-up all dependant targets through recursion. +# The default deployment target is a target which rolls-up all dependent targets through recursion. # - **MODULE:** name of the deployment module. This is usually equivalent to $PROJECT_NAME. # - **TARGET:** name of the top-target (e.g. dict). Use ${MODULE_NAME}_${TARGET_NAME} for a module specific target # - **SOURCE:** list of source file inputs from the CMakeList.txt setup diff --git a/cmake/utilities.cmake b/cmake/utilities.cmake index 296f425719..0435934d66 100644 --- a/cmake/utilities.cmake +++ b/cmake/utilities.cmake @@ -279,7 +279,7 @@ endfunction() # but will be supplied as link libraries. These tokens are of several types: # # 1. Linker flags: starts with -l -# 2. Existing Files: accounts for pre-existing libraries shared and otherwise +# 2. Existing Files: accounts for preexisting libraries shared and otherwise # # OUTPUT_VAR: variable to set in PARENT_SCOPE to TRUE/FALSE # TOKEN: token to check if "linker only" diff --git a/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp b/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp index 2b2955c9f7..77f9279520 100644 --- a/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp +++ b/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp @@ -144,7 +144,7 @@ namespace Ref { // Verify operation request on mathOpOut - // verify that that one output port was invoked overall + // verify that one output port was invoked overall ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was invoked once ASSERT_from_mathOpOut_SIZE(1); diff --git a/docs/Tutorials/MathComponent/Tutorial.md b/docs/Tutorials/MathComponent/Tutorial.md index da727b8382..335ae1838b 100644 --- a/docs/Tutorials/MathComponent/Tutorial.md +++ b/docs/Tutorials/MathComponent/Tutorial.md @@ -908,7 +908,7 @@ void Tester :: // Verify operation request on mathOpOut - // verify that that one output port was invoked overall + // verify that one output port was invoked overall ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was invoked once ASSERT_from_mathOpOut_SIZE(1); diff --git a/docs/Tutorials/MathComponent/md/Tutorial.md b/docs/Tutorials/MathComponent/md/Tutorial.md index 7257ae5531..97c161b4b9 100644 --- a/docs/Tutorials/MathComponent/md/Tutorial.md +++ b/docs/Tutorials/MathComponent/md/Tutorial.md @@ -714,7 +714,7 @@ void Tester :: // Verify operation request on mathOpOut - // verify that that one output port was invoked overall + // verify that one output port was invoked overall ASSERT_FROM_PORT_HISTORY_SIZE(1); // verify that the math operation port was invoked once ASSERT_from_mathOpOut_SIZE(1); diff --git a/docs/UsersGuide/best/ground-interface.md b/docs/UsersGuide/best/ground-interface.md index 2b9db7ac79..a02fb85492 100644 --- a/docs/UsersGuide/best/ground-interface.md +++ b/docs/UsersGuide/best/ground-interface.md @@ -193,6 +193,6 @@ described int the ByteStreamDriverModel. These ports are called out in the belo 1. **ready**: (output) drivers call this port without arguments to signal it is ready to receive data via the send port. 2. **send**: (input) clients call this port passing in an `Fw::Buffer` to send data. -3. **recv**: (output) drivers operating in asynchronous mode call this port with a RecvStatus and and `Fw::Buffer` to +3. **recv**: (output) drivers operating in asynchronous mode call this port with a RecvStatus and `Fw::Buffer` to provide data. 4. **poll**: (input) drivers operating in poll mode fill an `Fw::Buffer` and return a PollStatus to provide data. diff --git a/docs/UsersGuide/gds/gds-introduction.md b/docs/UsersGuide/gds/gds-introduction.md index be5dd86735..b720c3a971 100644 --- a/docs/UsersGuide/gds/gds-introduction.md +++ b/docs/UsersGuide/gds/gds-introduction.md @@ -167,7 +167,7 @@ optional arguments: -d DEPLOY, --deployment DEPLOY Deployment directory for detecting dict, app, and logging. [default: /Users/mstarch] - -l LOGS, --logs LOGS Logging directory. Created if non-existent. Default: + -l LOGS, --logs LOGS Logging directory. Created if nonexistent. Default: deployment directory. --log-directly Logging directory is used directly, no extra dated directories created. diff --git a/docs/doxygen/Doxyfile b/docs/doxygen/Doxyfile index 20ac07d539..0079c4ca4d 100644 --- a/docs/doxygen/Doxyfile +++ b/docs/doxygen/Doxyfile @@ -730,7 +730,7 @@ SHOW_NAMESPACES = YES # The FILE_VERSION_FILTER tag can be used to specify a program or script that # doxygen should invoke to get the current version for each file (typically from # the version control system). Doxygen will invoke the program by executing (via -# popen()) the command command input-file, where command is the value of the +# popen()) the command input-file, where command is the value of the # FILE_VERSION_FILTER tag, and input-file is the name of an input file provided # by doxygen. Whatever the program writes to standard output is used as the file # version. For an example see the documentation. From ac3c67480c422311bb24733cb3a9a93b423c195b Mon Sep 17 00:00:00 2001 From: Ani Date: Wed, 3 Aug 2022 00:28:36 -0700 Subject: [PATCH 042/169] Use the original sourcing command '.' for compatibility with shells where 'source' isn't defined (#1605) * Avoid use of the alias for sourcing * Change the ones in the other two spots --- docs/INSTALL.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/INSTALL.md b/docs/INSTALL.md index b75205a03f..b1f502afad 100644 --- a/docs/INSTALL.md +++ b/docs/INSTALL.md @@ -42,11 +42,11 @@ use the path: `$HOME/fprime-venv` ``` python3 -m venv $HOME/fprime-venv -source $HOME/fprime-venv/bin/activate +. $HOME/fprime-venv/bin/activate pip install -U setuptools setuptools_scm wheel pip ``` -> Note: `source $HOME/fprime-venv/bin/activate` must be run in each new terminal where the user wishes to use the virtual environment. +> Note: `. $HOME/fprime-venv/bin/activate` must be run in each new terminal where the user wishes to use the virtual environment. ### Cloning the F´ Repository and Installing F´ Tools @@ -144,7 +144,7 @@ If the user is using a virtual environment and receives the command not found, t environment not being sourced in a new terminal. Make sure to source the environment before running: ``` -source $HOME/fprime-venv/bin/activate +. $HOME/fprime-venv/bin/activate ``` If installing without a virtual environment, PIP occasionally uses `$HOME/.local/bin` as a place to install user tools. From 7f6f0a2df496652044b32e106845882295fb50f7 Mon Sep 17 00:00:00 2001 From: Josh Soref <2119212+jsoref@users.noreply.github.com> Date: Wed, 3 Aug 2022 03:31:55 -0400 Subject: [PATCH 043/169] Fix Autodocumentation (+ ci tweaks) (#1599) * Provide -y flag to apt-get Sometimes apt-get will run in a mode where it thinks it can ask a user a yes/no question. If this happens, the build will get stuck... * Use default commit message for merge Sometimes the CI might run in some manner where it thinks it might have a terminal, but does not really have one. These commands do not want to talk to a user. * Update spelling expect file Now that check-spelling 0.0.20 is running... * Make doc image files unique Currently fprime/docs/doxygen/generate_docs.bash puts all images into a single directory. --- .github/actions/autodoc.bash | 2 +- .github/actions/spelling/expect.txt | 168 ------------------ .github/workflows/autodocs.yml | 2 +- .../img/top/{file.json => deframer-file.json} | 0 .../img/top/{file.png => deframer-file.png} | Bin .../img/top/{file.txt => deframer-file.txt} | 0 Svc/Deframer/docs/sdd.md | 2 +- .../img/top/{file.json => framer-file.json} | 0 .../img/top/{file.png => framer-file.png} | Bin .../img/top/{file.txt => framer-file.txt} | 0 Svc/Framer/docs/sdd.md | 2 +- ci/config.xml | 2 +- 12 files changed, 5 insertions(+), 173 deletions(-) rename Svc/Deframer/docs/img/top/{file.json => deframer-file.json} (100%) rename Svc/Deframer/docs/img/top/{file.png => deframer-file.png} (100%) rename Svc/Deframer/docs/img/top/{file.txt => deframer-file.txt} (100%) rename Svc/Framer/docs/img/top/{file.json => framer-file.json} (100%) rename Svc/Framer/docs/img/top/{file.png => framer-file.png} (100%) rename Svc/Framer/docs/img/top/{file.txt => framer-file.txt} (100%) diff --git a/.github/actions/autodoc.bash b/.github/actions/autodoc.bash index 1916638c9d..e5a496e591 100755 --- a/.github/actions/autodoc.bash +++ b/.github/actions/autodoc.bash @@ -11,7 +11,7 @@ git config --local user.name "nasa-fprime[bot]" git fetch "${REMOTE}" release/documentation git fetch "${REMOTE}" devel git checkout release/documentation -git merge "${REMOTE}"/devel +GIT_EDITOR=true git merge "${REMOTE}"/devel ${GITHUB_WORKSPACE}/docs/doxygen/generate_docs.bash git add -Af "${GITHUB_WORKSPACE}/docs" diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 4a985b8e32..abd3544472 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -5,7 +5,6 @@ ABCDEF abcdefghijklmnopqrstuvwxyz ablack abspath -ABuffer acconstantsini accurev AClass @@ -43,7 +42,6 @@ APIDOCS aports apos APPENDFILE -apps aps apxs AQuat @@ -55,16 +53,12 @@ argcount arglist ARGN argname -argparse -args argtype argv arijitdas arinc -arity arpa asm -aspx ASTRING asyc asynch @@ -81,13 +75,11 @@ autocode autocoded autocoders autocoding -autocomplete autocompletion autodoc Autodocumentation autogen Autogenerate -autogenerated autogenerator AUTOLINK autoload @@ -134,9 +126,7 @@ bugprone builddir buildroot builtins -bw bysource -bytearray BYTEDRV calcu callee @@ -159,7 +149,6 @@ cdn cerrno cface CFDP -cfg cflag cfsetispeed cfsetospeed @@ -168,20 +157,15 @@ changelog changeme CHANNELID chdir -checkbox cheetahtemplate CHK -chmod CHNG -chr chrono -ci cin cinttypes CIRCULARSTATE classdiagram classdoc -classmethod classname classtype climits @@ -218,8 +202,6 @@ commonpath COMPACKET COMPONENTTESTERIMPL COMSPLITTER -Concat -config configparser configs configurability @@ -237,11 +219,9 @@ Cpkt cplusplus CPOL cpos -cpp cppreference cprogramming cpuset -cpy CRCAMPCS crcccitt crcdnp @@ -257,8 +237,6 @@ cryptsoft Csharp csignal CSIZE -cspell -css cstat cstdarg cstddef @@ -268,7 +246,6 @@ cstdlib CSTOPB cstring csum -csv ctest ctime CTORS @@ -279,7 +256,6 @@ curdir curmsgs cuz cwd -cxx CYCLEOUT cygwin daringfireball @@ -287,7 +263,6 @@ Daruwala DASSERT databinding datastore -datetime dawbarton DBUILD DCMAKE @@ -304,7 +279,6 @@ deframe deframed deframer deframing -delattr delchars delitem deployables @@ -315,7 +289,6 @@ deregistration deser Deserial deserialization -deserialize deserialized deserializes deserializing @@ -325,7 +298,6 @@ DFL DFPRIME DGRAM dhesikan -DHTML diafile dictgen dicts @@ -340,13 +312,11 @@ dirpath dirs DISF Divs -django dlog dnp DNs docblocks docbook -dockerfile docset docstring doctag @@ -372,7 +342,6 @@ Doxywizard dpi DPRIVATE DPROTECTED -dropdown drv drvipsocket drvsocketreadtask @@ -411,7 +380,6 @@ EHAs EINTR EINVAL EISDIR -elif elist ELOG ELOOP @@ -422,16 +390,13 @@ EMSGSIZE ENAMETOOLONG endcode endcond -endfor endforeach endfunction endian endianness -endif endl endloc endmacro -endswith enduml ENOENT ENOSPC @@ -456,16 +421,13 @@ errornum ert etime ETIMEDOUT -etree eturn -ev EVENTID eventname evr evt EXAMPLECOMPONENTIMPL excinfo -exe executables exitcode expandtabs @@ -480,7 +442,6 @@ fallthrough fcheck fclose fcntl -fd fds fdset featuredarticles @@ -490,7 +451,6 @@ fflush Ffs fgetc fgets -fh filecmp filedown FILEDOWNLINK @@ -501,9 +461,7 @@ fileopen filepath filesize FILESTUBS -filesystem filesystems -filetypes finalizer findall fio @@ -546,12 +504,8 @@ fstrength fsw fsync ftest -fullstack -func -functools fus FWCASSERT -gainsboro Gangianpour gbl gcc @@ -564,12 +518,10 @@ genfile GENHUB GENREP genshi -getattr getattribute getbuffer getchildren getcontext -getcwd getdata getdefaultencoding getextern @@ -579,7 +531,6 @@ getitem getline getopt getoutput -getpass getpid getquaternion getroot @@ -591,12 +542,10 @@ gettime gettimeofday getty getuser -gh ghprb github gjslint glibc -globals gmtime Gnc gnd @@ -620,10 +569,8 @@ gtags gtest gui Guire -gz handcoded hardtoaccess -hasattr hashlib hashvalue Heade @@ -636,7 +583,6 @@ hexid hexnums hexopcode HFiles -hh hhc hhk hhp @@ -647,26 +593,17 @@ hlp HLTH Hofman hostname -hpp -href htags HTH -htm -html htmlfile HTMLHELP htonl htons -http -hu huey Huynh HVisitor -hxx -hyperlink hyperlinks hypermail -hz iadd ibd idl @@ -684,7 +621,6 @@ ignorables iif imap ime -img impl imple implgen @@ -693,14 +629,11 @@ INADDR iname inbool inet -ini inin initfiles inits initstate inkscape -inl -ino inode INPCK Inputline @@ -718,7 +651,6 @@ ioctl iomanip ior iostream -ip ipc IPCFG IPHELPER @@ -728,22 +660,17 @@ ipriority ipv IRUSR IRWXU -isabs isalpha isdigit -isdir isequal isf -isfile isgenerator ishii -isinstance isnan isoschematron isr ISREG isspace -issubclass isupper ITAR itimerspec @@ -751,14 +678,12 @@ itle itr itval itype -iu IWRITE ixor ixx janamian jasonduley javadoc -javascript Jax jdk jdperez @@ -767,13 +692,11 @@ jenkinsci jishii jobrestrictions joshuaa -jpg jpl jplffs jre jsdelivr JSO -json jsonable keepalive kermit @@ -789,7 +712,6 @@ LBLOCK LCHILD ldl lemstarch -len lestarch levelname lflag @@ -802,9 +724,6 @@ libgtest libiconv LIBLOC lic -lifecycle -lightgreen -lightyellow lindent lineno lineroo @@ -813,16 +732,13 @@ linting linux LINUXSERIALDRIVER LINUXTIMEIMPL -listdir Listst LJR -ljust lkml lld llvm loadfile localhost -localtime LOCKGUARDTESTER locs LOGASSERT @@ -837,9 +753,7 @@ lpthread lrt lseek lshift -lstrip ltab -lte LTIME LTIMER LTLT @@ -847,10 +761,8 @@ LVL lxml macos MACROFILE -mailto maincpp mainpage -makedirs makefiles makeindex MAKEVAR @@ -890,22 +802,17 @@ methodname methodstub microcontrollers microsoft -middleware mindepth MINGW -mkdir mkdtemp -mlist mman mmap MMAPALLOCATOR MMD MML -mname modbus MOSI MOVEFILE -mq mqd mqueue Mrf @@ -919,10 +826,8 @@ msgsize mstarch mstat mstring -MTIME mtype mul -multiline multioptionals multirequired multline @@ -931,19 +836,14 @@ mutex mutexattr mutexes mval -MVC mycompany myfile myproject -Mypy mytype -namespace nano nanosleep -nargs nathan nbits -nbsp ncsl NDELAY ndiffs @@ -954,7 +854,6 @@ newself newstring newtio nfds -Nh Nicolich ninjaaron NMEA @@ -969,7 +868,6 @@ nonblock noncomma NONINFRINGEMENT Nop -noreply noreturn normalwidths normpath @@ -1002,7 +900,6 @@ oflag okidocki oldeol OMG -onchange onlinepubs OPCODEBASE opcodes @@ -1016,7 +913,6 @@ optarg optind optparse oran -orangered Orgs orgslist ORhex @@ -1036,7 +932,6 @@ otherside outbool outdir outout -overridable ovr packetization packetize @@ -1056,14 +951,10 @@ pbuild pcmake pcomp pdb -pdf pdflatex Peet -perl PERLMOD pexpect -php -phtml pid PINGSEND pinit @@ -1073,7 +964,6 @@ plainnat plantuml plugin pname -png PNGs pollerr pollfd @@ -1088,7 +978,6 @@ portlist PORTOUT PORTSELECTOR PORTSOUT -posix ppandian pport PQueue @@ -1114,7 +1003,6 @@ PRMDBLIMPLCFG prmname probs PROGRAMLISTING -proj projectbrief projectlogo projectname @@ -1137,7 +1025,6 @@ ptype punc pushd pwd -py pycodestyle pydeps pydocstyle @@ -1148,10 +1035,7 @@ pylint pymod pyparsing PYS -pytest pytests -PYTHONPATH -pyw qch QEvent qhelpgenerator @@ -1162,7 +1046,6 @@ qsf qtest qthelpproject quatchan -quickstart RAbrack radd RAII @@ -1174,7 +1057,6 @@ RATEGROUPDRIVER RATEGROUPDRIVERIMPLTESTER RATEGROUPMEMBEROUT RATELIMITERTESTER -rb RBF Rce RCHILD @@ -1185,7 +1067,6 @@ RDONLY rdwr Readback readdir -readline readme readthedocs realloc @@ -1198,7 +1079,6 @@ reder refactor refactoring refspec -regex regexp regexs relaxng @@ -1221,27 +1101,20 @@ RHH ridgerun riverbankcomputing Rizvi -rmdir -rmtree -rng rootdir ror -rp rpaetz rpi RPIDEMO RPIDEMOCOMPONENTIMPLCFG rptr RSend -rstrip rtd rtems -rtf RTOS runcycles runperiod runtest -rx RXD rxor saddr @@ -1276,7 +1149,6 @@ serafin serializables serializer setaffinity -setattr setbuf setbuffer setdata @@ -1308,7 +1180,6 @@ SGN SHELLCOMMAND Shenker showinitializer -shutil sideeffect SIGALRM sighandler @@ -1347,8 +1218,6 @@ SPHINXBUILD SPHINXOPTS spi spidev -splitext -splitlines sprintf Sqlite srand @@ -1368,10 +1237,8 @@ STAMEM standalone standardpipeline startloc -startswith startuml statfs -staticmethod statvfs STDC stddef @@ -1386,7 +1253,6 @@ strcmp STREQ STREQUAL strerror -strftime strg stri stringbuffer @@ -1404,8 +1270,6 @@ strnlen strs strtol strtoul -structs -stylesheet subdir subfolder subgrouping @@ -1417,13 +1281,11 @@ subtargets sudo SVCLOGFILE SVCLOGFILEL -svg svipc swcaegitadmin SYMLINKS synchronicity synopsys -sys SYSFS sysinfo systemd @@ -1449,7 +1311,6 @@ tcpserver TCSANOW tcsetattr tcsh -td tdir tdirection telem @@ -1499,12 +1360,10 @@ TIMERVAL timespec timetag timeval -timezone timothycanham tions tjh TKC -tl tlc tlist tlm @@ -1519,13 +1378,10 @@ TLMPACKETIZERTYPES tlmval TLOG TML -tmp -tmpl tmptokens tmptree tname tnum -toc toctree todo TODOLIST @@ -1536,9 +1392,7 @@ tokenized tokenlist toklist TOLOWER -toolchain toolchains -tooltip topologyapp Torvalds tostring @@ -1553,7 +1407,6 @@ trimwhitespace trinomials TRUNC truncstring -tt tts ttype Tuszynski @@ -1566,7 +1419,6 @@ typelist typename typeslist typetoken -tz tzinfo uart ubuntu @@ -1603,8 +1455,6 @@ upfiles upl upto URI -url -urllib usb usec usecond @@ -1612,11 +1462,8 @@ usepackage usleep usr ustr -utc utdir UTF -utils -uuid valgrind validator vals @@ -1637,16 +1484,13 @@ virtualization virtualized vla vlist -vm VMIN vmstat vsnprintf VTIME vtype -vue vuejs vwong -vx vxworks VXWORKSLOGASSERT WAITALL @@ -1660,7 +1504,6 @@ Wextra Wformat wget whitebox -whitelist Whitelisted wiki wikipedia @@ -1672,8 +1515,6 @@ WORKDIR workflow worklist Woverloaded -wp -writelines WRONLY wrs Wshadow @@ -1681,7 +1522,6 @@ Wsign WSL Wundef www -wx wxgui Xabcdefx xapian @@ -1691,12 +1531,7 @@ xdf xdffe Xelect xfer -xhtml -xls -xlsx -xml xmlfile -xmlns xmls xoff xon @@ -1707,7 +1542,4 @@ xxxx XYZZY yacc yacgen -yml yyyymmdd -zsh -zu diff --git a/.github/workflows/autodocs.yml b/.github/workflows/autodocs.yml index 081ffbe32f..4db1b4b4c3 100644 --- a/.github/workflows/autodocs.yml +++ b/.github/workflows/autodocs.yml @@ -17,6 +17,6 @@ jobs: - name: Setup Dependencies run: | sudo apt-get update - sudo apt-get install doxygen + sudo apt-get install -y doxygen - name: Autodocs run: .github/actions/autodoc.bash diff --git a/Svc/Deframer/docs/img/top/file.json b/Svc/Deframer/docs/img/top/deframer-file.json similarity index 100% rename from Svc/Deframer/docs/img/top/file.json rename to Svc/Deframer/docs/img/top/deframer-file.json diff --git a/Svc/Deframer/docs/img/top/file.png b/Svc/Deframer/docs/img/top/deframer-file.png similarity index 100% rename from Svc/Deframer/docs/img/top/file.png rename to Svc/Deframer/docs/img/top/deframer-file.png diff --git a/Svc/Deframer/docs/img/top/file.txt b/Svc/Deframer/docs/img/top/deframer-file.txt similarity index 100% rename from Svc/Deframer/docs/img/top/file.txt rename to Svc/Deframer/docs/img/top/deframer-file.txt diff --git a/Svc/Deframer/docs/sdd.md b/Svc/Deframer/docs/sdd.md index 0807465438..a7612e5d68 100644 --- a/Svc/Deframer/docs/sdd.md +++ b/Svc/Deframer/docs/sdd.md @@ -376,7 +376,7 @@ assign these numbers. **Topology 3: Buffers containing packet data:**
- +
### 6.2. Sequence Diagrams diff --git a/Svc/Framer/docs/img/top/file.json b/Svc/Framer/docs/img/top/framer-file.json similarity index 100% rename from Svc/Framer/docs/img/top/file.json rename to Svc/Framer/docs/img/top/framer-file.json diff --git a/Svc/Framer/docs/img/top/file.png b/Svc/Framer/docs/img/top/framer-file.png similarity index 100% rename from Svc/Framer/docs/img/top/file.png rename to Svc/Framer/docs/img/top/framer-file.png diff --git a/Svc/Framer/docs/img/top/file.txt b/Svc/Framer/docs/img/top/framer-file.txt similarity index 100% rename from Svc/Framer/docs/img/top/file.txt rename to Svc/Framer/docs/img/top/framer-file.txt diff --git a/Svc/Framer/docs/sdd.md b/Svc/Framer/docs/sdd.md index 569fe1c408..88efb84332 100644 --- a/Svc/Framer/docs/sdd.md +++ b/Svc/Framer/docs/sdd.md @@ -199,7 +199,7 @@ The `eventLogger` instance sends event packets to the `framer` instance. **Topology 3: File packets:**
- +
The `fileDownlink` instance sends a sequence of file packets, diff --git a/ci/config.xml b/ci/config.xml index 310dcd03ca..42e50fee27 100644 --- a/ci/config.xml +++ b/ci/config.xml @@ -104,7 +104,7 @@ swcaegitadmin export PATH="/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin" . /opt/fprime-venv/bin/activate echo "Merging: origin/${ghprbTargetBranch} into ${ghprbActualCommit}}" -git merge origin/${ghprbTargetBranch} +GIT_EDITOR=true git merge origin/${ghprbTargetBranch} if (( $? != 0 )) then echo "[ERROR] Automatic merge failed." 1>&2 From f74e266a693c2f36b78764d8207f21e95f3f70bf Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Wed, 3 Aug 2022 09:43:57 -0700 Subject: [PATCH 044/169] Revise unit tests for Svc/Framer (#1606) * Refactor Framer unit tests * Revise Framer unit tests * Revise Framer unit tests * Revise Framer unit tests * Revise comments * Revise Framer unit tests Add comments and requirements to test output * Update unit tests Remove error code from nominal test --- Svc/Framer/test/ut/TestMain.cpp | 39 +++++++++++++-- Svc/Framer/test/ut/Tester.cpp | 63 ++++++++++++++++++------ Svc/Framer/test/ut/Tester.hpp | 85 +++++++++++++++++++++++---------- 3 files changed, 144 insertions(+), 43 deletions(-) diff --git a/Svc/Framer/test/ut/TestMain.cpp b/Svc/Framer/test/ut/TestMain.cpp index f86598850d..c94c289a77 100644 --- a/Svc/Framer/test/ut/TestMain.cpp +++ b/Svc/Framer/test/ut/TestMain.cpp @@ -2,26 +2,59 @@ // TestMain.cpp // ---------------------------------------------------------------------- +#include "Fw/Test/UnitTest.hpp" +#include "Os/Log.hpp" #include "Tester.hpp" +// Enable the console logging provided by Os::Log +Os::Log logger; + TEST(Nominal, Com) { + COMMENT("Send one Fw::Com buffer to the framer (nominal behavior)"); + REQUIREMENT("SVC-FRAMER-001"); + REQUIREMENT("SVC-FRAMER-003"); Svc::Tester tester; - tester.test_incoming(); + tester.test_com(); } TEST(Nominal, Buffer) { + COMMENT("Send one Fw::Buffer to the framer (nominal behavior)"); + REQUIREMENT("SVC-FRAMER-002"); + REQUIREMENT("SVC-FRAMER-003"); Svc::Tester tester; tester.test_buffer(); } TEST(Nominal, ManySends) { + COMMENT("Send several buffers"); + REQUIREMENT("SVC-FRAMER-001"); + REQUIREMENT("SVC-FRAMER-002"); + REQUIREMENT("SVC-FRAMER-003"); Svc::Tester tester; - tester.test_incoming(27); + tester.test_com(27); tester.test_buffer(27); - tester.test_incoming(31); + tester.test_com(31); tester.test_buffer(31); } +TEST(SendError, Buffer) { + COMMENT("Send one Fw::Buffer to the framer (send error)"); + REQUIREMENT("SVC-FRAMER-002"); + REQUIREMENT("SVC-FRAMER-003"); + Svc::Tester tester; + tester.setSendStatus(Drv::SendStatus::SEND_ERROR); + tester.test_buffer(); +} + +TEST(SendError, Com) { + COMMENT("Send one Fw::Com buffer to the framer (send error)"); + REQUIREMENT("SVC-FRAMER-001"); + REQUIREMENT("SVC-FRAMER-003"); + Svc::Tester tester; + tester.setSendStatus(Drv::SendStatus::SEND_ERROR); + tester.test_com(); +} + int main(int argc, char **argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); diff --git a/Svc/Framer/test/ut/Tester.cpp b/Svc/Framer/test/ut/Tester.cpp index 9b903dfe36..e5e78f1a28 100644 --- a/Svc/Framer/test/ut/Tester.cpp +++ b/Svc/Framer/test/ut/Tester.cpp @@ -1,10 +1,10 @@ // ====================================================================== // \title Framer.hpp -// \author mstarch +// \author mstarch, bocchino // \brief cpp file for Framer test harness implementation class // // \copyright -// Copyright 2009-2015, by the California Institute of Technology. +// Copyright 2009-2022, by the California Institute of Technology. // ALL RIGHTS RESERVED. United States Government Sponsorship // acknowledged. // @@ -19,7 +19,11 @@ namespace Svc { Tester::MockFramer::MockFramer(Tester& parent) : m_parent(parent) {} -void Tester::MockFramer::frame(const U8* const data, const U32 size, Fw::ComPacket::ComPacketType packet_type) { +void Tester::MockFramer::frame( + const U8* const data, + const U32 size, + Fw::ComPacket::ComPacketType packet_type +) { Fw::Buffer buffer(const_cast(data), size); m_parent.check_last_buffer(buffer); Fw::Buffer allocated = m_interface->allocate(size); @@ -30,13 +34,14 @@ void Tester::MockFramer::frame(const U8* const data, const U32 size, Fw::ComPack // Construction and destruction // ---------------------------------------------------------------------- -Tester ::Tester() - : +Tester ::Tester() : FramerGTestBase("Tester", MAX_HISTORY_SIZE), component("Framer"), m_mock(*this), m_framed(false), - m_returned(false) + m_sent(false), + m_returned(false), + m_sendStatus(Drv::SendStatus::SEND_OK) { this->initComponents(); @@ -50,13 +55,22 @@ Tester ::~Tester() {} // Tests // ---------------------------------------------------------------------- -void Tester ::test_incoming(U32 iterations) { +void Tester ::test_com(U32 iterations) { for (U32 i = 0; i < iterations; i++) { Fw::ComBuffer com; m_buffer.set(com.getBuffAddr(), com.getBuffLength()); m_framed = false; + m_sent = false; + m_returned = false; invoke_to_comIn(0, com, 0); ASSERT_TRUE(m_framed); + if (m_sendStatus == Drv::SendStatus::SEND_OK) { + ASSERT_TRUE(m_sent); + } + else { + ASSERT_FALSE(m_sent); + } + ASSERT_FALSE(m_returned); } } @@ -64,10 +78,17 @@ void Tester ::test_buffer(U32 iterations) { for (U32 i = 0; i < iterations; i++) { Fw::Buffer buffer(new U8[3412], 3412); m_framed = false; + m_sent = false; m_returned = false; m_buffer = buffer; invoke_to_bufferIn(0, buffer); ASSERT_TRUE(m_framed); + if (m_sendStatus == Drv::SendStatus::SEND_OK) { + ASSERT_TRUE(m_sent); + } + else { + ASSERT_FALSE(m_sent); + } ASSERT_TRUE(m_returned); } } @@ -76,33 +97,41 @@ void Tester ::check_last_buffer(Fw::Buffer buffer) { ASSERT_EQ(buffer, m_buffer); } -void Tester ::check_not_freed() { - ASSERT_FALSE(m_returned); -} - // ---------------------------------------------------------------------- // Handlers for typed from ports // ---------------------------------------------------------------------- -void Tester ::from_bufferDeallocate_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { +void Tester ::from_bufferDeallocate_handler( + const NATIVE_INT_TYPE portNum, + Fw::Buffer& fwBuffer +) { this->pushFromPortEntry_bufferDeallocate(fwBuffer); m_returned = true; delete[] fwBuffer.getData(); } -Fw::Buffer Tester ::from_framedAllocate_handler(const NATIVE_INT_TYPE portNum, U32 size) { +Fw::Buffer Tester ::from_framedAllocate_handler( + const NATIVE_INT_TYPE portNum, + U32 size +) { this->pushFromPortEntry_framedAllocate(size); Fw::Buffer buffer(new U8[size], size); m_buffer = buffer; return buffer; } -Drv::SendStatus Tester ::from_framedOut_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& sendBuffer) { +Drv::SendStatus Tester ::from_framedOut_handler( + const NATIVE_INT_TYPE portNum, + Fw::Buffer& sendBuffer +) { this->pushFromPortEntry_framedOut(sendBuffer); this->check_last_buffer(sendBuffer); delete[] sendBuffer.getData(); m_framed = true; - return Drv::SendStatus::SEND_OK; + if (m_sendStatus == Drv::SendStatus::SEND_OK) { + m_sent = true; + } + return m_sendStatus; } // ---------------------------------------------------------------------- @@ -132,4 +161,8 @@ void Tester ::initComponents() { this->component.init(INSTANCE); } +void Tester ::setSendStatus(Drv::SendStatus sendStatus) { + m_sendStatus = sendStatus; +} + } // end namespace Svc diff --git a/Svc/Framer/test/ut/Tester.hpp b/Svc/Framer/test/ut/Tester.hpp index 16a36ce7dd..55aac73d54 100644 --- a/Svc/Framer/test/ut/Tester.hpp +++ b/Svc/Framer/test/ut/Tester.hpp @@ -1,10 +1,10 @@ // ====================================================================== // \title Framer/test/ut/Tester.hpp -// \author mstarch +// \author mstarch, bocchino // \brief hpp file for Framer test harness implementation class // // \copyright -// Copyright 2009-2015, by the California Institute of Technology. +// Copyright 2009-2022, by the California Institute of Technology. // ALL RIGHTS RESERVED. United States Government Sponsorship // acknowledged. // @@ -20,87 +20,122 @@ namespace Svc { class Tester : public FramerGTestBase { + public: + // ---------------------------------------------------------------------- - // Construction and destruction + // Types // ---------------------------------------------------------------------- + + //! Mock framing protocol class MockFramer : public FramingProtocol { public: MockFramer(Tester& parent); - void frame(const U8* const data, const U32 size, Fw::ComPacket::ComPacketType packet_type); + void frame( + const U8* const data, + const U32 size, + Fw::ComPacket::ComPacketType packet_type + ); Tester& m_parent; }; + // ---------------------------------------------------------------------- + // Construction and destruction + // ---------------------------------------------------------------------- + public: + //! Construct object Tester - //! Tester(); //! Destroy object Tester - //! ~Tester(); public: + // ---------------------------------------------------------------------- // Tests // ---------------------------------------------------------------------- - //! Test incoming data to the framer - //! - void test_incoming(U32 iterations = 1); + //! Test incoming Fw::Com data to the framer + void test_com(U32 iterations = 1); - //! Test incoming data to the framer - //! + //! Test incoming Fw::Buffer data to the framer void test_buffer(U32 iterations = 1); + //! Check that buffer is equal to the last buffer allocated void check_last_buffer(Fw::Buffer buffer); - void check_not_freed(); private: + // ---------------------------------------------------------------------- // Handlers for typed from ports // ---------------------------------------------------------------------- //! Handler for from_bufferDeallocate - //! - void from_bufferDeallocate_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer& fwBuffer); + void from_bufferDeallocate_handler( + const NATIVE_INT_TYPE portNum, //!< The port number + Fw::Buffer& fwBuffer //!< The buffer + ); //! Handler for from_framedAllocate - //! - Fw::Buffer from_framedAllocate_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U32 size); + Fw::Buffer from_framedAllocate_handler( + const NATIVE_INT_TYPE portNum, //!< The port number + U32 size //!< The size + ); //! Handler for from_framedOut - //! - Drv::SendStatus from_framedOut_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer& sendBuffer); + Drv::SendStatus from_framedOut_handler( + const NATIVE_INT_TYPE portNum, //!< The port number + Fw::Buffer& sendBuffer //!< The buffer containing framed data + ); + + public: + + // ---------------------------------------------------------------------- + // Public instance methods + // ---------------------------------------------------------------------- + + //! Set the send status + void setSendStatus(Drv::SendStatus sendStatus); private: + // ---------------------------------------------------------------------- - // Helper methods + // Private instance methods // ---------------------------------------------------------------------- //! Connect ports - //! void connectPorts(); //! Initialize components - //! void initComponents(); private: + // ---------------------------------------------------------------------- // Variables // ---------------------------------------------------------------------- //! The component under test - //! Framer component; + //! Buffer for sending unframed data Fw::Buffer m_buffer; + + //! Mock framing protocol MockFramer m_mock; + + //! Whether framing succeeded bool m_framed; + + //! Whether sending succeeded + bool m_sent; + + //! Whether the frame buffer was deallocated bool m_returned; + + //! Send status for error injection + Drv::SendStatus m_sendStatus; }; } // end namespace Svc From ff2aee29f5f1f4c678b300f2823262e6eed6880e Mon Sep 17 00:00:00 2001 From: M Starch Date: Wed, 3 Aug 2022 11:36:39 -0700 Subject: [PATCH 045/169] lestarch: reworked linux serial driver into linux uart driver following byte stream driver model (#1597) * lestarch: reworked linux serial driver into linux uart driver following byte stream driver model * lestarch: reworking RPI demo for new serial driver * lestarch: removing unnecessary UartFramer * lestarch: cleaning-up CI failures and spelling * lestarch: UART driver code quality enhancements * lestarch: removing one final TODO * lestarch: removing DR_ from event names * lestarch: sp * lestarch: removing unused stubs/test and adding port comments per-review --- .github/actions/spelling/expect.txt | 4 +- Drv/CMakeLists.txt | 4 +- Drv/LinuxSerialDriver/CMakeLists.txt | 31 -- Drv/LinuxSerialDriver/LinuxSerialDriver.hpp | 17 - .../LinuxSerialDriverComponentImpl.cpp | 415 -------------- .../LinuxSerialDriverComponentImpl.hpp | 124 ----- .../LinuxSerialDriverComponentImplCommon.cpp | 66 --- .../LinuxSerialDriverComponentImplStub.cpp | 49 -- .../LinuxSerialDriverComponentReport.txt | 6 - Drv/LinuxSerialDriver/Telemetry.fppi | 5 - Drv/LinuxSerialDriver/test/ut/Tester.cpp | 223 -------- Drv/LinuxSerialDriver/test/ut/Tester.hpp | 110 ---- Drv/LinuxSerialDriver/test/ut/main.cpp | 77 --- Drv/LinuxUartDriver/CMakeLists.txt | 18 + .../Events.fppi | 14 +- Drv/LinuxUartDriver/LinuxUartDriver.cpp | 372 +++++++++++++ .../LinuxUartDriver.fpp} | 19 +- Drv/LinuxUartDriver/LinuxUartDriver.hpp | 88 +++ Drv/LinuxUartDriver/Telemetry.fppi | 5 + Drv/SerialDriverPorts/CMakeLists.txt | 12 - Drv/SerialDriverPorts/SerialDriverPorts.fpp | 24 - Drv/UartFramer/CMakeLists.txt | 26 - Drv/UartFramer/UartFramer.cpp | 106 ---- Drv/UartFramer/UartFramer.fpp | 62 --- Drv/UartFramer/UartFramer.hpp | 86 --- Drv/UartFramer/docs/UartFramer.vsdx | Bin 57961 -> 0 bytes Drv/UartFramer/docs/img/Downlink.svg | 142 ----- Drv/UartFramer/docs/img/Topo.svg | 520 ------------------ Drv/UartFramer/docs/img/UartFramer.svg | 204 ------- .../docs/img/UartFramerAllocate.svg | 125 ----- Drv/UartFramer/docs/img/Uplink.svg | 130 ----- Drv/UartFramer/docs/sdd.md | 174 ------ Drv/UartFramer/test/ut/TestMain.cpp | 35 -- Drv/UartFramer/test/ut/Tester.cpp | 320 ----------- Drv/UartFramer/test/ut/Tester.hpp | 150 ----- RPI/RpiDemo/RpiDemo.fpp | 4 +- RPI/RpiDemo/RpiDemoComponentImpl.cpp | 49 +- RPI/RpiDemo/RpiDemoComponentImpl.hpp | 2 +- RPI/Top/instances.fpp | 43 +- RPI/Top/topology.fpp | 8 +- config/LinuxSerialDriverComponentImplCfg.hpp | 15 - config/LinuxUartDriverCfg.hpp | 16 + 42 files changed, 590 insertions(+), 3310 deletions(-) delete mode 100644 Drv/LinuxSerialDriver/CMakeLists.txt delete mode 100644 Drv/LinuxSerialDriver/LinuxSerialDriver.hpp delete mode 100644 Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.cpp delete mode 100644 Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp delete mode 100644 Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplCommon.cpp delete mode 100644 Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplStub.cpp delete mode 100644 Drv/LinuxSerialDriver/LinuxSerialDriverComponentReport.txt delete mode 100644 Drv/LinuxSerialDriver/Telemetry.fppi delete mode 100644 Drv/LinuxSerialDriver/test/ut/Tester.cpp delete mode 100644 Drv/LinuxSerialDriver/test/ut/Tester.hpp delete mode 100644 Drv/LinuxSerialDriver/test/ut/main.cpp create mode 100644 Drv/LinuxUartDriver/CMakeLists.txt rename Drv/{LinuxSerialDriver => LinuxUartDriver}/Events.fppi (92%) create mode 100644 Drv/LinuxUartDriver/LinuxUartDriver.cpp rename Drv/{LinuxSerialDriver/LinuxSerialDriver.fpp => LinuxUartDriver/LinuxUartDriver.fpp} (61%) create mode 100644 Drv/LinuxUartDriver/LinuxUartDriver.hpp create mode 100644 Drv/LinuxUartDriver/Telemetry.fppi delete mode 100644 Drv/SerialDriverPorts/CMakeLists.txt delete mode 100644 Drv/SerialDriverPorts/SerialDriverPorts.fpp delete mode 100644 Drv/UartFramer/CMakeLists.txt delete mode 100644 Drv/UartFramer/UartFramer.cpp delete mode 100644 Drv/UartFramer/UartFramer.fpp delete mode 100644 Drv/UartFramer/UartFramer.hpp delete mode 100644 Drv/UartFramer/docs/UartFramer.vsdx delete mode 100644 Drv/UartFramer/docs/img/Downlink.svg delete mode 100644 Drv/UartFramer/docs/img/Topo.svg delete mode 100644 Drv/UartFramer/docs/img/UartFramer.svg delete mode 100644 Drv/UartFramer/docs/img/UartFramerAllocate.svg delete mode 100644 Drv/UartFramer/docs/img/Uplink.svg delete mode 100644 Drv/UartFramer/docs/sdd.md delete mode 100644 Drv/UartFramer/test/ut/TestMain.cpp delete mode 100644 Drv/UartFramer/test/ut/Tester.cpp delete mode 100644 Drv/UartFramer/test/ut/Tester.hpp delete mode 100644 config/LinuxSerialDriverComponentImplCfg.hpp create mode 100644 config/LinuxUartDriverCfg.hpp diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index abd3544472..e1bc9d9d10 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -548,7 +548,7 @@ gjslint glibc gmtime Gnc -gnd +Gnd GNUC gnueabihf google @@ -730,7 +730,7 @@ lineroo lineterm linting linux -LINUXSERIALDRIVER +LINUXUARTDRIVER LINUXTIMEIMPL Listst LJR diff --git a/Drv/CMakeLists.txt b/Drv/CMakeLists.txt index 70d7471532..a9e30b762e 100644 --- a/Drv/CMakeLists.txt +++ b/Drv/CMakeLists.txt @@ -3,7 +3,6 @@ # Ports add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/DataTypes/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/GpioDriverPorts/") -add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/SerialDriverPorts/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/SpiDriverPorts/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/I2cDriverPorts/") @@ -11,10 +10,9 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/I2cDriverPorts/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BlockDriver/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ByteStreamDriverModel/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/LinuxGpioDriver/") -add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/LinuxSerialDriver/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/LinuxSpiDriver/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriver/") -add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/UartFramer/") # IP Socket is only supported for Linux, Darwin, VxWorks if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux" OR ${CMAKE_SYSTEM_NAME} STREQUAL "Darwin" OR ${CMAKE_SYSTEM_NAME} STREQUAL "VxWorks") diff --git a/Drv/LinuxSerialDriver/CMakeLists.txt b/Drv/LinuxSerialDriver/CMakeLists.txt deleted file mode 100644 index db60b6b2dd..0000000000 --- a/Drv/LinuxSerialDriver/CMakeLists.txt +++ /dev/null @@ -1,31 +0,0 @@ -#### -# F prime CMakeLists.txt: -# -# SOURCE_FILES: combined list of source and autocoding diles -# MOD_DEPS: (optional) module dependencies -# -#### -set(MOD_DEPS Os) - -if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux" OR ${CMAKE_SYSTEM_NAME} STREQUAL "Darwin") - set(SOURCE_FILES - "${CMAKE_CURRENT_LIST_DIR}/LinuxSerialDriver.fpp" - "${CMAKE_CURRENT_LIST_DIR}/LinuxSerialDriverComponentImplCommon.cpp" - "${CMAKE_CURRENT_LIST_DIR}/LinuxSerialDriverComponentImpl.cpp" - ) - register_fprime_module() -else() - message(STATUS "Cannot use ${CMAKE_CURRENT_LIST_DIR} with platform ${CMAKE_SYSTEM_NAME}. Skipping.") -endif() - -### UTs ### -# Note: this UT expects user input -#set(UT_MOD_DEPS -# Os -#) -#set(UT_SOURCE_FILES -# "${CMAKE_CURRENT_LIST_DIR}/LinuxSerialDriverComponentAi.xml" -# "${CMAKE_CURRENT_LIST_DIR}/test/ut/main.cpp" -# "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" -#) -#register_fprime_ut() diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriver.hpp b/Drv/LinuxSerialDriver/LinuxSerialDriver.hpp deleted file mode 100644 index 63bda9ab5c..0000000000 --- a/Drv/LinuxSerialDriver/LinuxSerialDriver.hpp +++ /dev/null @@ -1,17 +0,0 @@ -// ====================================================================== -// LinuxSerialDriver.hpp -// Standardization header for LinuxSerialDriver -// ====================================================================== - -#ifndef Drv_LinuxSerialDriver_HPP -#define Drv_LinuxSerialDriver_HPP - -#include "Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp" - -namespace Drv { - - using LinuxSerialDriver = LinuxSerialDriverComponentImpl; - -} - -#endif diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.cpp b/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.cpp deleted file mode 100644 index dee01d2731..0000000000 --- a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.cpp +++ /dev/null @@ -1,415 +0,0 @@ -// ====================================================================== -// \title LinuxSerialDriverImpl.cpp -// \author tcanham -// \brief cpp file for LinuxSerialDriver component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - - -#include -#include "Fw/Types/BasicTypes.hpp" -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -//#define DEBUG_PRINT(x,...) printf(x,##__VA_ARGS__); fflush(stdout) -#define DEBUG_PRINT(x,...) - -namespace Drv { - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - bool LinuxSerialDriverComponentImpl::open(const char* const device, UartBaudRate baud, UartFlowControl fc, UartParity parity, bool block) { - // TODO remove printf - - NATIVE_INT_TYPE fd; - NATIVE_INT_TYPE stat; - - this->m_device = device; - - DEBUG_PRINT("Opening UART device %s\n", device); - - - // TODO can't use O_NDELAY and block (it is same as O_NONBLOCK), so removing NDELAY for now - /* - The O_NOCTTY flag tells UNIX that this program doesn't want to be the "controlling terminal" for that port. If you don't specify this then any input (such as keyboard abort signals and so forth) will affect your process. Programs like getty(1M/8) use this feature when starting the login process, but normally a user program does not want this behavior. - - The O_NDELAY flag tells UNIX that this program doesn't care what state the DCD signal line is in - whether the other end of the port is up and running. If you do not specify this flag, your process will be put to sleep until the DCD signal line is the space voltage. - */ - fd = ::open(device, O_RDWR | O_NOCTTY); // | O_NDELAY); - //fd = open(device, O_RDWR | O_NONBLOCK | O_SYNC); - - if (fd == -1) { - DEBUG_PRINT("open UART device %s failed.\n", device); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,this->m_fd,_err); - return false; - } else { - DEBUG_PRINT("Successfully opened UART device %s fd %d\n", device, fd); - } - - this->m_fd = fd; - - // Configure blocking reads - struct termios cfg; - - stat = tcgetattr(fd,&cfg); - if (-1 == stat) { - DEBUG_PRINT("tcgetattr failed: (%d): %s\n",stat,strerror(errno)); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } else { - DEBUG_PRINT("tcgetattr passed.\n"); - } - - /* - If MIN > 0 and TIME = 0, MIN sets the number of characters to receive before the read is satisfied. As TIME is zero, the timer is not used. - - If MIN = 0 and TIME > 0, TIME serves as a timeout value. The read will be satisfied if a single character is read, or TIME is exceeded (t = TIME *0.1 s). If TIME is exceeded, no character will be returned. - - If MIN > 0 and TIME > 0, TIME serves as an inter-character timer. The read will be satisfied if MIN characters are received, or the time between two characters exceeds TIME. The timer is restarted every time a character is received and only becomes active after the first character has been received. - - If MIN = 0 and TIME = 0, read will be satisfied immediately. The number of characters currently available, or the number of characters requested will be returned. According to Antonino (see contributions), you could issue a fcntl(fd, F_SETFL, FNDELAY); before reading to get the same result. - */ - // wait for at least 1 byte for 1 second - // TODO VMIN should be 0 when using VTIME, and then it would give the timeout behavior Tim wants - cfg.c_cc[VMIN] = 0; // TODO back to 0 - cfg.c_cc[VTIME] = 10; // 1 sec, TODO back to 10 - - stat = tcsetattr(fd,TCSANOW,&cfg); - if (-1 == stat) { - DEBUG_PRINT("tcsetattr failed: (%d): %s\n",stat,strerror(errno)); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } else { - DEBUG_PRINT("tcsetattr passed.\n"); - } - - // Set flow control - if (fc == HW_FLOW) { - - struct termios t; - - int stat = tcgetattr(fd, &t); - if (-1 == stat) { - DEBUG_PRINT("tcgetattr UART fd %d failed\n", fd); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } - - // modify flow control flags - t.c_cflag |= CRTSCTS; - - stat = tcsetattr(fd, TCSANOW, &t); - if (-1 == stat) { - DEBUG_PRINT("tcsetattr UART fd %d failed\n", fd); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } - } - - NATIVE_INT_TYPE relayRate = B0; - switch (baud) { - // TODO add more as needed - case BAUD_9600: - relayRate = B9600; - break; - case BAUD_19200: - relayRate = B19200; - break; - case BAUD_38400: - relayRate = B38400; - break; - case BAUD_57600: - relayRate = B57600; - break; - case BAUD_115K: - relayRate = B115200; - break; - case BAUD_230K: - relayRate = B230400; - break; -#if defined TGT_OS_TYPE_LINUX - case BAUD_460K: - relayRate = B460800; - break; - case BAUD_921K: - relayRate = B921600; - break; -#endif - default: - FW_ASSERT(0,baud); - break; - } - - struct termios newtio; - - stat = tcgetattr(fd, &newtio); - if (-1 == stat) { - DEBUG_PRINT("tcgetattr UART fd %d failed\n", fd); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } - - // CS8 = 8 data bits, CLOCAL = Local line, CREAD = Enable Receiver - // TODO PARENB for parity bit - /* - Even parity (7E1): - options.c_cflag |= PARENB - options.c_cflag &= ~PARODD - options.c_cflag &= ~CSTOPB - options.c_cflag &= ~CSIZE; - options.c_cflag |= CS7; - Odd parity (7O1): - options.c_cflag |= PARENB - options.c_cflag |= PARODD - options.c_cflag &= ~CSTOPB - options.c_cflag &= ~CSIZE; - options.c_cflag |= CS7; - */ - newtio.c_cflag = CS8 | CLOCAL | CREAD; - - switch (parity) { - case PARITY_ODD: - newtio.c_cflag |= (PARENB | PARODD) ; - break; - case PARITY_EVEN: - newtio.c_cflag |= PARENB ; - break; - case PARITY_NONE: - newtio.c_cflag &= ~PARENB ; - break; - default: - FW_ASSERT(0,parity); - break; - } - - // Set baud rate: - stat = cfsetispeed(&newtio, relayRate); - if (stat) { - DEBUG_PRINT("cfsetispeed failed\n"); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } - stat = cfsetospeed(&newtio, relayRate); - if (stat) { - DEBUG_PRINT("cfsetospeed failed\n"); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } - - // Raw output: - newtio.c_oflag = 0; - - // set input mode (non-canonical, no echo,...) - newtio.c_lflag = 0; - - // TODO if parity, then do input parity too - //options.c_iflag |=INPCK; - newtio.c_iflag = INPCK; - - // Flush old data: - (void) tcflush(fd, TCIFLUSH); - - // Set attributes: - stat = tcsetattr(fd,TCSANOW,&newtio); - if (-1 == stat) { - DEBUG_PRINT("tcsetattr UART fd %d failed\n", fd); - close(fd); - Fw::LogStringArg _arg = device; - Fw::LogStringArg _err = strerror(errno); - this->log_WARNING_HI_DR_OpenError(_arg,fd,_err); - return false; - } - - // All done! - Fw::LogStringArg _arg = device; - this->log_ACTIVITY_HI_DR_PortOpened(_arg); - return true; - } - - LinuxSerialDriverComponentImpl :: - ~LinuxSerialDriverComponentImpl() - { - if (this->m_fd != -1) { - DEBUG_PRINT("Closing UART device %d\n", this->m_fd); - - (void) close(this->m_fd); - } - } - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - void LinuxSerialDriverComponentImpl :: - serialSend_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &serBuffer - ) - { - if (this->m_fd == -1) { - return; - } - - unsigned char* data = serBuffer.getData(); - NATIVE_INT_TYPE xferSize = serBuffer.getSize(); - - NATIVE_INT_TYPE stat = ::write(this->m_fd,data,xferSize); - - // TODO no need to delay for writes b/c the write blocks - // not sure if it will block until everything is transmitted, but seems to - - if (-1 == stat || stat != xferSize) { - Fw::LogStringArg _arg = this->m_device; - this->log_WARNING_HI_DR_WriteError(_arg,stat); - } - } - - void LinuxSerialDriverComponentImpl :: - serialReadTaskEntry(void * ptr) { - - Drv::SerialReadStatus serReadStat; // added by m.chase 03.06.2017 - - LinuxSerialDriverComponentImpl* comp = static_cast(ptr); - - Fw::Buffer buff; - - while (true) { - // wait for data - int sizeRead = 0; - - // find open buffer - - comp->m_readBuffMutex.lock(); - // search for open entry - NATIVE_INT_TYPE entryFound = false; - for (NATIVE_INT_TYPE entry = 0; entry < DR_MAX_NUM_BUFFERS; entry++) { - if (comp->m_buffSet[entry].available) { - comp->m_buffSet[entry].available = false; - buff = comp->m_buffSet[entry].readBuffer; - entryFound = true; - break; - } - } - comp->m_readBuffMutex.unLock(); - - if (not entryFound) { - Fw::LogStringArg _arg = comp->m_device; - comp->log_WARNING_HI_DR_NoBuffers(_arg); - serReadStat = SerialReadStatus::SER_NO_BUFFERS; // added by m.chase 03.06.2017 - comp->serialRecv_out(0,buff,serReadStat); - // to avoid spinning, wait 50 ms - Os::Task::delay(50); - continue; - } - -// timespec stime; -// (void)clock_gettime(CLOCK_REALTIME,&stime); -// DEBUG_PRINT("<<< Calling dsp_relay_uart_relay_read() at %d %d\n", stime.tv_sec, stime.tv_nsec); - - bool waiting = true; - int stat = 0; - - while (waiting) { - if (comp->m_quitReadThread) { - return; - } - - stat = ::read(comp->m_fd, - buff.getData(), - buff.getSize()); - - // Good read: - if (stat > 0) { - sizeRead = stat; - // TODO remove - static int totalSizeRead = 0; - totalSizeRead += sizeRead; - //printf("<<< totalSizeRead: %d, readSize: %d\n", totalSizeRead, sizeRead); - //printf("<<< read size: %d\n", stat); - } - - // check for timeout - if (0 == stat) { - if (comp->m_quitReadThread) { - return; - } - } else { // quit if other error or data - waiting = false; - } - } - - if (comp->m_quitReadThread) { - return; - } - - // check stat, maybe output event - if (stat == -1) { - // TODO(mereweth) - check errno - Fw::LogStringArg _arg = comp->m_device; - comp->log_WARNING_HI_DR_ReadError(_arg,stat); - serReadStat = SerialReadStatus::SER_OTHER_ERR; // added by m.chase 03.06.2017 - //comp->serialRecv_out(0,buff,Drv::SER_OTHER_ERR); - } else { -// (void)clock_gettime(CLOCK_REALTIME,&stime); -// DEBUG_PRINT("serialRecv_out(0,buff,Drv::SER_OK); - } - comp->serialRecv_out(0,buff,serReadStat); // added by m.chase 03.06.2017 - } - } - - void LinuxSerialDriverComponentImpl :: - startReadThread(NATIVE_UINT_TYPE priority, NATIVE_UINT_TYPE stackSize, NATIVE_UINT_TYPE cpuAffinity) { - - Os::TaskString task("SerReader"); - Os::Task::TaskStatus stat = this->m_readTask.start(task, serialReadTaskEntry, this, priority, stackSize, cpuAffinity); - FW_ASSERT(stat == Os::Task::TASK_OK, stat); - } - - void LinuxSerialDriverComponentImpl :: - quitReadThread() { - this->m_quitReadThread = true; - } - -} // end namespace Drv diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp b/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp deleted file mode 100644 index dad0418ab8..0000000000 --- a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp +++ /dev/null @@ -1,124 +0,0 @@ -// ====================================================================== -// \title LinuxSerialDriverImpl.hpp -// \author tcanham -// \brief hpp file for LinuxSerialDriver component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef LinuxSerialDriver_HPP -#define LinuxSerialDriver_HPP - -#include -#include -#include -#include - -namespace Drv { - - class LinuxSerialDriverComponentImpl : - public LinuxSerialDriverComponentBase - { - - public: - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object LinuxSerialDriver - //! - LinuxSerialDriverComponentImpl( - const char *const compName /*!< The component name*/ - ); - - //! Initialize object LinuxSerialDriver - //! - void init( - const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ - ); - - //! Configure UART parameters - typedef enum BAUD_RATE { - BAUD_9600, - BAUD_19200, - BAUD_38400, - BAUD_57600, - BAUD_115K, - BAUD_230K, - BAUD_460K, - BAUD_921K - } UartBaudRate ; - - typedef enum FLOW_CONTROL { - NO_FLOW, - HW_FLOW - } UartFlowControl; - - typedef enum PARITY { - PARITY_NONE, - PARITY_ODD, - PARITY_EVEN - } UartParity; - - // Open device with specified baud and flow control. - bool open(const char* const device, UartBaudRate baud, UartFlowControl fc, UartParity parity, bool block); - - //! start the serial poll thread. - //! buffSize is the max receive buffer size - //! - void startReadThread(NATIVE_UINT_TYPE priority = Os::Task::TASK_DEFAULT, NATIVE_UINT_TYPE stackSize = Os::Task::TASK_DEFAULT, NATIVE_UINT_TYPE cpuAffinity = Os::Task::TASK_DEFAULT); - - //! Quit thread - void quitReadThread(); - - //! Destroy object LinuxSerialDriver - //! - ~LinuxSerialDriverComponentImpl(); - - PRIVATE: - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for serialSend - //! - void serialSend_handler( - NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &serBuffer - ); - - //! Handler implementation for readBufferSend - //! - void readBufferSend_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer& fwBuffer - ); - - NATIVE_INT_TYPE m_fd; //!< file descriptor returned for I/O device - const char* m_device; //!< original device path - - //! This method will be called by the new thread to wait for input on the serial port. - static void serialReadTaskEntry(void * ptr); - - Os::Task m_readTask; //!< task instance for thread to read serial port - - struct BufferSet { - Fw::Buffer readBuffer; //!< buffers for port reads - bool available; //!< is buffer available? - } m_buffSet[DR_MAX_NUM_BUFFERS]; - - Os::Mutex m_readBuffMutex; - - bool m_quitReadThread; //!< flag to quit thread - - }; - -} // end namespace Drv - -#endif diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplCommon.cpp b/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplCommon.cpp deleted file mode 100644 index dbd2e0b787..0000000000 --- a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplCommon.cpp +++ /dev/null @@ -1,66 +0,0 @@ -/* - * LinuxSerialDriverComponentImplCommon.cpp - * - * Created on: Nov 29, 2016 - * Author: tcanham - */ - -#include - -namespace Drv { - - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - LinuxSerialDriverComponentImpl :: - LinuxSerialDriverComponentImpl( - const char *const compName - ) : LinuxSerialDriverComponentBase(compName), - m_fd(-1), - m_device("NOT_EXIST"), - m_quitReadThread(false) - { - // initialize buffer set - for (NATIVE_INT_TYPE entry = 0; entry < DR_MAX_NUM_BUFFERS; entry++) { - this->m_buffSet[entry].available = false; - } - - } - - void LinuxSerialDriverComponentImpl :: - init( - const NATIVE_INT_TYPE instance - ) - { - LinuxSerialDriverComponentBase::init(instance); - } - - void LinuxSerialDriverComponentImpl :: - readBufferSend_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer& Buffer - ) - { - this->m_readBuffMutex.lock(); - bool found = false; - - // search for open entry - for (NATIVE_UINT_TYPE entry = 0; entry < DR_MAX_NUM_BUFFERS; entry++) { - // Look for slots to fill. "Available" is from - // the perspective of the driver thread looking for - // buffers to fill, so add the buffer and make it available. - if (not this->m_buffSet[entry].available) { - this->m_buffSet[entry].readBuffer = Buffer; - this->m_buffSet[entry].available = true; - found = true; - break; - } - } - this->m_readBuffMutex.unLock(); - FW_ASSERT(found,Buffer.getContext()); - - } - -} diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplStub.cpp b/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplStub.cpp deleted file mode 100644 index bd81a71a02..0000000000 --- a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentImplStub.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// ====================================================================== -// \title LinuxSerialDriverImpl.cpp -// \author tcanham -// \brief cpp file for LinuxSerialDriver component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - - -#include - -namespace Drv { - - LinuxSerialDriverComponentImpl :: - ~LinuxSerialDriverComponentImpl() - { - - } - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - void LinuxSerialDriverComponentImpl :: - serialSend_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &serBuffer - ) - { - // TODO - } - - void LinuxSerialDriverComponentImpl :: - startReadThread(NATIVE_INT_TYPE priority, NATIVE_INT_TYPE stackSize, NATIVE_INT_TYPE cpuAffinity) { - } - - bool LinuxSerialDriverComponentImpl::open(const char* const device, UartBaudRate baud, UartFlowControl fc, UartParity parity, bool block) { - //TODO - return false; - } - - void LinuxSerialDriverComponentImpl :: - quitReadThread() { - } -} // end namespace Drv diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentReport.txt b/Drv/LinuxSerialDriver/LinuxSerialDriverComponentReport.txt deleted file mode 100644 index 17f9ba4f81..0000000000 --- a/Drv/LinuxSerialDriver/LinuxSerialDriverComponentReport.txt +++ /dev/null @@ -1,6 +0,0 @@ -Input Ports: 2 -Output Ports: 5 -Channels: 2 - ChanIds: 0,1 -Events: 7 - EventIds: 0,1,2,3,4,5,6 diff --git a/Drv/LinuxSerialDriver/Telemetry.fppi b/Drv/LinuxSerialDriver/Telemetry.fppi deleted file mode 100644 index 1c8289b568..0000000000 --- a/Drv/LinuxSerialDriver/Telemetry.fppi +++ /dev/null @@ -1,5 +0,0 @@ -@ Bytes Sent -telemetry DR_BytesSent: U32 id 0 - -@ Bytes Received -telemetry DR_BytesRecv: U32 id 1 diff --git a/Drv/LinuxSerialDriver/test/ut/Tester.cpp b/Drv/LinuxSerialDriver/test/ut/Tester.cpp deleted file mode 100644 index 3dfd847313..0000000000 --- a/Drv/LinuxSerialDriver/test/ut/Tester.cpp +++ /dev/null @@ -1,223 +0,0 @@ -// ====================================================================== -// \title LinuxSerialDriver.hpp -// \author tcanham -// \brief cpp file for LinuxSerialDriver test harness implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#include "Tester.hpp" -#include -#include - - -#define INSTANCE 0 -#define MAX_HISTORY_SIZE 10 - -namespace Drv { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - Tester :: - Tester(const char* const device, NATIVE_INT_TYPE numReadBuffers, NATIVE_INT_TYPE bufferSize, - LinuxSerialDriverComponentImpl::UartFlowControl flow, - LinuxSerialDriverComponentImpl::UartParity parity) : - LinuxSerialDriverTesterBase("Tester", MAX_HISTORY_SIZE), - component("LinuxSerialDriver") - ,m_numBuffers(numReadBuffers),m_bufferSize(bufferSize) - { - this->initComponents(); - this->connectPorts(); - - // allocate and configure buffers - for (NATIVE_INT_TYPE buffer = 0; buffer < m_numBuffers; buffer++) { - // initialize buffers - this->m_readData[buffer] = new BYTE[bufferSize]; - FW_ASSERT(this->m_readData[buffer]); - this->m_readBuffer[buffer].setdata(reinterpret_cast(this->m_readData[buffer])); - this->m_readBuffer[buffer].setsize(bufferSize); - this->m_readBuffer[buffer].setbufferID(buffer); - - // push buffers to serial port - this->invoke_to_readBufferSend(0,this->m_readBuffer[buffer]); - } - - // configure port - this->component.open(device,LinuxSerialDriverComponentImpl::BAUD_921K,flow,parity,true); - - // spawn driver thread - this->component.startReadThread(); - - } - - Tester :: - ~Tester() - { - // kill thread - this->component.quitReadThread(); - // free buffers - for (NATIVE_INT_TYPE buffer = 0; buffer < m_numBuffers; buffer++) { - // initialize buffers - delete[] this->m_readData[buffer]; - } - - } - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - void Tester :: - sendSerial(BYTE* data, NATIVE_INT_TYPE size) - { - Fw::Buffer buff; - buff.setdata(reinterpret_cast(data)); - buff.setsize(size); - - this->invoke_to_serialSend(0,buff); - - } - - // ---------------------------------------------------------------------- - // Handlers for typed from ports - // ---------------------------------------------------------------------- - - void Tester :: - from_serialRecv_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &serBuffer, - Drv::SerialReadStatus& status - ) - { -// this->pushFromPortEntry_serialRecv(serBuffer, status); - - static int numPkts = 0.0; - static int numErrs = 0; - //static BYTE expVal = 253; // ramp down, skipping xon and xoff - //static BYTE expVal = 255; // ramp down - static BYTE expVal = 0; // ramp up - - numPkts++; - - BYTE* ptr = (BYTE*) serBuffer.getdata(); - U32 error = 0; - printf("<< size: %d\n",serBuffer.getsize()); - for (NATIVE_UINT_TYPE byte = 0; byte < serBuffer.getsize(); byte++) { - //printf("%d: 0x%02X ",byte,ptr[byte]); - - // For this verification to work, must be sent ramping pattern of size of at least 256 -#if 1 - // ramp down, skipped xon and xoff (17 and 19) when sending - /*if (expVal == 19) expVal -= 1; - if (expVal == 17) expVal -= 1;*/ - - if (ptr[byte] != expVal && error == 0) { - - //error = 1; - printf("ERROR: exp: %d idx: %d got: %d size: %d\n",expVal,byte,ptr[byte],serBuffer.getsize()); - } - //--expVal; // ramp down - ++expVal; // ramp up -#endif - } - - //expVal = ptr[serBuffer.getsize()-1]-1; // ramp down - expVal = ptr[serBuffer.getsize()-1]+1; // ramp up - - if (error) { - numErrs++; - for (NATIVE_UINT_TYPE byte = 0; byte < serBuffer.getsize(); byte++) { - //printf("%d: 0x%02X ",byte,ptr[byte]); - } - - } - printf("\nTOTAL NUMBER OF ERRORS: %d\n",numErrs); - printf("TOTAL ERROR PERCENTAGE: %f\n", ((double)numErrs/(double)numPkts)*100.0); - printf("TOTAL NUMBER OF PACKETS: %d\n",numPkts); - printf("\n"); - printf("\n"); - - // send buffer back - this->m_readBuffer[serBuffer.getbufferID()].setsize(this->m_bufferSize); - this->invoke_to_readBufferSend(0,this->m_readBuffer[serBuffer.getbufferID()]); - } - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - void Tester :: - connectPorts() - { - - // serialSend - this->connect_to_serialSend( - 0, - this->component.get_serialSend_InputPort(0) - ); - - // readBufferSend - this->connect_to_readBufferSend( - 0, - this->component.get_readBufferSend_InputPort(0) - ); - - // serialRecv - this->component.set_serialRecv_OutputPort( - 0, - this->get_from_serialRecv(0) - ); - - // Tlm - this->component.set_Tlm_OutputPort( - 0, - this->get_from_Tlm(0) - ); - - // Time - this->component.set_Time_OutputPort( - 0, - this->get_from_Time(0) - ); - - // Log - this->component.set_Log_OutputPort( - 0, - this->get_from_Log(0) - ); - - // LogText - this->component.set_LogText_OutputPort( - 0, - this->get_from_LogText(0) - ); - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init( - INSTANCE - ); - } - - void Tester::textLogIn( - const FwEventIdType id, //!< The event ID - Fw::Time& timeTag, //!< The time - const Fw::TextLogSeverity severity, //!< The severity - const Fw::TextLogString& text //!< The event string - ) { - TextLogEntry e = { id, timeTag, severity, text }; - - printTextLogHistoryEntry(e,stdout); - } - -} // end namespace Drv diff --git a/Drv/LinuxSerialDriver/test/ut/Tester.hpp b/Drv/LinuxSerialDriver/test/ut/Tester.hpp deleted file mode 100644 index 29213dd205..0000000000 --- a/Drv/LinuxSerialDriver/test/ut/Tester.hpp +++ /dev/null @@ -1,110 +0,0 @@ -// ====================================================================== -// \title LinuxSerialDriver/test/ut/Tester.hpp -// \author tcanham -// \brief hpp file for LinuxSerialDriver test harness implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef TESTER_HPP -#define TESTER_HPP - -enum { - READ_BUFF_SIZE = 4*1024, // This is large enough for the circular buffer - NUM_READ_BUFFERS = 100 -}; - -#include "TesterBase.hpp" -#include "Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp" - -namespace Drv { - - class Tester : - public LinuxSerialDriverTesterBase - { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - public: - - //! Construct object Tester - //! - Tester(const char* const device, NATIVE_INT_TYPE numReadBuffers, NATIVE_INT_TYPE bufferSize, - LinuxSerialDriverComponentImpl::UartFlowControl flow, - LinuxSerialDriverComponentImpl::UartParity parity); - - //! Destroy object Tester - //! - ~Tester(); - - public: - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - //! Send serial data - //! - void sendSerial(BYTE* data, NATIVE_INT_TYPE size); - - private: - - // ---------------------------------------------------------------------- - // Handlers for typed from ports - // ---------------------------------------------------------------------- - - //! Handler for from_serialRecv - //! - void from_serialRecv_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &serBuffer, /*!< Buffer containing data*/ - Drv::SerialReadStatus& status /*!< Status of read*/ - ); - - private: - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - //! Connect ports - //! - void connectPorts(); - - //! Initialize components - //! - void initComponents(); - - private: - - // ---------------------------------------------------------------------- - // Variables - // ---------------------------------------------------------------------- - - //! The component under test - //! - LinuxSerialDriverComponentImpl component; - - NATIVE_INT_TYPE m_numBuffers; - NATIVE_INT_TYPE m_bufferSize; - Fw::Buffer m_readBuffer[NUM_READ_BUFFERS]; - BYTE* m_readData[NUM_READ_BUFFERS]; - - void textLogIn( - const FwEventIdType id, //!< The event ID - Fw::Time& timeTag, //!< The time - const Fw::TextLogSeverity severity, //!< The severity - const Fw::TextLogString& text //!< The event string - ); - - }; - -} // end namespace Drv - -#endif diff --git a/Drv/LinuxSerialDriver/test/ut/main.cpp b/Drv/LinuxSerialDriver/test/ut/main.cpp deleted file mode 100644 index d75ddb22ba..0000000000 --- a/Drv/LinuxSerialDriver/test/ut/main.cpp +++ /dev/null @@ -1,77 +0,0 @@ -// ---------------------------------------------------------------------- -// Main.cpp -// ---------------------------------------------------------------------- - -#include "Tester.hpp" -#include -#include "Drv/LinuxSerialDriver/LinuxSerialDriverComponentImpl.hpp" -#include - - -//TEST(Test, NominalTlm) { -// Svc::Tester tester; - // Allocate read buffer -// tester.nominalTlm(); -//} - -void run_simple_test(Drv::Tester& tester) -{ - BYTE pattern[] = {0xA5, 0xA5, 0xA5, 0xA5}; - - tester.sendSerial(pattern,FW_NUM_ARRAY_ELEMENTS(pattern)); - - // delay for 10 sec waiting for some receive data - printf ("Delaying 10 sec for UART input\n"); - Os::Task::delay(1000); -} - -void run_ramping_pattern_test(Drv::Tester& tester) -{ - BYTE pattern[256]; - for (U32 i = 0; i < FW_NUM_ARRAY_ELEMENTS(pattern); ++i) { - pattern[i] = i; - } - - for (NATIVE_INT_TYPE iter = 0; iter < 20*60*100; iter++) { - tester.sendSerial(pattern,FW_NUM_ARRAY_ELEMENTS(pattern)); - Os::Task::delay(1); - } -} - -void run_router_test(Drv::Tester& tester) -{ - - // Fake FcRouter packet: - const int FC_ROUTER_PKT_SIZE = 75; - BYTE pattern[FC_ROUTER_PKT_SIZE]; - memset(pattern,0,sizeof(pattern)); - pattern[0] = 0xa5; - pattern[1] = 0x47; - pattern[2] = 0x1; - pattern[3] = 0x45; - - pattern[FC_ROUTER_PKT_SIZE-2] = 0xe6; - pattern[FC_ROUTER_PKT_SIZE-1] = 0xd5; - - for (NATIVE_INT_TYPE iter = 0; iter < 20*60*100; iter++) { - tester.sendSerial(pattern,FW_NUM_ARRAY_ELEMENTS(pattern)); - Os::Task::delay(1); - } -} - - -int main(int argc, char **argv) { - if ((argc < 1) || (argv[1] == nullptr)) { - printf("Need arg - name of device to open\n"); - return 1; - } - - Drv::Tester tester(argv[1],20,READ_BUFF_SIZE, - Drv::LinuxSerialDriverComponentImpl::NO_FLOW, - Drv::LinuxSerialDriverComponentImpl::PARITY_NONE); - - run_simple_test(tester); -// run_ramping_pattern_test(tester); -// run_router_test(tester); - -} diff --git a/Drv/LinuxUartDriver/CMakeLists.txt b/Drv/LinuxUartDriver/CMakeLists.txt new file mode 100644 index 0000000000..3d87a0e9b2 --- /dev/null +++ b/Drv/LinuxUartDriver/CMakeLists.txt @@ -0,0 +1,18 @@ +#### +# F prime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoding diles +# MOD_DEPS: (optional) module dependencies +# +#### +set(MOD_DEPS Os) + +if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux" OR ${CMAKE_SYSTEM_NAME} STREQUAL "Darwin") + set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver.fpp" + "${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver.cpp" + ) + register_fprime_module() +else() + message(STATUS "Cannot use ${CMAKE_CURRENT_LIST_DIR} with platform ${CMAKE_SYSTEM_NAME}. Skipping.") +endif() diff --git a/Drv/LinuxSerialDriver/Events.fppi b/Drv/LinuxUartDriver/Events.fppi similarity index 92% rename from Drv/LinuxSerialDriver/Events.fppi rename to Drv/LinuxUartDriver/Events.fppi index 899aa1c8b2..cd430d0c72 100644 --- a/Drv/LinuxSerialDriver/Events.fppi +++ b/Drv/LinuxUartDriver/Events.fppi @@ -1,5 +1,5 @@ @ UART open error -event DR_OpenError( +event OpenError( device: string size 40 @< The device error: I32 @< The error code name: string size 40 @< error string @@ -9,7 +9,7 @@ event DR_OpenError( format "Error opening UART device {}: {} {}" @ UART config error -event DR_ConfigError( +event ConfigError( device: string size 40 @< The device error: I32 @< The error code ) \ @@ -18,7 +18,7 @@ event DR_ConfigError( format "Error configuring UART device {}: {}" @ UART write error -event DR_WriteError( +event WriteError( device: string size 40 @< The device error: I32 @< The error code ) \ @@ -28,7 +28,7 @@ event DR_WriteError( throttle 5 @ UART read error -event DR_ReadError( +event ReadError( device: string size 40 @< The device error: I32 @< The error code ) \ @@ -38,7 +38,7 @@ event DR_ReadError( throttle 5 @ UART port opened event -event DR_PortOpened( +event PortOpened( device: string size 40 @< The device ) \ severity activity high \ @@ -46,7 +46,7 @@ event DR_PortOpened( format "UART Device {} configured" @ UART ran out of buffers -event DR_NoBuffers( +event NoBuffers( device: string size 40 @< The device ) \ severity warning high \ @@ -55,7 +55,7 @@ event DR_NoBuffers( throttle 20 @ UART ran out of buffers -event DR_BufferTooSmall( +event BufferTooSmall( device: string size 40 @< The device $size: U32 @< The provided buffer size needed: U32 @< The buffer size needed diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.cpp b/Drv/LinuxUartDriver/LinuxUartDriver.cpp new file mode 100644 index 0000000000..5ef78a26df --- /dev/null +++ b/Drv/LinuxUartDriver/LinuxUartDriver.cpp @@ -0,0 +1,372 @@ +// ====================================================================== +// \title LinuxUartDriverImpl.cpp +// \author tcanham +// \brief cpp file for LinuxUartDriver component implementation class +// +// \copyright +// Copyright 2009-2015, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include +#include +#include + +#include "Fw/Types/BasicTypes.hpp" + +#include +#include +#include + +//#include +//#include +//#define DEBUG_PRINT(x,...) printf(x,##__VA_ARGS__); fflush(stdout) +#define DEBUG_PRINT(x, ...) + +namespace Drv { + +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +LinuxUartDriver ::LinuxUartDriver(const char* const compName) + : LinuxUartDriverComponentBase(compName), m_fd(-1), m_device("NOT_EXIST"), m_quitReadThread(false) { +} + +void LinuxUartDriver ::init(const NATIVE_INT_TYPE instance) { + LinuxUartDriverComponentBase::init(instance); +} + +bool LinuxUartDriver::open(const char* const device, + UartBaudRate baud, + UartFlowControl fc, + UartParity parity) { + FW_ASSERT(device != nullptr); + NATIVE_INT_TYPE fd = -1; + NATIVE_INT_TYPE stat = -1; + + this->m_device = device; + + DEBUG_PRINT("Opening UART device %s\n", device); + + /* + The O_NOCTTY flag tells UNIX that this program doesn't want to be the "controlling terminal" for that port. If you + don't specify this then any input (such as keyboard abort signals and so forth) will affect your process. Programs + like getty(1M/8) use this feature when starting the login process, but normally a user program does not want this + behavior. + */ + fd = ::open(device, O_RDWR | O_NOCTTY); + + if (fd == -1) { + DEBUG_PRINT("open UART device %s failed.\n", device); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, this->m_fd, _err); + return false; + } else { + DEBUG_PRINT("Successfully opened UART device %s fd %d\n", device, fd); + } + + this->m_fd = fd; + + // Configure blocking reads + struct termios cfg; + + stat = tcgetattr(fd, &cfg); + if (-1 == stat) { + DEBUG_PRINT("tcgetattr failed: (%d): %s\n", stat, strerror(errno)); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } else { + DEBUG_PRINT("tcgetattr passed.\n"); + } + + /* + If MIN > 0 and TIME = 0, MIN sets the number of characters to receive before the read is satisfied. As TIME is + zero, the timer is not used. + + If MIN = 0 and TIME > 0, TIME serves as a timeout value. The read will be satisfied if a single character is read, + or TIME is exceeded (t = TIME *0.1 s). If TIME is exceeded, no character will be returned. + + If MIN > 0 and TIME > 0, TIME serves as an inter-character timer. The read will be satisfied if MIN characters are + received, or the time between two characters exceeds TIME. The timer is restarted every time a character is + received and only becomes active after the first character has been received. + + If MIN = 0 and TIME = 0, read will be satisfied immediately. The number of characters currently available, or the + number of characters requested will be returned. According to Antonino (see contributions), you could issue a + fcntl(fd, F_SETFL, FNDELAY); before reading to get the same result. + */ + cfg.c_cc[VMIN] = 0; + cfg.c_cc[VTIME] = 10; // 1 sec timeout on no-data + + stat = tcsetattr(fd, TCSANOW, &cfg); + if (-1 == stat) { + DEBUG_PRINT("tcsetattr failed: (%d): %s\n", stat, strerror(errno)); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } else { + DEBUG_PRINT("tcsetattr passed.\n"); + } + + // Set flow control + if (fc == HW_FLOW) { + struct termios t; + + int stat = tcgetattr(fd, &t); + if (-1 == stat) { + DEBUG_PRINT("tcgetattr UART fd %d failed\n", fd); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } + + // modify flow control flags + t.c_cflag |= CRTSCTS; + + stat = tcsetattr(fd, TCSANOW, &t); + if (-1 == stat) { + DEBUG_PRINT("tcsetattr UART fd %d failed\n", fd); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } + } + + NATIVE_INT_TYPE relayRate = B0; + switch (baud) { + case BAUD_9600: + relayRate = B9600; + break; + case BAUD_19200: + relayRate = B19200; + break; + case BAUD_38400: + relayRate = B38400; + break; + case BAUD_57600: + relayRate = B57600; + break; + case BAUD_115K: + relayRate = B115200; + break; + case BAUD_230K: + relayRate = B230400; + break; +#if defined TGT_OS_TYPE_LINUX + case BAUD_460K: + relayRate = B460800; + break; + case BAUD_921K: + relayRate = B921600; + break; +#endif + default: + FW_ASSERT(0, baud); + break; + } + + struct termios newtio; + + stat = tcgetattr(fd, &newtio); + if (-1 == stat) { + DEBUG_PRINT("tcgetattr UART fd %d failed\n", fd); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } + + // CS8 = 8 data bits, CLOCAL = Local line, CREAD = Enable Receiver + /* + Even parity (7E1): + options.c_cflag |= PARENB + options.c_cflag &= ~PARODD + options.c_cflag &= ~CSTOPB + options.c_cflag &= ~CSIZE; + options.c_cflag |= CS7; + Odd parity (7O1): + options.c_cflag |= PARENB + options.c_cflag |= PARODD + options.c_cflag &= ~CSTOPB + options.c_cflag &= ~CSIZE; + options.c_cflag |= CS7; + */ + newtio.c_cflag = CS8 | CLOCAL | CREAD; + + switch (parity) { + case PARITY_ODD: + newtio.c_cflag |= (PARENB | PARODD); + break; + case PARITY_EVEN: + newtio.c_cflag |= PARENB; + break; + case PARITY_NONE: + newtio.c_cflag &= ~PARENB; + break; + default: + FW_ASSERT(0, parity); + break; + } + + // Set baud rate: + stat = cfsetispeed(&newtio, relayRate); + if (stat) { + DEBUG_PRINT("cfsetispeed failed\n"); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } + stat = cfsetospeed(&newtio, relayRate); + if (stat) { + DEBUG_PRINT("cfsetospeed failed\n"); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } + + // Raw output: + newtio.c_oflag = 0; + + // set input mode (non-canonical, no echo,...) + newtio.c_lflag = 0; + + newtio.c_iflag = INPCK; + + // Flush old data: + (void)tcflush(fd, TCIFLUSH); + + // Set attributes: + stat = tcsetattr(fd, TCSANOW, &newtio); + if (-1 == stat) { + DEBUG_PRINT("tcsetattr UART fd %d failed\n", fd); + close(fd); + Fw::LogStringArg _arg = device; + Fw::LogStringArg _err = strerror(errno); + this->log_WARNING_HI_OpenError(_arg, fd, _err); + return false; + } + + // All done! + Fw::LogStringArg _arg = device; + this->log_ACTIVITY_HI_PortOpened(_arg); + this->ready_out(0); // Indicate the driver is connected + return true; +} + +LinuxUartDriver ::~LinuxUartDriver() { + if (this->m_fd != -1) { + DEBUG_PRINT("Closing UART device %d\n", this->m_fd); + + (void)close(this->m_fd); + } +} + +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- + +Drv::SendStatus LinuxUartDriver ::send_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& serBuffer) { + Drv::SendStatus status = Drv::SendStatus::SEND_OK; + if (this->m_fd == -1 || serBuffer.getData() == nullptr || serBuffer.getSize() == 0) { + status = Drv::SendStatus::SEND_ERROR; + } else { + unsigned char *data = serBuffer.getData(); + NATIVE_INT_TYPE xferSize = serBuffer.getSize(); + + NATIVE_INT_TYPE stat = ::write(this->m_fd, data, xferSize); + + if (-1 == stat || stat != xferSize) { + Fw::LogStringArg _arg = this->m_device; + this->log_WARNING_HI_WriteError(_arg, stat); + status = Drv::SendStatus::SEND_ERROR; + } + } + // Deallocate when necessary + if (isConnected_deallocate_OutputPort(0)) { + deallocate_out(0, serBuffer); + } + return status; +} + +void LinuxUartDriver ::serialReadTaskEntry(void* ptr) { + FW_ASSERT(ptr != nullptr); + Drv::RecvStatus status = RecvStatus::RECV_ERROR; // added by m.chase 03.06.2017 + LinuxUartDriver* comp = reinterpret_cast(ptr); + + while (!comp->m_quitReadThread) { + // wait for data + int sizeRead = 0; + + Fw::Buffer buff = comp->allocate_out(0, Drv::UART_READ_ALLOCATION_REQUEST_SIZE); + + // On failed allocation, error and deallocate + if (buff.getData() == nullptr) { + Fw::LogStringArg _arg = comp->m_device; + comp->log_WARNING_HI_NoBuffers(_arg); + status = RecvStatus::RECV_ERROR; + comp->recv_out(0, buff, status); + // to avoid spinning, wait 50 ms + Os::Task::delay(50); + continue; + } + + // timespec stime; + // (void)clock_gettime(CLOCK_REALTIME,&stime); + // DEBUG_PRINT("<<< Calling dsp_relay_uart_relay_read() at %d %d\n", stime.tv_sec, stime.tv_nsec); + + int stat = 0; + + // Read until something is received or an error occurs. Only loop when + // stat == 0 as this is the timeout condition and the read should spin + while ((stat == 0) && !comp->m_quitReadThread) { + stat = ::read(comp->m_fd, buff.getData(), buff.getSize()); + } + + // On error stat (-1) must mark the read as error + // On normal stat (>0) pass a recv ok + // On timeout stat (0) and m_quitReadThread, error to return the buffer + if (stat == -1) { + Fw::LogStringArg _arg = comp->m_device; + comp->log_WARNING_HI_ReadError(_arg, stat); + status = RecvStatus::RECV_ERROR; + } else if (stat > 0) { + buff.setSize(sizeRead); + status = RecvStatus::RECV_OK; // added by m.chase 03.06.2017 + } else { + status = RecvStatus::RECV_ERROR; // Simply to return the buffer + } + comp->recv_out(0, buff, status); // added by m.chase 03.06.2017 + } +} + +void LinuxUartDriver ::startReadThread(NATIVE_UINT_TYPE priority, + NATIVE_UINT_TYPE stackSize, + NATIVE_UINT_TYPE cpuAffinity) { + Os::TaskString task("SerReader"); + Os::Task::TaskStatus stat = + this->m_readTask.start(task, serialReadTaskEntry, this, priority, stackSize, cpuAffinity); + FW_ASSERT(stat == Os::Task::TASK_OK, stat); +} + +void LinuxUartDriver ::quitReadThread() { + this->m_quitReadThread = true; +} + +} // end namespace Drv diff --git a/Drv/LinuxSerialDriver/LinuxSerialDriver.fpp b/Drv/LinuxUartDriver/LinuxUartDriver.fpp similarity index 61% rename from Drv/LinuxSerialDriver/LinuxSerialDriver.fpp rename to Drv/LinuxUartDriver/LinuxUartDriver.fpp index f41b4b8838..151ef8b825 100644 --- a/Drv/LinuxSerialDriver/LinuxSerialDriver.fpp +++ b/Drv/LinuxUartDriver/LinuxUartDriver.fpp @@ -1,14 +1,25 @@ module Drv { - passive component LinuxSerialDriver { + passive component LinuxUartDriver { # ---------------------------------------------------------------------- # General ports # ---------------------------------------------------------------------- - sync input port readBufferSend: Fw.BufferSend + @ Indicates the driver has connected to the UART device + output port ready: Drv.ByteStreamReady - sync input port serialSend: Drv.SerialWrite + @ Produces data received via the UART device on the receive task + output port $recv: Drv.ByteStreamRecv + + @ Takes data to transmit out the UART device + guarded input port send: Drv.ByteStreamSend + + @ Allocation port used for allocating memory in the receive task + output port allocate: Fw.BufferGet + + @ Deallocates buffers passed to the "send" port + output port deallocate: Fw.BufferSend # ---------------------------------------------------------------------- # Special ports @@ -16,8 +27,6 @@ module Drv { event port Log - output port serialRecv: Drv.SerialRead - telemetry port Tlm text event port LogText diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.hpp b/Drv/LinuxUartDriver/LinuxUartDriver.hpp new file mode 100644 index 0000000000..2beaedc81c --- /dev/null +++ b/Drv/LinuxUartDriver/LinuxUartDriver.hpp @@ -0,0 +1,88 @@ +// ====================================================================== +// \title LinuxUartDriverImpl.hpp +// \author tcanham +// \brief hpp file for LinuxUartDriver component implementation class +// +// \copyright +// Copyright 2009-2015, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef LinuxUartDriver_HPP +#define LinuxUartDriver_HPP + +#include +#include +#include +#include + +namespace Drv { + +class LinuxUartDriver : public LinuxUartDriverComponentBase { + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object LinuxUartDriver + //! + LinuxUartDriver(const char* const compName /*!< The component name*/ + ); + + //! Initialize object LinuxUartDriver + //! + void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ + ); + + //! Configure UART parameters + enum UartBaudRate { BAUD_9600, BAUD_19200, BAUD_38400, BAUD_57600, BAUD_115K, BAUD_230K, BAUD_460K, BAUD_921K }; + + enum UartFlowControl { NO_FLOW, HW_FLOW }; + + enum UartParity { PARITY_NONE, PARITY_ODD, PARITY_EVEN }; + + // Open device with specified baud and flow control. + bool open(const char* const device, UartBaudRate baud, UartFlowControl fc, UartParity parity); + + //! start the serial poll thread. + //! buffSize is the max receive buffer size + //! + void startReadThread(NATIVE_UINT_TYPE priority = Os::Task::TASK_DEFAULT, + NATIVE_UINT_TYPE stackSize = Os::Task::TASK_DEFAULT, + NATIVE_UINT_TYPE cpuAffinity = Os::Task::TASK_DEFAULT); + + //! Quit thread + void quitReadThread(); + + //! Destroy object LinuxUartDriver + //! + ~LinuxUartDriver(); + + PRIVATE: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for serialSend + //! + Drv::SendStatus send_handler(NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& serBuffer); + + + NATIVE_INT_TYPE m_fd; //!< file descriptor returned for I/O device + const char* m_device; //!< original device path + + //! This method will be called by the new thread to wait for input on the serial port. + static void serialReadTaskEntry(void* ptr); + + Os::Task m_readTask; //!< task instance for thread to read serial port + + + bool m_quitReadThread; //!< flag to quit thread +}; + +} // end namespace Drv + +#endif diff --git a/Drv/LinuxUartDriver/Telemetry.fppi b/Drv/LinuxUartDriver/Telemetry.fppi new file mode 100644 index 0000000000..ec8fd1ce51 --- /dev/null +++ b/Drv/LinuxUartDriver/Telemetry.fppi @@ -0,0 +1,5 @@ +@ Bytes Sent +telemetry BytesSent: U32 id 0 + +@ Bytes Received +telemetry BytesRecv: U32 id 1 diff --git a/Drv/SerialDriverPorts/CMakeLists.txt b/Drv/SerialDriverPorts/CMakeLists.txt deleted file mode 100644 index f681d9ea94..0000000000 --- a/Drv/SerialDriverPorts/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -#### -# F prime CMakeLists.txt: -# -# SOURCE_FILES: combined list of source and autocoding diles -# MOD_DEPS: (optional) module dependencies -# -#### -set(SOURCE_FILES - "${CMAKE_CURRENT_LIST_DIR}/SerialDriverPorts.fpp" -) - -register_fprime_module() diff --git a/Drv/SerialDriverPorts/SerialDriverPorts.fpp b/Drv/SerialDriverPorts/SerialDriverPorts.fpp deleted file mode 100644 index 13744b76ce..0000000000 --- a/Drv/SerialDriverPorts/SerialDriverPorts.fpp +++ /dev/null @@ -1,24 +0,0 @@ -module Drv { - - port SerialWrite( - ref serBuffer: Fw.Buffer - ) - -} - -module Drv { - - enum SerialReadStatus { - SER_OK = 0 @< Transaction okay - SER_PARITY_ERR = 1 @< Parity error on data - SER_NO_BUFFERS = 2 @< Serial driver ran out of buffers - SER_BUFFER_TOO_SMALL = 3 @< Target buffer is too small - SER_OTHER_ERR = 4 @< Other errors that don't fit - } - - port SerialRead( - ref serBuffer: Fw.Buffer @< Buffer containing data - ref status: SerialReadStatus @< Status of read - ) - -} diff --git a/Drv/UartFramer/CMakeLists.txt b/Drv/UartFramer/CMakeLists.txt deleted file mode 100644 index a46d3d6b54..0000000000 --- a/Drv/UartFramer/CMakeLists.txt +++ /dev/null @@ -1,26 +0,0 @@ -#### -# F prime CMakeLists.txt: -# -# SOURCE_FILES: combined list of source and autocoding diles -# MOD_DEPS: (optional) module dependencies -# -#### -set(MOD_DEPS Os) - -set(SOURCE_FILES -"${CMAKE_CURRENT_LIST_DIR}/UartFramer.fpp" -"${CMAKE_CURRENT_LIST_DIR}/UartFramer.cpp" -) -register_fprime_module() - -## UTs ### -# Note: this UT expects user input -set(UT_MOD_DEPS - Os -) -set(UT_SOURCE_FILES - "${CMAKE_CURRENT_LIST_DIR}/UartFramer.fpp" - "${CMAKE_CURRENT_LIST_DIR}/test/ut/TestMain.cpp" - "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" -) -register_fprime_ut() diff --git a/Drv/UartFramer/UartFramer.cpp b/Drv/UartFramer/UartFramer.cpp deleted file mode 100644 index 155e4e5eff..0000000000 --- a/Drv/UartFramer/UartFramer.cpp +++ /dev/null @@ -1,106 +0,0 @@ -// ====================================================================== -// \title UartFramer.cpp -// \author tcanham -// \brief cpp file for UartFramer component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - - -#include -#include "Fw/Types/BasicTypes.hpp" -#include "Fw/Types/Assert.hpp" - -namespace Drv { - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - UartFramer :: - UartFramer( - const char *const compName - ) : UartFramerComponentBase(compName), m_size(0) - { - - } - - void UartFramer :: - init( - const NATIVE_INT_TYPE instance - ) - { - UartFramerComponentBase::init(instance); - } - - UartFramer :: - ~UartFramer() - { - - } - - void UartFramer::allocate(NATIVE_UINT_TYPE number, NATIVE_UINT_TYPE size) { - - FW_ASSERT(size > 0, size); - this->m_size = size; - - Fw::Buffer buff; - // request a buffer and pass it on to the UART for each requested - for (NATIVE_UINT_TYPE buffNum = 0; buffNum < number; buffNum++) { - buff = this->DeframerAllocate_out(0,this->m_size); - FW_ASSERT(buff.getSize() == size,buff.getSize(),size); - FW_ASSERT(buff.getData()); - this->readBufferSend_out(0,buff); - } - - } - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - Drv::SendStatus UartFramer :: - Framer_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &sendBuffer - ) - { - this->serialSend_out(0,sendBuffer); - this->FramerDeallocate_out(0,sendBuffer); - // no status from send, so return OK - return Drv::SendStatus::SEND_OK; - } - - void UartFramer :: - serialRecv_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &serBuffer, - Drv::SerialReadStatus &status - ) - { - - Drv::RecvStatus outStat = Drv::RecvStatus::RECV_OK; - // Check the UART status - if (status != Drv::SerialReadStatus::SER_OK) { - outStat = Drv::RecvStatus::RECV_ERROR; - } - - // Forward buffer to deframer - this->Deframer_out(0,serBuffer,outStat); - - // allocate a replacement buffer and send it to - // the UART driver - Fw::Buffer newBuff = this->DeframerAllocate_out(0,this->m_size); - if (newBuff.getSize() != this->m_size) { - this->log_WARNING_HI_BuffErr(); - } else { - this->readBufferSend_out(0,newBuff); - } - - } - -} // end namespace Drv diff --git a/Drv/UartFramer/UartFramer.fpp b/Drv/UartFramer/UartFramer.fpp deleted file mode 100644 index e459c7b75f..0000000000 --- a/Drv/UartFramer/UartFramer.fpp +++ /dev/null @@ -1,62 +0,0 @@ -module Drv { - - passive component UartFramer { - - # ---------------------------------------------------------------------- - # Ports for UART - # ---------------------------------------------------------------------- - - @ port to send a buffer for reads to the UART driver - output port readBufferSend: Fw.BufferSend - - @ send a UART buffer - output port serialSend: Drv.SerialWrite - - @ receive a buffer from the UART - one of the above - sync input port serialRecv: Drv.SerialRead - - # ---------------------------------------------------------------------- - # Ports for Framer/Deframer - # ---------------------------------------------------------------------- - - @ Buffer from Framer - sync input port Framer: Drv.ByteStreamSend - - @ Buffer to Deframer - output port Deframer: Drv.ByteStreamRecv - - # ---------------------------------------------------------------------- - # Ports to get buffers - # ---------------------------------------------------------------------- - - @ Allocation output port - will be sent to Deframer for deallocation - output port DeframerAllocate: Fw.BufferGet - - @ Deallocation output port - deallocation of Framer buffers - output port FramerDeallocate: Fw.BufferSend - - - # ---------------------------------------------------------------------- - # Special F Prime ports - # ---------------------------------------------------------------------- - - event port Log - - text event port LogText - - time get port Time - - # ---------------------------------------------------------------------- - # Events - # ---------------------------------------------------------------------- - - @ UART open error - event BuffErr() \ - severity warning high \ - id 0 \ - format "Couldn't get UART buffer" \ - throttle 5 - - } - -} diff --git a/Drv/UartFramer/UartFramer.hpp b/Drv/UartFramer/UartFramer.hpp deleted file mode 100644 index cea6af3fae..0000000000 --- a/Drv/UartFramer/UartFramer.hpp +++ /dev/null @@ -1,86 +0,0 @@ -// ====================================================================== -// \title UartFramer.hpp -// \author tcanham -// \brief hpp file for UartFramer component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef UartFramer_HPP -#define UartFramer_HPP - -#include "Drv/UartFramer/UartFramerComponentAc.hpp" - -namespace Drv { - - class UartFramer : - public UartFramerComponentBase - { - - public: - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object UartFramer - //! - UartFramer( - const char *const compName /*!< The component name*/ - ); - - //! Initialize object UartFramer - //! - void init( - const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ - ); - - //! Destroy object UartFramer - //! - ~UartFramer(); - - - //! Allocate pool of buffers for UART receive - BufferManager and UART - // instances must be connected and ready. BufferManager should have at least - // number+1 buffers allocated - void allocate(NATIVE_UINT_TYPE number, NATIVE_UINT_TYPE size); - - PRIVATE: - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for Framer - //! - Drv::SendStatus Framer_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &sendBuffer - ); - - //! Handler implementation for serialRecv - //! - void serialRecv_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &serBuffer, /*!< - Buffer containing data - */ - Drv::SerialReadStatus &status /*!< - Status of read - */ - ); - - // Private data members - - NATIVE_UINT_TYPE m_size; //!< size of UART buffers - - - }; - -} // end namespace Drv - -#endif diff --git a/Drv/UartFramer/docs/UartFramer.vsdx b/Drv/UartFramer/docs/UartFramer.vsdx deleted file mode 100644 index 8fab7e49063aab88cff24f0cd9c8f9fe58b23fe5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 57961 zcmeF2V*W5aU{+Jh?+e~3nYfR z&7fwJj3TfyV7y!{WU{AkA489e+Y{%)bW0$9N((7x4OlhsqB_M?vr!$2m{+!OVN~(( zA#BQ39#CfzS-lR2mI%4lPDwjNW6s4X1-kmtr zB~eDEn9+c!AJ6g;ZYcF3XkR)%fZKkrZno(PC(4`_=pL2^T`#(t_C-r@E|*A&;^OII zwxXzSiK*n&U84LR3qpbYgb+4=#a~nvEcO^WeUK730^}oF?pEJ1|JuApaX>bs99|Gc;nfodaw^vLsT8J0KkMDTec$z-~)mFVAPd_&cV;4nid2HSJuSravHR8{ozHe_%V&t-Z;5_?g8=0JH=P%&^)-_H)wvD`008q> z=eqXBmJST`|E&LC-~SJb`oBDSMf~_b`WAbZ_y{=k+ArV@l#jPYRCIw1LcqL`G(ZwC zk}G?b~~&r%dpbK4JKVcL{+W~H%SvWSw@r2!G2`~>$Bd>T=l2wd9AlO znhVPkN^5)3EOK_&B>5hOedxi2z$&i$Pohm7WGI)wU%A|HU|R%X11GA=+5c8mwywjM zxu^g@s~-S>{PzxLGY2yp1|u6oC#%0b^q=N=p>5@`-h%YCmHGuCdmXTLI^f=XfwPX+ zsTS?w%`^Vf{&OyuY-BHpSS8MW@BMKT3=)_S9o0$J>v-u&#=tBa486yoR*iNfzuQY2 ztdRnp!W$KTS<_?EJu0Z)^eQA~_))ga)kVJg^YS3Zhx2U*#0Yniod&&#Z3jAj|BYF8 zd7A@!)N=HfPF?eziCuzdgrg05CHAbr?zGxI6c*0q@A6GGH*YnJj_qM|mxkX&3GJbK ziOJ+13LhzGL>589Y41@fU^>uq{%v3Ffy zG2!qS(v@%r)Ls#OhFu5RyQUmA?Ck)fu8}^u+@Ev$y z43*;AKVJb=R6gb9n^k82c$^&zcbmH*L4-|0PMG{7#Q)+r_6gLR zNrT~0{wIf%A%ch`0!pD+ZuP5}2|Cd&Fdt9&aheM zWu!-|^Zbh7$z$?&xvs~u`4i9Q&vuWQa=azIP;qGn@JmqT>Uy6U8>e-=kGCP1d{A1^ z_NB8$_eS>b%O&m`frmrV8+^a~`J*-kR71pf9X%Mo!)JJSc#TxV%3t-1RM5SHAXwa; zYwe%-HJEt~=I@Qx=d5I6w#f+Aq;H^dHK%BCbL!qWLp zYV!8N_;8s3^S50p^qNln;ziTbqFi_A(VHlS<9?yut==eg(;oX;V2kLQW$~^j;_z&8 z={L;2GLv8362fXefqh&0e34$d_|_VE$==BsC&}7s`wGmU9%d$6_%92~(an1eNDFzp z*qnT<6-S*$rf7+SrOl*pgsSr6qVZRZPWgOs(lak>L^eCz$x&nbnZ~wENHt(2@#hg# z3{g^D26QNCfmJI8LT_pjUeK>@_Q>jEvYOKg7|e+y)^M&d%%F}o{Td{r{Bip`M=Y<} z^A^2`hq(wLGOIPZpF|i)8B`c%n1y=WS_=rYKfO$62yY0&%!2B-a+T*y?(vJv5@dt; zYKcu8U{Z&@VWZ(+hMH-kS6(k9*$4vev8d{Ocr6HgPJDKqL4TOt;UK{0>y!k zVjC4&;MDsT4kU>3^PifrGxD?UvPv7dSKLDLra_}GFuuJNczt)cmU<=<5V5+s2?tkLki7?5F>z z1IBwyjEu(kS|AU5308W~ya~HZQJMUSx(2SAo?ZKdW=^tKR-}+-@ho{!U`IIp2Sw85 zL1-_qHVDKshV$s&kGv>VB$*&nA$T$wM)WDZRrg7zb^yVv=LDJYZu@&FJ-zM^Z@p>V zJXiXI+0vDSb3~VA&&oY9%yQI;h}vZLRn9gKT-!9}7Q14(nd1ErJ=B+0XGw!=3pK5N1lAItJgjZZMv7>_98xDRE6UksW-KGcQwTU4SJ5{CyJKdFzM zpa#{o2Uu(xk=IO04k06LVVU5V+>2P44h)g&NYlN^(T+r5d&?|W8YM;B^=H)oWFxX9 zwi8<*SfSM>BEjIFRPL}E5xhguf=qMGVtVOoU-i@*s_#2)a>+4X6(~gcPouQfv?Cgx zusd3aOADj~oH#SsI@tB^q4n3G?qa0^`UIGPI3E06EWm;FV}A2=qkPk(#~5L(J){%9 zDGCRB=};SZR{hE|UF~Y61e~Z!J_-(Au5NRbv(fp2+o}>q0EUxKOe!G(obOocj8L9t zL#$p?&^w#9Qgrj4IYsBbcgSdTVth3oj7objPXmN9iWgm)Nj=yh`rxc=?6Otq zH9zXZ@>$`*N8MVs5LpawP+uJ?Y%y7`S!!?W#T;S9Q_F0-m^78rVVc3mY9|-_Q%d5_ z5Fyfuh#Krs5d)nGzqK8~>M7#3a%U4uEba? zHVgVmUstMCdr}$^dF2)nP<=$9z*r_n#9Lz$4UcZ88HtRTB3$DuxWW_w9QvM^cOAvm z(~aR}=^2wp2Abs~xAS91j(N`4UYI@njhOmFJ8#<-MQoj{t6LbVN7m0^k-d`eEp1TX zMS0{B++VJ?$%OIYY8dXNZv%a&r#$6%xf!iHbZ~DSG^2bR7yTbZ(Su5-WC&{^Fia_z z)56+sCuuuE9W<>bqH5qlSr;_i&O{|X)wt}@ay&dxVV!IS6=>?!fsRgkScz7$WN5xD+B$c>1uZMXu4k`n^$5s1m!D_*oAHtV! z!6zWTg*op!ig>qNlFoxCoZ6VFad%)j70`Z^l|c-5YpgRKei6MuZVg*0=^60&s?hpC zDuF19ijbyU{q@ChOFB7+!P;tIp>xzC==^Vp=AVCG1@q`{0!=e!Q2HLd`^AWqwT)1? z;|l>VF|Z#B`m+R>n)|;XqHiEoZ<6R3*B~by0wd6T@gc;1=vyM8Wp1%#-9|}TJ2~-< zNy5*@{)Ax*T8NzIs)&NWGfA3CQi5z>z5B^EX$B4IR^vZUI;++%hoa2Ndo-J2#|XiX zoRNsXY;*N6M7=aS7oem?w5lVWL1`kc==&1>+xNl$B{Iz*586Rgbx=_e+HaN0zrB!B z%Tx-8SN9(8c#Bks~UocijMD0Z6=9Jd^vRRWo|=e3Kux6wJ&lKsAz& z24r8m#VfX*2KRRN@ewSeupPMegyr;iE3R3J3C9BeV7Y%{Rt`=?Um2rmyv4)oq5uWi zCC=~`M$JHX9E|giv>->AqGiRfU0$s>1n= zU`y`~GLjxQL{B#zDm{IvRqbS23>WdM_Tc=EYglx!?MmtOc8If4bABn|V370FJx_zS zps;^-;`7%}V5Sqy&CM`O?OX{2J+n=^OdaNTr8xJ%Nn)Utw?yr`%)ww-ARwSSej8%s zFD3KwJ?FKk2V;KmWjGE3Rlu$ynjh+lXb{V$_I&{@ukq4b&43kv z<$(y{7u>=-R8$5GJoj}p!}&nQQvp9YaYuYQX#mAN&+_D-mpG(=M{*hQ8$$z0@=CE- z3o_vw+H^Xag0Fmr5h&q9%G-w6xWFU6bZr&MEVl&TUvD=)MW)<4@)^NMpy#H5!z^gg z^gQ#2`|SP*$S`v3vqk9vYMCVN3h6y0^>V{NZCgj1oIP$S@e6n0(pI@wW*}1-joolV z2xG#|nLk+3H#yQIb~lh_Cg&>&vwTPdvn#2J4j6hnVzQI;c<9WTrB7TeO#aL>U~j?N zAGP{rt(nvU4i6q}bICp6$)swZ4&uLR!G=qrgCK`GbS0l1%kW*mEy_7Iax!9o0-!BN z?O{Xti5c|DHsn>z%Xwut^;!pd-o|eyFV1Fk$jQes9u-)UFBR?3zvJ1NLKRZ}TZlJt zFKLnwm_*v1#Fd0aV2JKd8BH_F*2E|4qiAtU_SJhfh?zU2; zwdgMzB@4O4EMZO?WwaV{8#Y&_+UZR*Pm+O8LAvp3W-UvkvYrT?-(XpJ`RaaT2n@p{zNj=vgEa$gq~V`QU&K zwqOrUP}DZJmqx?{8Yh4P2YI?TeAm&FuOUWbz|PXwiwSPe%R6&*Y_hVtl0K_=`3y5y zO~R^en+_BDKaVz2+w=VyUIZ>SJ`vvNhHz&xi8fW31iw|TMW>h&C3~6+#m$47=2mSj z{nyG2$;GK~9hapxDUEwnyhH93-h}zZ+-?cK=v{dlMOa@hylr{D9PSy~E>*n3qgD!& zgdw|jrpoQ_9k{H8+%D=To=;4>Ahd$~KE#`!_2(nLATlENc1--pUjnm~zfPY~ovDu^ z**t;>_9BY2x92 zoTORu*q@}SYTvX{zHg4DI2<~Nezw86^SloydfyT2*fVfk?PNruxrWCF?bW^^bv!rb zf#qI&f{A3g-Od*vT-M*?W}IaiwCEiII#4mvh9QsGG5I)iXY?bghC*rSbJ7Ra*To?h z3_9-z_3sdu+0ohKW>TQ5C_U3)5~8TWK%u-#WAY35psjY@Oz~A;j)s!iePi;gnbU=Y z)y0`O9{~;TN|FJ%*#(`42j`^&kU*$`O3uTMwDIOYa(d7=cna-FU-8;BcmtPaJ14N zXxxkvvMJdjTwuZug!00Lk%|09l)yNw7ab_jkiphQgFr)FUXtpKSXOH+Z%QWm!(TcA zPD$FCJvzqKaR(~u>N)9?d6ooYBWl4j#;LKvvm4X`ve4c=BG^nx?4Q3L?jHJg_NK*A z=V5u3{m)GtG_kb)Kxts7{z|lfOoc6sE83XFw*Sp= zgW3`M*0fo>wPIgLHQz{^j7m>aO}dX*le09ihK^SAu5T=W)Nz%Q!3Z0vr!nso?Q2|v<)8q(NVnEz4F)62R|D0k@itJcsL3|W4xDxP zdueUI&E5u@qO;9h*Sq!>O`Jm4vi0!~18cisQMpdsE|L4F_D)S4{q5(?Da8&DnUlH} z>-KnK6xy}VopApgxTP!D>mIOl12^p!VvMv)?G|Ng!7I}{KNkUF5E{lgzJ_({GS(ZN ziViqr(_@QR#)PU^B%!^UPZe8do#6ICXJ&A9r`8} znCkLBKyRv)-q%hM-QR74*WK2)2s+I#A=OGBHt!!G$JnQ=<_s+jos|&Jro5B;+4@6aD*O5g-lE}b@^e4|IEv-XIu_3d)1EoE4Lx$Wm zRdQ;Z?garM^;YmtOGWZ<{mZ=W*BY~;p3aAVf+LoXwlFJ}zqfQ` zRX3SF&JTHF@5xJcWT>bU4~AmLi3)37V*Im%!2aG2baz|pj z4$e*Sg9F|uv*OG4-lg&IBLRmc$ST6E3AzLS4EmQ&gHR;Hl{KjXBL23nP9!jcq#_!>?J`z#!s=b95~`{}{(W5{O!y7H9BDGL*dLy!e84{apo9Tr%Nb^ElhiR8!kZlufqjp{0f_s*cH)X__&1 z`;kGbk)Bt2-{L?S(=2pj6N~$9 zQS&b(zq)xwM%PQb|04RoGZw(sK;7YAXzhP97Seygv(k5PG`4qO_)m!c^XeaK_&*pn z%y<67u;-R9)&;S7xGr;mip;)Aa4C-8Hg-hHbBC_-{gXlg3Y7ebu#@qFU~ zF)Z)p2S7OcBlDP9RG=R=b7TtW$HaR067ZJ>Zvr9$S1lb;6IU%25j$5c4UsdKov!f4 z@qjjz-80SIVDkCDH_abLb2L`|;_3feV}$?0WUFst{J$Xm$N9eyRm}ZQM4kU2TCU41 zNI>M$B(#tu5FEi!A9xd_5WahAg$-&$mBaswNX~zq;L017W8%O-eny!M5|;dlUJY#f zc>kROlA8O$JrW3wH+E;Ha_dQ#^Q`=h!S|%Emp^$lYJbfR*wxP6G;fdB>$Rt9n z*Fr<}gEaQr;&M)drvdd;vJ8K#5^_uUb?bX_BPg^Pl&#^*CCvq3hk z!FRx{QJ$J;5I<&^<>}dNh(b4OPE_3>3q>4camG=lm-RP_u!&zAWzmnUGEc70&*u1a z(_ja%0yF%Q`@E58k51mKeb%wYgn^7hOAS*dX%9^@eP|jcwBf?-dPdzU z)qZjFo$iw=Q~|4i9xyOd9qB3MaAVtRZ8y=Ov{n_L7nSv_g{YcWbM48={Js~4uVr0c z)&?P3XWub-!xQOyJ-Bt}p0u-L7(PkU=k_@4l5Wk{_U|)4<);FtH&^G{nI*aCYMR-` zcpR)47(w9mp0X{hYFbP54PDd_t}e%%<8mVulgO{o(&|*gbRXUG5$BZFOI88y+qgeJ zAEzJfC6<=JMSC~0330Kd#g`BcKYq&STi+}i8#=!O#rTcIe;I`aRXQj_#<*9|3&J)(6NUtd*leMXG3f> z&oF<}7O=ov;;ZcEK9~UGdnJY(hWIQ<^-)dE!&f@#j>T79j0dc7rq^dq?>8{F;3T8@ zUZ@qezrZ7`b^tsgI8d-fkD%@(h0Sv<-Xbx^kv84K)HQHpf`aZC&An+Fy$cvR4j{7B&@i)N7 z-blZc7q19}D7%m=C9SxwI|58KXM5>TStttv+RH+;Ki7A7E;%XA9Qt=lK2?MB= z+FYm++tTvKfr%Cf;V4n83F^eHjoP9SEJ4JC5RjX|SA9kbPUuE1$F%JQtrZG3Rb_Yy zpMhFAFw$M9$gf1L+hJN~v0EW7{#*@TS%+CYSo6K80k+Y58V}Rkf_AJsf)0|-i4W4U z^gT{82|TxakBfq7`xmX2n~<1yMvJ3Av+<{Afu=zk-D!Dt-0lY*l|2*m>Mvh&CL8Cl~5-s+$mBw;85&=4J-M7Ow5ou+#s^+4TH#s0kx0$Q2b+TQl@ zs0*Ak2=PDya`T5C3NjsB>Mf&#eb0N8VMV7w7<2=s+>d<3{BOS0)NvJ|Fv|#TOV3^# zCwO#{kS+6+IxS}QNQ3pTebF6@{()4!6534Ue(C<1qZ_*9sFz-Kj(p5J$xMdjbS+HeW3>4O53D+Xu$7sDgpCKDcGV@Ju{-l!B=y7_HtWf6K zqnO-f1)5_5Zd3LsMb!xJO&bJ~{wxb`{zYrydZkH3rg3v@P9{dH(eQ5^*3bxij=(P9 z)3~%PPZTJ?C}3rl!k(M7y_nkZ`X@FUSgq+OarOkCu^WZyfS-Ov`w&8_Z&Kcp5lf4Q zv7kWDZas#_-7oQuQw{>~u2IKV5Falr3`=ZPVFKyJmDDcxqi^GmX|WGDi+|{i#HtMv zpam4ba&v`j`W!%nr~66FR`iFjuytbEI}>(#_Yj#Z%94~7oGl{zTfcXTU2@wkoqw(GI02ejS?UVXm&a5W+L=#k@?wAkCZWKV=Y7xA5+ zg*91SkyN3P4~S0LuX{$ouhUW)8QM=GT_nn;^F`@@sx>WSiSO2WOwWdvFrr`F-J!Ko6k^)*mr>8~K9qKX=+U!0Y^E^KEC*n8Wr) zfZ5nwWI64tbiZ3eSGt@mY^N@(r6|$T()#l2?8ivf)KEhGZoqJ(kJY0U1O)j7wG8Eb za!y3iwD@1!?<1b&W@CeRht7skXt~}yPI~p*^Y7;|MwylvLPduMxYv1qN36)j-3OdR1#D9&2RZ^8m zJg)?J0C}RE@ zs5Pf%@B4BX{uj6c>e~^CU4ed^5-uQlTNQ7br#Gzab2`BEhXdWS{EF6y${ASG!u$Cq zz6`<^QP0@v+ue$|DiUAIrf@kRFIgV38UE^`y5!!Rk5Nl8@1H}W3#)_TNI3fki%AP z3mtq;6H=(R5F!7cK@d=L%>Y3A6bBXPfO>ugy(3`=aBC%U(I!N$jyUYnUcOF8`%wx?G#G=$y4OD#<3O)@&4k-iK8x)%fE1FU{7pySI>A z6bbV-ydC=9g8>C^gyjJIUC!arw&a+70=*0P9m@7rQ6ezKUbTtm>uu3nq{9krQ(R@P z$b3^PT(RKmC)zOu&KKvbxxBdoYSy(sKiGX;P>q6^AfyzsjtPdzFvT%i2l>Mgq?3(* zIJXI_Uat8UJy`a#vY|n@^3% z)U*19{X%(?=cy80eTTCK&KBayRWTc>9-6rGx(NU|*?&Ej zBZ$mTfzdomoe>M=0;8`A*|#TN*Mx^OUD6Z_w;>i@ng~BcBW#^07zZYbvmytTz8{yZ zN^co1wguFyC)2(&nlH{o+CTI5Ya1wz2;n)@Ao4BF^1KYT7Dfy#PM@&*q};!PMtd{P z*qC$|f6?nXBdd<~@v`<6KYX4XrYZM@jpyfjKISR+8L1#?+!Uz>A85gT<=oH6YwiU- zh_}EaJw1|l97F7uSQ|V`*-d2pHQIQJV-t0+VuG<$aP8)Zy)en-PfA!86Lzy>??LR;5XbB-MUk`yKGztxgXPUo#YI3j$-J zRQgm}@ukWa!_;T%31OBLQcY`sW-_-X?Oh~B_49aQg7!8pE1CRt>>*#P5I4+#wl`;Y zyXO55mW(|$JIDgannM30&L>I7lAq1X$?bo)`?NWb!O-7PV#~Dp3oKSvre{f&<`m(! z;UXV$!$kNS1JB$E<}SZUHDXz}9Fr7kQpNNsrUW3knZD$T;6GVUWb##L2`gW|C%x68 zybw{;aL&sKo8FF1ATDWF{N&GdtC}HN+u2>z`wlVaGo9&s+e=nsvrRPwcXfgQE5_ex zPVZ~-A|tXv+xauWXPoFuY{R*m!Dm^2HaM5Mea8n6IS-Iuf)rM+OJ;(-OnV(jcfcBY zMMSD=^)!Xct<3S-k08o~Y-*#}AIuwwB9uv0zyIx5bgLVbv*};^MGf}9-|TVx<18$w zYTB$ZVtQpaeD63RSQoQlm@Y?1&{p$S05BpL8*6;J;drdVWIZR+(0(*^GI z6nTFF3V#V}!}3uGxb?kFF@Y9#TKQg4$Vo6T6obcAGDmD_D98^rc`mtWHzpI!kXI@|ghSrW7Dm?qAU;$b$5s6_M=G$dqSy^onlO znHU{)kb3#GIsX^D8D z*U-!yJN71d=s!IvRQ^BE0syET1$V7 z6-bENNv37Y(5@W)==I2Q2hW3XT>!hJMT2;{j<3{m2}2WFg;UXO9PLRB1EsEk3~|71yhQ z$T7uYxH_M@Mw8~j^w$|h*3++nAa4RbAG098-B*WMvGw$-WI}ZA(u~ZPfm&fq>zW!> zp!3URJ!9EXW4pt6-xpnp+t2pfK8-(uAM}pv$%F2-jBXl2ty>kqkc4v z2D@v{xUW{iT|wzKf5#j`_fg-H2Xim^QDF$^BNq3<>>my9&i?K#v}(qSW;v_(A*{pr zbOS%|yS$HOIgqJ`#Ne{1wRF+d<$j=voCY)>+Mm*`#XjTMtU4aU>-SNstuz`|zZfAW zi&eKghJrq27aUKr^2v4uwT4Wti}&-}q^MxNeHz!U|6t*~(n-GRjRj}x-??QX+?~F^ zu`0xEAL-tn`dD|9F!2ig0UNhR9y`WrNcTsKddTc@g10mDpg@jZUt{^HbR7gL!nK)+b7_|>CXSFvc2;D%3)b>|(CD2EC5po%B!fxEMOs)ViO zT23k?Inmx@=B!bAaXuoV-(KuAkZvRwtLgpY8m&wj334GQVsa=pg^-NBM6sduYTuTUkwnZWG1Q^X zs@9l~YQ?HLnC|0RpLspb(iv#5!&!B$-ZcRNYenj8MG=R+a*y-#;dzZo&F*&`c2@V5 z@@e?!rWXtkc^mSkZeL^f>aZNpLF5C!p7i7qcRhZ~D@Bbah`V9CoRSh1#dK6ZtTVqb z!+$=qYP|raUPoQXW%H`87mtd2uwiaovTAWp7a2}#pDC|JC*E{9y)|?)9ysul` zHFR4`^gL5~GCuMx$*tPA61Yg&xPvBzeT%E3w2IReDmP1G#V3N{pYX}aTeatO7PAn4 zYX{){rVABum~NKLK^uDaX-}QL_tX)E%$yb}DIctBY+1M@Xe8o--N@a(s{UC?6t(A6`EjGveuF}F7O)!lA?3X31t(nC`CL&ik~nYcU{`-^ z?^(Bm4Cy4ckeHj8-T>Z4pil_Dk$b1=5v%$z+~rNF4V{@voD3P=Ff_0;htw}r?I@e{ ze)vHHq?HLgcrNUv@Vt?vBvfQ;2MS&RJ@-z83OV>(>sW{1s!I>|QP)!qectXBa{@9N z7PcIiMAZU3Ig3k;$MIaeo%yU9O=e{FT4TkI&VuQUyui_`5W&Y zw8kb8C85qWK_}v#7=QmXScF+tLSMv>HxQEre7j}XvM3DSguGZ~Uq*;6h*gYof0rR4 zS`Jwgd+j!&-B4cf!DKDoki##%yw-{qV+*08>`~aq(GO~Dh=`_<6{~bEtp)r|EF=qd z+f0gCl(u;%s#Jh=T8EPuAR%Hdi`ap8)#7+mGo&);(zHOff=k!u2G#q-94=+GGuS@} zs=s+Ci{LBb=63cRI=tXlFQjNAG(rnerSVKhlcor`xe<&bQw*7r1MU0w6#Uwth<@ia z*J;ELM4kkxKR|cT(3+GcQSQk5fIY-3yg=jnb%yjr=#Qu+NksfRas}eoAU?ry40U7M z0Vn0d7@A*^YRH&K1)xHJ0n?n2CzNVY{YcjxgEqfjLs0w1m{}Agivo5weuHgS-}H%h zw3%Y{5BV^}vwC}X(=m^lnBGz7yz%MnO1DF-}v4pDiK7A{2~mfzbnf^V8tc+zD=#&MiI z_q%rd3O|)=`?g*3IDbR)SndjvwC^1HHGUalqhdt0PoO{oV}YZle-GX-RBwajL{ov` z;Z_YSpJSdFWevdH%e(>(p@1+k8!iAs3X>bnzamh9nzOzsNW?*vbH)Oshyr3*#^uH9 zASdoyGcYPux4P4-L>K)0Di69jAo1BHf4Ytz9D&R@vl;>Fir z`l-9`_ZGlhe4HGWDOWC!?;Y24STQM&4L^#2#mX~rbg|X@nP0RtXe{)c!rhM-)x16d z^V)ha;*x+8o~r*Wgy(5Fsvx)+Rk&1 zgTD(jv_WKy36d{P!Ye}@ZmX62L`HQhWO24ty=5LCZu$;(m9Kh}8w4FW_gDZ+HKb}O zzh?U7d;OEB@R?5o>U=Fm+oG`j>zeH%tdXdGBpo<;mW=22B_%E;(ju%>M}wtnmBIjf zYTpvO&J#3N+5~x2QkWPkjg83d_$ywXRPI~+Q>NWw{5L~V#NJ-5dL}Ug29;kaX%*jm z2|>L@AI~5CK^YX1Fs)%${v}dxMD&ZEqjl;AzZ~ngd5OVC&w$-R%`d+jKu^fDO5b-S zH^kMW1XXQX-!~;Hva*G9M^)nC2EkdkZIyUpaH5+sALw<3jxvLR!d^JcPt#v4xgX57 zZx*|$Y`2;0?fuAkb;J$MJkqr|bN+D}^St6L)hPr9B)hx(^PFAWIFNIrNwM}=w7p|!-%A#0NG-$z|s=E?4p zA&P;3v6BiZR`AD(vESpO%>EgraoaANntqJ-B`*kB3?UEiJ>M_UV7gU5#^%0y#{otc zDLJD9+F6-ZnG z0;oZmbmj2zeJAuK2T6ZAaMO34x-!e0gKI37AQL*7F9FQt6}%lGJqwa7sbj(2DI`gd za>M7D6{%9DWvZ;22J3`23AfRCtQh6DhAZqAyxY~lTS6rp_RDMBwYo9A=5^?!X>(nbc z>d?s>Ix1vP5OlSEAk_F~M!=NaDuKZk{N7(wztRUpLMTP-4pvp*Fr)gu%F;?)7>pZK zOydM+&(2MG5_|XXrZqDnM1ZuE%!U?<>5gqX3DDwK?B7q+R2$9?^bQ3yA6vp@;(oYM z(quX(F8Yd*QswdzEBdoBs3;m2&SIVt=?idGYkG2cH|*hbDi9;Ei5+tspy@p9vH6E{ zJfS0qr*4Q#326Ba8vDeU@$$FyVR2nbCAyqHa& zp_rMXTBVeg=4;DJ&YFW_=M*MLN_lV;oyi`Hcuz@MuG3Ck>dCkdR9Goy`9vbwa4hn94z@&zv#!93QV0}j_Oyrx4T zM+&3WM!(D%QucNpsCV|9elkaOG>*G^<3Ww=@oR$bseFhM_ZTanD~jz5s|}QDzBxO?nJ}4aAF@zkim8s=Ob`6ki%fpF(_&-dKCA?91k@7 z&lFDJ>FkokS;euVSwdY!6{H49mgJ3EXuOvS{jz6jbnn87>@iJT>JaB8&2V#r`6bc| z^W-*M;^6l6XmqzvD1$hOgWiA6>9t%dH({f|lS*LC^$#2AXLVH| z>q3!M;*D0KrD0+SEO45%JRyQ$al8}qQO-p&?-U4kfsw-mTv~t|)$LYKocdAfYoQj~2ZEfL!s^I%nY#YWc2F^1Bz4yHY#bMO)fDZ&dMO(xv)M^l< zI%oswt38=I5Kb9b-Ck!fe<){=RE7Eg@nP%ViDOH%^j#DA54r76+(km40Yf7~Y;B6N2L;WHFkC z;kBL4=0QQZm*&6JR<_V|DPGpFF!Z<3zFUtkrnQ1^U+=JVN6B-fd3(Ui(>lau7i&B~ z>Uo0HJI9vyR@4g3ANacc)kLnL11(O9QOXq@6)axp;HoF8UKr4?v)}EN^k$G>s>waq zORVxN?~8`CH4PVV=S%nsx(vOWp4PS#Fq_EC8P3G+GOUI>DsW6@q@l_Jwc2Bba_;m? zyN@pI7`7))b^k`f|Mw_YmEfc)FEjw~oAbY~ET(@d>q7JVAEV;?uTddj>ZL-V79c3B zHv(pZgx_=y`vhdSqa+o~WJ#{c8}<=o)7M0xPN zT*WQhS!MxZ612tfI2C{GTd)TE&Yvd6In!8P(+Ne=@z+ahdfHK(NvVp;Ug~)#?n!T~ z(r)L+7L&v0<(hBII(HkjF?=9f`*QwjisF^SVSUtG&OTYwR%(W=SFAsKN*(m^1t5BF zV>{cox|jl;|7`#AjAKxD>m)@=u?IdB?{BK4o~f}oQl}HqlY*3)2jy?MHF%#Sg&KoQ)Eo-FenC&8p09?5-+>Qt*XJKH@QQ)~ zKW{2BxM(16W*t|h<_)TJEvD+ZzC)btyG>{?LMh=Wl`2T9vvtz5>#!N~ z>f_ad75=`=7q=XDyUKOCIO#bjtjN&K zKe+%ubF4}SA>yssMht(FEi6mCsgqEu0iYH>x4oVLz509L+GnJU9o|hBdWVCMmS14y zXB=nnU>8{G4DNhPf*)LG(P3(sm|F%h!-GYT@eJ6Q1y@$hTbtk27)JgzTjGO>sAL>a zvSTc4#nH<-xMI`%BfJ*CWBe_0U=}zDbX(c}djQ5~0>?rJ_OKUM!W^O=%*nvyR5?+_ z3Usg+)~z4Y01ZtjaY56yZw??5wu3G10BQOxb3d>$%v*nBAq2Fz=CBu54XE0|fJRxY20yCL|N4{)oPAp}I39w}a47%(9SG&-*Id?A0$Bwo+lZ$3) zA`*x&@4Z7Zy;kQF<|i~`7da!#`MLENdGC~5QLY^ue>JNV|1k3@2LLG#DM^Y@*sWf* zZmB;CKPsX`5}eB#KJ5n>`VKdRj z9E#tyUFRr(CH`MaY!niNl(3Ta73pI7Y@Q-Y9oz)XhHI5IXQgGEp=!Grsv}C7P)!+* zBbgJ1M<^FKCD9R8nRRqT`bqIhUF4aJ8!QMwWz8~N&;^KFBZfNFh-QpA`Y5i`uSXaN zFX{UKq7jilodO zXQ|;{qfoWZ(hR<1+dmVS+wBj}FRM))b-1iHcv!TuHZ#fA4*5Hp!o3 zf{0GaAku%@=+pQ^!9HFKsoj4OzT(0dllija^u~>v+WsSZ<0K^&;zSGT+60dbJq@rh z$NhTk-!;whrI6gwEm)&u!z@*7vZW4>;65FHA)wVtmr6Wds zg!Cnr!Cd9Pfwn7nntw#w9G(sYp&HvR@V?@VV(@*u9 z7|%VF9}*)=D<(hs2a~@F%43gv=60jG!mZxCp;Ck=v&u~__5)Q0o z(aAK(s+;T^bjOn7fv{1>D`_=r;6rqdJLO1h3jU4uk#8X-aN8N0?0?gN+g#3KjXQ3n zi~gt1-dm-c(8Y<8k{KIp=p7MyrkpG~#I%i2MhaTIBmHZFtjAxrV%**-h$*cdSVzRQe=pu`Gv$Ja)5`$W zuKQFfd(x4x`hOazr4}W?>M^r5O@HZ!PG^j!LdP@g7w$F%yW3LuLF^FK6MsMiik*p8 zw|yr-w?FXfb~#8P1s_qEFd&OEXRTMAYgI(WnQu|KU83eh8T> zX0ZhutVRX1Taep)0F=ngY6B-xLi7NpHzz=#KMy*_!M59WQwf-{AnZZq`g2JBTqEEs zYBXuAbjnjnT%~h3i%CpLH<)V?+jXlptXgxa+i-WS{Dihhtrp`0P`BCo5vcxMs3^^bA0{lA! zgGCUflScZVMh&;DuP09+Hp7uCn1@3r3?bU;qg0cr7Wzc{~JkTA9IPwcnLB`wA&^ zMj5-SOw=wTzr|>n#@B`@?GN8^rx@+^d&;hS>|xEE$f6s_i!NEjihD2z8S9!3qd{}W z#S$+Z{^(M5%boe3d!sIx`5b(DPZ{lbpSE6hOv}Ovi5k+fsZz1kZh+sAel=?U{0q=k0VANG-QcWWX>Qk zCF`|d@gUpLv~*%lzVEuJfhSygTt@hhPfcB*r7ejk!~A?{l_AxaO9?Ope&43(URc zsgGA>!4JDLHQKY#U>i^v0_|m3x(!!U{MdJ zQ7ciVm>zKbZ@IQZp+y(g1@QW92=mBAlvG^#uSr^acwTzcb>oh`t*MZL(x(V?>0T74 zmXKbp}7d^o*mHo5UCLE7sqdg7r+!Qy6FwY zSA#)w`{M)5etJ*;i)1^!7Molsie%p#%zh(r!MWE55K>D6(KHU-EvKtP3AqQ+cirym ze;-{(5eL$b|A5idpTRcK|I1VS|I*_B13Le=av*Lh5`-Df|E9lNWXvZM8q}7tT!9$?b^tNYtFg??(UG4HeZy3X({75{E`AD#bq3=*h!LnmBs>_S<9`7bg$il zL;Z^-Pm5{Efk`1|0B7+vXXqmqzmqm%q1ZANWV;iOXtr5HSaG>jCD>p>V#$Ab21W4T z_e7|F&Cyln(S{y3!}c2ge}&%vXLb&53Jm4zGe?K)>*+xT%jd7YF>8in|)`2ZZhCE8anmtNp} zT?VE_PETrjLEuWZ$uWg6Q3L$huX55S#EnQ_dciw!EXeDwhEn3S!~pK?=^^y96AGxz zRA>xWS(MoG9$N-?RxR6*YH#fC6#x6Lpn2RWmGV>5$07aC)fe0UT6mGVjZ=mc+Ly1{ zwO?KvD>yHN*n#wVT8yH~F^p#b)_a+V1AwBJ1y(Zi>n&$XOoyaytSTM4-s`C|_ay7_ z{2`Vqi2zv=6z|zswrT<;(x($Ksi4|Z|8EURkY?Ic-`cTFPV6WL!jYq$1vG_ zy~>brVgr`pH!(z zdJV^1lsrSNdNz2&Lt}a3N;VS20;`^Alj9n(c z)!LTY)dz-*@)^zx67m9RCehbyX}!r?EOco&2_@C4H7i9!wdIwocu$a<;|y}8e^td=4u3@OA|TG zV645_(voM(nzf78mfU-R&s>*zbGnrF*$L(Q9fjy7O8g!b9121F+ryD|WUF-{+e?H@ zC(Rz%Z-PqXphR4f`@P2Rk*I9ii3k5bG{*3FFFt7ULzn5>A$iHy*&J3iGY>$0!?4Wr zg!ztPJN>_~UYSm}!6)G=~UqgMQdHf0MkzWISrRnuW(!QddU6t&0- zn)v#`Z1$6-JF%ERq?&hCrI;zUX@Hjgt-fOv0IJg!R(31AFcJ zgJ$u?^D|uSkPX#HG>S_cSBFV}%Am-o#{neIK_MD~%8~{?q>7{P4;O5O?$Y~-^n0Rv z7Fwu$j1>g^6|9+{6=1x0sr20UKoR32dPjmiMjUJu0TKgLdoPlyR=sXBS-JI{;T)Mp ze@~DP#-FI?m8aRxvL*eh7bBSg99B9#$PLi7C~Vsh~q~==X1^ zqzm_{BIfv1=|wGuFHHXVbj;e%*qk&~hQME*1OSz1b(amOoVK>x%++LLs4Qd44q!<$ zoeYTWep0+UtKvb)7Yl9zV|*kio+DK;QKYbxA93jceYA;p!rvv(+ZUJG(Rn%Q#4+_9 znhC;j*q`|$`%i`A4N14bH}_6M9_a2K_x@|W*qEw*X+z7nfCe@SCQXW`e3ejyU6A25 zZv%ybU5GomK-<*tg!zTOJJLUm;m3HeH>j)BJZ*0b#lUB+#MsWiHW)iPq%ALNe`>pm zVarGk>L?(BaqN*%8-@TwQfk1998HQW{-VW#*P|ixAU~M2lXrgslXy3QLn}pDXudDYenKOm7dw8pp=D)iVgi}&g7XXJ6 zz`y6IOZ!!6{|WowT4}_T>R&!TX0yc1|MOwa@xNPXTFM*0(R^=YzJt!ERk&P?*Yv}c zC5Bhin10L+M0U#x!`YWbmo3TCgFoJKx+FW+la0bf&J=X98Y`UMr*kq>wp#R#^IiTV zu=UR6Y&mLg2*=0P1f81B=o&Ai)>vO$W#;;=^WV+Gk^A78P>n0W>i(JM_ewFjyD(*a zG&8?0p60tn&Dys(esSL(T(H5jvplCibG^EJ z$PlXIJk}f&1Qp%Tfs|vtzRUzQuwMiHmT=_PwRTm=)cD)$>7A&(u?p6(gyDV7_Qv|E zbql|v?6O_S&1ECI>RPpe_T~*q+l;llij=Waq;HDOi1z-$=mST@1;tqJx;8Hv=FWI3C%f@s^P13@_83-#U_ zI0#pAgZMi!Xksj^a4u9hj%SDq0W|1nC!Z;2m+O`~|L08e`j~V2So=uTYvJL=AA0h^ z+ac%nf7M$K)oU3=u9X`^u6yH(a1hp6tE(hv#qwcpYQ@y!6)j}Gk7z)B=7l_gSP>Y= z9n$w*K3k*?r{dIO$XPx~Foiie%c;5<*#$Ips({EeY8d-}) z!W^yE(asX33P}8ShA$Ub^ZTH=^kRFWm3s*`$=HgL2dWd7R5ASg*%|a&y=1{6ax$=8 zu0muCA?9q2AIBC6(xtb`WP;s1+*1-oJaAwUxF4+|v^zIkZ<`^{W)v(OaVhzrW3mu@ zD?@cU&dmoW#O;k&9J%a# zm%e>5;q|gGlZZ#=mSlM)bPr$G_)`N3=P=EklhkgSiUtf*BealM#XTvnlWkb?iPG>s z{zQrbbWt*|w0_@io9_$sN!>V+y$?gywMe4WLi$qD7fdR>MUi*l&nb@13J$w)(chOu zh=~_{mQ60vHSCOgC+z|?yC^wIbZM9~Kj?WS#Zuw&mwrV5B#KxX8Ok(aOfBbBnDTDZ z-|RJH%ivaWv;J0fPn`irV+Am3ku;ZMx1Hy$DXQ?Rjs%Cn)!>>Dy4V^XXKSF+Kk#hL z2ZmlG#a0Ee%3&?a#y4ph-1aBj_9uLgon68s+mRsNWd1~0Bu*2}Lep57aW|x>(%(3f za!F}J!N^WTid@vv<;}G!BTebToVz9R&&F(n0|Qjq>qWG|jk~u(&3CskDM0EeAqz~) z<6fY^_@4`CxIx82UO1U@4U(P7v~fx4Gu>kX2jlVXu67no4dQ)S zcc?QPc!6)Wr*QoCEWSn(@${G=KNXE|7H#L_*RuE+=={52j}F;}a)>7RuIsEG6;-_E z&!$$$&)|)LVp!WIUFKo}U&|hf2ol#eL|aMBz=7~ zmRPVMegsKCLBwhpca9as?JorJ{d5;+$pT;I4s<=`ihCewROy~2gg{Y+cn~%|6N{hl zA#uec3%mF|5i+F&QPIeIw)WUs_TbptKeNhV1FWA1ySU#2b!Vvd|}+2QvrHgDT&M+P~{{rr75urTGXMpaWgT+%6sA zMKgqTPZ~M&#sqa7AmI$DE>NQ35Rh{U>Dn6D=SgL*Z|-!pUbY?G$(G~E?-M$Y;dNM@I% zQHlPMB0jf-ectqIT0zospKf->S_N&p0vAk)5_Pk_$hiEkd0syyUSyeP1S4H>$vZlY zienS>A(MTg87n`9BSFMo40;dT5CvO51|7rV-V=ElL1TvI@KTa^I-T_SnVL0Z4Rh(N zLS|B2O?_;R=43BSq^bT8jT)dCr6N>4xfFu!a!Sym0&wN%P!hZSxvCS*z%MQ(w$0F5BjR9?UKRx>8gdy}C6=Pd zkRqoIPoZyX0Vr_2HTs?_;UTXIcZCV04+|s%NHvS^v`3ZRrcDJ4EdHmHBs3vzF>Hm9 z2;kXypu|QY7Ib7p*oma!i5;f$eqZv!a|_B9KoThZ$vm4$UNhs9_8kA@Uon@tqUY}X zbEI#^S(WdZy(z)}+Jlg8Z`hUmkr0$>{dY0`f2!_F?G48bE)<`g@=wUAOVF#S;QkP> zF_lAV%I+vDo7fRmly{R7tn}ulcri@!lX|@#NFZ_$5^BwEvUIxSFm<$9Ae`PlgTfBI zueVpv#n&|BL<62{?nQDrN^HdWhrO5jlTA6soG`hQmFS-Dt0P74^iH{v1!KN!X9Wws zGj6qov#CF}ZY-@*)dvw?{CLJ^WL;_PLI2t_b+zFjC7%zF3Ob?`mb+rYjKo)b;*%{) zILELY8Rsu~a^yDIIwr-ei-R_-*kFl8og0kN-7Z^$T_TKxU)>R(8QAmbpNox{$(|(jgd?7Z4l(^xcH`#A*W8yAN4QInPJ=MQfUH?X9mgJgt!G%@x7qrB?p&sS`2Ow5 z-Ft6eOWsM?J6cjf9PsYWMToi+8$?Bp2;L3A3>9uEe!G|7e>?K@bXMm*O|Uhn+dO`8 zOe!_aRbD}qK>7ts65h!KqtZ0>bxh3a_4S9FreQ35?v^4qd}yS>7pq-Rj$+`O0`jcQ zHaiW_INr!2R;+#?zlb|&z`e_{u#~7yX2P6m8{*Tyi@PE9@Ak@bizvFGCDcb z53o8^lEt(GpbCbx{^XH$XVN+zn5gxYKvx3w@aTgdOD!EM&>**Bt3QSk(e>Iwr7zL% zCSGGZS@e?bP56w~LRayt6Hz#jej+D<<;WM#F6KiAGr(TPYRvxrE&m5DVg~eBJbpcH zYV=fzK$8$q15HC;>&dt3mGMcjQXU{PD4d&E@gV>7q^;@wPCETw^<20@>aW^uWgM~- z+l=_WQS#~L6=s#<-FB}Q$N1;Q^zIdD$~yMoxlpvQQlKwN@zVM_*IJ8S@@T8U61dv# zz`9gD3J13bQB}k0z)F9~fyFYA7Bp5GD?tRUh%GOv?fIH2B(<)ZPRt+zJQddGPD+Um z|Du~s>h6X_40_pzx)xAy03rA2YetJ3m=NUbw$uQ#2u@ldvXy*B=ft0XS}EQ}==dai zT3G^gcQLzm8>qb_(134Ala3+VL$7t5(%a2tv>ByhjuL5hdaap*! zg&*Ba0Ovvs3$zdR9hDLNdxHpy+HCOIU36em`&N{W6ONPwOomb=1BKK^%a%j-BSgd2 zLk=Ftv_V@A{Eq8Rj7nILrDZDXh#`5oelz9B7q`#`{pZDxKyV47kEUB>Z5x|(iQ!Ww z?C$^#;7j(6=`~Gjs(OGXx|XK3oJ#MW#dYf=on7S(YrU;~47LlrL8BK5I`)nI@(u(y zHHyY=+M3fFY4eEi52oATTXSO^?@Z{b8)O1xcmD9+XZA5~8ev>8FzscdBqt9Tn!j%% zsO$Gx%P5*SU}&~b_W8X%QUV<+X=7&Km;t+ZH(Y~-IVKa<*+@~)ac1@x!Az`Ii(6Cd z+Ba>#!2S7>X7+!VAgHM|ufLt z3T)i3rOZ5K-ONGeuQ9=*n&WR*Pa5qZ;5eMgPUsUoe$E;f%5FFM?+}4RgOf(@Vs#`K zsJ`8RYz>6J<~%{Uv*1)@^h*+BeJnS=zQmi;x&2!G2!|%D#+?mW^qqMf?rxOc0*7m$ zbHO~BA<}YcxGZR4*J<3gB&ktGps)E4Cn2~?5`g2FVR0N9YUK?V7nF;H%XdC0K>u9|1{D~_riU3Sf} z@KO%}xxt6~XnFUbh>&sGf^PBVp_ja`1QIdQ-oZs;$c5dbF3-{2*GdQFLk`IGlsk%8 z1<$+b2JyMvBlN7MW0El(u`4kM?^cv*k}P7A6Y}9bco%VhBfQ3a%e;Mum#f^t8<|N* zi4W90!%s+oL-y3EzZKWb&s?NydX$i~*h~4-^gv@TYJE+7r#6vt40l(;)gT6rRXZ#D zYCs|Ups?KoM1XT7DPZkho1)gNuSU4QqV(B#i>`Sa31_Uqs#a*f~A2eGK}@ zK0uLgOb1xN8>&I~lO;LbxZyfcBI1XE=K4*WLyn3vTl?F8XtFLrFt8r9qsVD+R*YVn z3oK!GoO!?p`QgFXzz@4@@H}WwxDA&qj2z)9ef1L$CP|qM*6uXp>34Z_FUG7FgV_s* z#RZxLR;Nu(q$d#ua?wzaAKA|gTswzUiXo(k6z#FtI}qN<8_+3wh;~V>!7SqZl~gK7&cDRnoUB_Rz~RZnP2Nh0aLwiA|5ie@$2S z5s=}Y|DIU;V2_LzE@PW3>t&qj(fG}ZdSFWC+Tytr%Ex_3n6lC;;Q|LeuBjX=Iu2Y# z*U%tmwj(=6^-+Qn^yBH;uPe1Gv;*1h2TDnL@Q^2ev^UwU5k-6Tp1>9_J%{YO4&!G? z>zV6e&fh2?DJe@i44Uw~JZv3*^|(IoSW72*3gYVa2WgoSWPZLf5cqJ7qrAA0((4*V zkMHJ=!a!W`Wtqn(hl|*(!yf?GpJX-hIYEGCCaMnhuV|$|A23R~#%cG+*QRYBm(`ip zoDY>Q*}duR&n#qr-ECiAKRMWXJ^3nOd&s#VWf`6UVVq^}oq%zV+<#au?`?ncWi$4z zQ_qJ)MNBHwAqSs>2l$qZoou)EB$h!nI0p|g6xQq0B`khWWy6{DGaA7jZpu_4ia0$^ zVTZ`oVLy}>WgNM1(B`Y^`;1^JcVU5g1Z|WWqG_2~0rQj(USXEX<~p8cOWO>+pi)DA7&>BX;3u_dy2g^uZx9o|BKT> zhR`QtF1&@xgss8T=62iKB0;v=pd8H&h2`zj&qs(5S21L>a-P_c{in;}I_}NOOy(l` zmo?Z*G#*Zb;dhGL8X8>Erqu6-mn?4%+C;ZdSXE-5)iP~oesQdcjo{2tL@MNP-2D98 zE{Up{E)l0+Q$qG%)g+j%U`Bl8;j5vTTqow(7qiu-mAqchhC_48g`7ig({pyOp@~Z~ zG!+xR>9j22=AYAy%L?3Dgjpxn?-|8oz2=*PH2a5Bd!-3EDQ}{etrdtyQoBOJ>3GNejBAnn9CoBhcyZkx2_I z5uOw5oGHRXaX#Pi@AFIJv!?q$y>%ozTDO2{sTsvin2~O8$KXp+esN)gjMQY)Iu*>t z-W7QlV*JlSy{+tMKTxUBB_S*hoMG6~<@T@0 zIAKd;60n-8gk0xcbA1u1*C^<c?Y3h^+-fwd6rVZp z$qMynFOJu!ItU=QtY^ooYrM7^A7@2QF-Vh|ASCTp>CU^yX`324oWomJGz27u3yCJ| z#*xG|o_+mIk%LE7bDk2Jd3f8ewxVSk)e1X`GOsyr?wym45iK6{Z$3EMq{WYVqTR$> z>rD$Et`LeRb2Fl!y9_)9zLrNAJJ-0bAKx47vj1JUzg_9y$gbaT$~|WidJgNH2JVQ|%|TywP4&B$O2H^(Y89aJwxi>=B?Z9hKJ zo)Yv@JJ3>2hD?g!ikV|W1Qex}d47#(n3;)lzSf)jJ_}xkeEDj4_Y6MkbkOz`cV%wW zMMzxk?3itxJRMjz77_$#C4OYuv+N>v-r79UPzuGhP5U{6+%y{cQ(SuBZw zr_2y}Xk3N&5-*3PU3sa@uufY(iPBntwQ~K@?SYm zu_~N$b@&vht_*)+pmbSQ-z>i_zO1|)^A|8Iw=JnC2~8vv=99^J=I!H2=3X-OdyUlt zv&hnGmCwBI`^`W@A^yWoY}k#PuV=Qi;LhRN=k2-d^2~j%tDb_{_IK-zi(qD^=FThS z7}t#tdwki}X=Rcwa)oqLP0hl!dt>`9bDWU|_12<8O3A~D<&-~z5`I)02w}n<*Hi$L zdVy)q%p50Ch;E17f^}TXgWc3{2khs{+B)Bq^X<7pmZ@i+X&(iZeMa_a~S2GI{Bs{ z5OqH<=Pz>a3cS&vu9RQ$xN5*66ZYtF6=BVyO7Ok7`{nhFIHxMkQIJ5NZq?-YYWfh_h#8w{BA$3ItrZM4aNF-0+BgbT~T$VBH1a~d`{*`_IMVzF;jIO?Y4|}pG@tJ#l*gA_r z)!TW&9b6gOIUWNbPBn&&mH2A=U)Cg?_QXNx5(x3d?6`+{K%usD^l4PGv zMPWaeirr{w&(|x`1zNquqKA=34`hbDZaZm+JsU-QR>1Th_% zfm^S>Wo7R;V>rP-yr6FFB2~q%VN%By!)0EA1`$XBW;SkURS3|aBM1ZW!g=Pt(5Pew zecRj9xI7fldWtIb6Pj#T1rf>_Hyk)>ZD;;7RL`s>I&N4DMv5RmI1bkIq|-&6_6AE=RKf%Y{JHlP+2%BDCkzO|`9sp^N1MsjflMYf^y`PJ9n8viV% zv{z6KPRzC=4>c;-v0{y?P=`_bb zy2Ji4H@UTIPnIh-v_aotkrFX^H~y_pxzP2Y(R-D4=>VGvAUC5=3|nY*NPWK$0DkcN z-K$I$6kS~CHAoyfQv!W)2TY1jgOeIeHSeT}Op8jTXm1gJ}G$f&u^P8`&X=*9LB_+_GFo66aa zE*zFi6l9kSRAhS=?{On?-U4B>dD~xN;hLh<)UeI|I0P_*Ps>mp!ZeKNURZ-R7i$*i z&*G4v3qvyjS_;^DrHIkPD7og%xO#77l`A3|sGm|L3YLz$=rrX=SjV2!Wz3c`gpZQqIO$#jDGQ`^91yq@o8AC z1V{af{NhFA!}F*OM=1Y$DFYQc_BczWUne3} z8J+vdMZc*%$<)7dzbKU=Tfq?;ohf#&n5FWT&>C9p*Dn{N$RXrBZ48^_jXx#(G$?_! zdV?~dqnRUIiv~jPkhrER!As|0niGEG@|4DIPmUZdi^erK4(KHw?B=#dOIq739oy1v zDMS;A#F+I*4JLKM_Hh!trsSl=c<(WS`WZt7z*sQ46X36`p~&GpXVgyoA?o{j6HPBB z!5bQpZ^&lpzdxxU$GDx{fIaI6Xc>h&_!dfIS6{Q9pNry{ib;`X2M zx#9l+2mix^y3EqC+u%S8y@9+G#M%l;a7mVoe52Wiv)FG0PoR_SdrTW=&)NrBUl z-1vOMPpFrD6RE#wy#hJ^+aye&RP=H`w?~Zl^}!;8gGfg>qOo3I8(j$@-J!uK2T6a? zecA(6Ih-5T^W|ud4ZrG;fk+mi6FyU; zhtN&qff!;zHjv2zp^&S|csun~_}Y3yNUlj<@V? zj1jxs0a^Ozc`f76zm>f{X6b}sv5EGm1>B0eZWH2-k$@YLU?>*}A!saf4X>J2ASFJ# zlCI28inG93Df)Z1 z2yqj^$(@`<5sNokj+k$g6Ak&4m_@q!A!98%=Q2Z)qQvHit55-Au#T9EzW3A8C->-! zs=H}ws~N!4pHjm*stqhvQLz>eEfi7lOJzlYQvpW6Rj(!kmEPGvg+-e(4It;RyTX!#lyI$Y6&0peSUAk7kTZ7|p@0W6ENqI${PlYo&St_SZ zS&_E?g$p2@^cNGE5Kg!%eH^6*tKmD9JziKVThS`yD?m3mU7v(EDK#u!UI!1tk_P~3 zvwxAAp@9C|SlNO_sQLhv6K+N2H!g30YZZBNhB|-F<&|mYof|-rqNr@+=GtjH(zF&2*(o5)z%Avrpr(QPn%NcUSMbv3b<-HKnnNX zO49+O(KZ6zK{|1wt$h}pRugxkeNoe4rH%w{qJ6S4x#EC$@;rN3k^nRw)QNMbi@Y56 zwnfT?^RI@XvivOFPz)~DVc0AkdZ4+vt1!0qRdS1;qnB)k&ZUxxx#}z(fU=u!7U zZK8)h`FLyU5(eCwN5s78jeu2j>tC&MMlwh}{ZwEwpuL@Ws=tI}Kld%zkTEa6#Nb>i zZApL%eiCLxI{Ey{v=uO47NGHx$HBBwe+=Y!m#CGfZ^Bd4KU)IUps1U5JXf1xvbB`a z!91aa8zh**dpa(yf0U7B8g`WBQ`i(0js0x-Bbol|$=QI(ph_?-_^0pWhs%35iuo?KI@ zQqbVgscY9MVT@Pf{mX78W<~9}HYuHRx)5z2kH)8_R<}#ajq@0=@+2IQz0+Uey#`YN zrC&7(OGY3yUv&gPfgs4yo!{%Abq=8dIh13-zPT+TcCC{}=UO7hNcl9tXT8O{3`~@8 zA(10)p3ewS2dxu?FieFWZRW$RTwaRysj0r2V4_9ruRPUGi|KC=DA0!Hj}$7d#URpm zU%su}TVwfm#~hRcH{*+#!*B4ZIb+qT>A*>$5q=&lqzDxYGJ_|EG*kK_e_?1Sa=9Bf zk0jj2Hv%|7w3NWu=oD=Yk7a80al;bxw#au*sMW{Tco=D#q9vrVZ&ZPsx2&0Lo zIgGq|MNo!vld5L11j>jKT6tp#=D8>vch8{Fq5xC1VCkN1^MJY}vj=NGqMDg#1=OL~ z^g|n~^h7o3RFiFx(1!+ejjPo%F9h~S0ubY*P=qckIP%c`idC%qHkJ8f6AQ&%h~yr_ zcV1EWfNNv~N+-mzOhTc)0(#noFu${n@~-hlUH| zp$a0lY30v)srJA1O_2-eosuw+RXQR5n8idLLw4X~ji>pg8*;H|bc9$#u6h-r*RIy^*I*p&&X75XfdK@d+3YNHQpP?2nn6A9G}lmV zWe{6yph_sbg3ZmykItNd&I=gMKwmx;>|7GmQ%}%4qH9Q_Rb1UMUMU?&0Am+~$d6kXfmtl^tt+q$fDN{>pKdli`(f@OA*EPPc#n;5>|l+%y4K$nRx&PgIiiwkowat>AXYg?&|U96$hYPK(p_AD4aw_!fIAxIxc= zKlb%55>uK7$sz2*zQ>sQE=c`v8@79@7~phQ$hjofj_Cy8jW&$|Mn*8FGJISEFfltY z#YS(C;)E&$EP1`x2?#2s)>0jR#2e4b4uvW>Ox@KiSO+>fj<(3>>)EdbjuDuN9P564Y6xJf+lC^Wh>RWZRUB9})a_ zu+yMfcRfH21cVh2{9jG*|HJyf)X{LlYiaV82Yi7ZybIAZhjlShFHlR7;R7TaN#-N} zC6qI-pvg5|ROQfNURc(3Z}i1txIuQTTs*$_ zT;1&GXsg{EyEV9RVpbe&-COc^sCRGZ>FR80tGpB1%|7~~16*Kfz4I$Ik%*V{9UzD;bs_hBh{&ds*65necalOJW=d|2hlravAL#XEJFePB8K2Pfeuy2e=~6u|v|t&KM_?uX{u3 z*HVub(|~7k#C=Og5W2gAE~;O9D~6p{s7tSBK_qLobz}#6Ci`(UT4t5SI0K|ejk%mq4w@L+$*zbG;YNbhazy@LJ2DgJ zaoU!NerH23leLjq61qcTpzI0pB;o144)`U96H0HsBH>I%MRzd7~Xc3O^@lxGav~R*d!Ubq%s1c7WGmSV3 zNp&)08%v#rBw{#=M57%H4V)t6Rh}zrns#gvw?Y3t4(kRZe8=fHSHgN!lP@ma8MO!4 zaL-xH5=B8@%H8y)7jEsXNxQOM{*G5Y+BBRxx)7(7qpDp}slLRcj^~yoc{9w4%x9|x zW!Qn2zna|@%N4n99d1^w!w*Lz=ibzWP9@qWj^inc7zfzK9vi4`www*^$I0g6oB1x+ zr}i#$-AHaQBTP&eY>kvBwE*TxcsP7hi6NkwJW|tG8`4#trD>AYz~3Dc2~+{~5}Gs> zV#lGpwawhNVHZSg8-Eig;oRCOJ>^X-Pc6~l#2waQ5fWJ?8b6A|6J(Jx&Ou~4`nuT8 z`e}|8E6UZ)G}3u^U}Emny)s;h@H*-fQbEr`#yuVv-Y#kwwmGdmzb|f%D;~#STu)&z z9=kt0dpH=&s$i<}>Hsre?*`rHaEniP{jSpEbaMS^k+h8o7pOA@ zeBnWKGV>(<5t&I4q4|UM4TVsmR4yYcF@pxxP)iEo;-R|ekj?BR^ISXfR znx=K?tCzs$w*itEq?%aNl5MPxn9+$ds)eBC4CXgemErvOzYqDf0zTn%-*vKSzeo8( zj0K!^#g;v^9up8`ywKm0Sxjki+9L4lisaZ@x$%Du7)W7vrOv6HO;|cL;lux4Xq?T{ zJLBy`leoK%A#oZk$gcA12Iq*Z0ee3cgw9{~Q9@GiP%XgrALr{2kSwI4HS|z=B2cpn zDDw5~Z1w&$7c78VASoVnP3iF_^?m*QZo=5suYq^S9H*i%`M?(^I`j2Jw@Oddt=2r3k&)H{cJAgd zYH6lWLlsR@-Bc2I6ZgAX?|f))q6@R+#LH|2(3B(Qch=92ZFf zApi`|tgJ*fy-xzhlp|)KduT#jqFNYNF%Z6PP&%_Cdd@YNQf`qJiNOlfRI?JpHrPh$ zIRyArV+5O{_2l2X``8a_p>;r?KSjz78&~~43CsLLcGF`6MbQrZrWy!s zZR_Ig0-pC^>m&jk2G`VYO;D{mL3p%{T4R)~L+{3~6Y0h_V&9HNTA8~7Bfs-?*-l&_ zs5iOebak=Dr8%|pq}RU3^7y0f36x{xP9P1Yn7K55j@&kL-qB+C3kRgaMg|I|zBvKp zy-o*usG~t}guVMITE_|1Bd>JZMg*&m>whwrex~8&R+k(^Y6_&E?3!fMqGn2Z z6GDWn1F`I(bm+%1=E$P*e{7^fKurj!_2_^~cCQ;{=J^l@Bn;eO^rAp&MX3%Pu=;p` zBN5Z#k{Kx+LNR6XdPEvzS<6VcZ^cdlVi9f#3vfFA$zIK?<=DAsTHY)}OB$r2RxOEd zg3f|+9u~_Cz;kf?6W7?^C4KeeqjF3y0QMg558%+z^GZ$ab$j&WAFy(U>?(F_W&AT}&~t6^ihVHG3{|rjwTM!E4T^&#LjPW{W?FYw%#fjXP;Iyz)X!&w;&$B1S=<=Jk|wSh&K>GZje!D>*aS zf|`HsSP>Zoe!Y@)u3%>Yal_&^?Xc+G{D21B5U|NmvqgpuByl*2K@P8B4;-w7hSj)E+vP!56Dauz3H?O^o^Fox7P zrVO|v3;Ia(5}11?gw`?HTWV%j;ZTwuPgq01QB(JWaOkK)c=&#pP?7J{M6H8TY(}|Z zg1Wc7X^(V3+t%Cwb34NW)VwZ`?H=3Yz`5)zSjXPO*bpO`0+fxrSZJbU@Fl#y^8}V} z2!(zL!@N-)x@P$YieFic_&p4_0gl3L{sQ6mfMqp9OQX`28K5qT;`c9=`scUzZ2muV zy<>1FLD#Mw+qP{x*|BZgwzI<>+qP}nwr$(a$@4x{U)5LVJ%74uW~!&=$INv1z1F&~ zL0HQg2cESqCdUG=3<8Q^&_1+MpYV%1CRjo3$A1C}^8#+g5SX> z197WNKn6TKDy$sbb>lpicJ72>PNKGi(!D#VO)s~Ls}WMZ1q5{cmUyNeDZ9=dj>WVz z8-67SKp~|-Amo1=1(b^5WLV+3aG-Kfp?hIn>N~gdI{6!db%m)=uDH%q5#rtD)W`e)5cP~{pp>CH+bN_zW^{@)kr{P~ z9B4qDV4QYI;DCtV<(75}!wI*BPsPh?PbAxy;l%@kF-T6wja>2C))ePGw024BueFyq zYR7MqQShks{FYCe-q3QnqaHYXxE9#(xgTq(jY8G?B>xxBeD_7?g76=5Q*`}5p=SP zK#BFrRs$kDQQHV!_rRD@-U|^4W458#gCmZ{eU5kM7iSv)%^Or2zBnXc3wV8#sX7r; z?D~XO5{Sh8dzDKC72!3ax~zJ7UXPOm--(DL8I{ydT+LI6wP!J0x_NY&j}-nLq#!o$ z5fR+L6L6pf6~R5Z$H+?v3%}#_+HLT|Gtt5RH->v=?Dhi$vp4RNT$}(x@lY8P%5*>g z@r>3;yDSWZSLiq_Zr^E?2NQ92^O2K@vOUI(>^s#`6#{=odj*uB%x}uwG)A!uUB2ol z=%G?w8m}l`mt(8*QM1!uQAbtH#c*z5W8-MZTW76POavevYYoSWAB73$pjkD{dO0I< zs5~FjmN3^t;03B5=#79P<3$~nGGXo*ikx52>iuohRD&`|pOUYBO^hwZfvh@8k~BUU z5`c|fxHHBg>o)C{L_}E$T!#)T;IsP3q-v2|Z;Z~1azwj8NFH{Lyr7OMl*Aw%L?U~z z7kdy@_JqoEM&!J%Tn)Sfs3M>zNn8YU0`@22;f2~rr8t`qO+_efv2_PeL@{Rvy+YB; zsc7Cn#n3C=8p%WUEpE9nS*4jrp7)*GC>#USN40 zppwL;nq)oQU&4+Vp)xco>%U7=7$9biR{u<4oecr3Jx7G=>&KCcqN0+ds*K^@L*;Mu zUe75bAW&RQQnj*lDveTNzGiI1^xPJJj&ls)1=sL!-V3C3`g_gT&lL1_mX8|2ws7Q|gB z6j&wf@gPEn|v|5q2y!B4g{fJ#TZ=2<%iS9PyU+xh=RX%5H^-}ZnuW*B>OottTEXzdZ*=_qp`bP-}b6ac0fo8Fa121GJ0TZ zC5kGY35M%mH@UXu0uj(bC}0Ef2)SX@E5qqGo_$2PDPE>0hy8enfE8ILNB=lz`SFD@ z7NfNA_Hd`OHr}rzXJO{nDzsaU)uUiOu+2*gQOA9(EDu&gh%aUMQEUKU94X>l zq;ew*ph0~hgvM=Sty;V>DMW^UrFfpf+)o%DWr&TWK#uZIuyINkDw?binc zy_bFOI2<~34aCvXhY~n$ZrR;vPXk^VRZXKl2rRXYaSxJT^lhB1t?9iN?pPa14SUj2 zWfu0qqYSW~{>^K3Ea^-Tnto6Hbu3f)FsR5u1`EXmO&>|=ise5=z^XB|syI^|G_f#+ zZG`R&mAaeIq4GM3R8tx57h$#UJH~Nd1lx5Kjxq5S6nHwdM|%%|gIZqI1#=)BCo6hG zolV!bYCOBI2x2s(v*IF_HAPJZ_ zH`}XUiG;Hp*7r4Kq<{1?{E7&E=^K2ze-T_#EvPLs%rT`cm`VR6cmXu3p6Q-DXS}^m zit&FyoZ{-UlTQq_(-}Hbj3>{+o)PD=FTpn$oO%cIGSkQyphkJ6s{fPwvF!sWl|6qo zqvlx};qB4>tFEn@!cEcGkWIh6t=drfcCVlEBiq(=I(`;3_!o3}5vrI6wGL$T5IG<( zq!pITYD++|lqxh6-61UT$t1j|@3S%s!hau=APoO1>h{b2H*5V4Jyag7kUaltk!U)K zK%kpML0@T|98UWW?RmhZKw^Ig>G;u&`wF%}Y;?`8bolz;5J~Z<0g~6rxBIV#bIY%* zr6rvvGN*6LzaM#)RO6uQJbn2>I3IJ&3kWDBQm*g!$5&5-U3|LLCB7=oTt^kpYR<;P z{!^7|6Iw>|W6mufS~vGV)-L_fPsr|wvmi`AQK?ex z1xVT zrmd;V6!lzmtI);f+}`=VHzjqaLrLu(vB)x&bYKV|w~$q(w2+q}ycX)fW-l5lFwZY3 zi?=zxeIO&)-nHyU{#4jlssLPDgO-VX)4yrTfqQe9adehE%_7s-v~_`Z&WlP(NUcDh zBYZ*EJ~dMy|A<~B(HbbxIyH_*gyeJyrgSykWxuZtd9||0J`;)r5~zX;=W20=`SV#I}(z?Nz}ipmf5|K0z|oQJWQ@sn#gTCkDOs&rM& z1+QvKdYmd9J#xio6KZ=k(rBnOfacqKA+s~Su`R~oJytNa) zMbF`;*q~cyWB#o<_!i*@#%6h(9VlVNEv!GR=%GA$Rli1JKYZKdZi+V8=%gT)flAX&_3t~ z0&c81sO`hNLN1ig*vja_+DUD4+h5pSz!v&_gO@yUD3^oB&C$l~D-hRVWVwylv0*Z6 zfRSg?6MEBjSAs5Y&FSKjpUC^EFc^H1SK874>V?m6oF!pxFS^nuc>|DLjX79VLcCdq zJPrHWTkbJ?d~vqQTMivb%tq*esJ#R_j9Z}|5(6FS!#3U7q6=BVXwCa8X;1k6bzmv! z7TbgGR}omp6&KDmOUN9Ev^VcDo>~!@K`#GxIksY%xTstsE$NU$wg6PvFPADayeZ-{&6|JR!32-X#te1&ORi}kVO3Xv(V6op#YB8Vv$}bD zQGvr2)AXJr2{V%~vQDXhBy^ty;!G05nHVK_x>qW0h70I~9C_=8Ihd{n0G+ZuKnrCb z&tBZzOlj^YQUB$x|6qxUeHqY6lQw_{2mDen^-ole?PB2YL2#gLY5okZrgf9Ra%Cmu zRcM1o7B>-8n+JfH1N{a`qgipocx0EA0u77S5Kj%UE;2d}gQ5Z_9)Up+x7U#|HM2BX zFn3uqq^;Nmf$&DLk~EB0H7#~|(baAG_~dNYh(-k+_8uP#r_s|d@esFnwR|~iQT7UD zVqCMl`Hm_=1ia4yM@uXrI^aN&ZQl{4i-fUqvEj+v#|en6s%cc*w>;$m`69feY4%RxJy=z{qCV=iKT8V6Q^1XzSkVT>in$ud|t8F-~Ec!I$~ zY*OJkJd;KFN@45YCb(cH&pP*i^~yWW_x&}unV9VC%*&-PHQoP6ozmVP|B*R;o=>5V zEgsj1Kj;2^{#UyMf1pI)%O~esqF0UDq(&C=DLK6yj>cY=$je{*d`JD}4_(=VK=HAF z(7d)7IrNXQa%V?ei7grhw0xRmQ(yQ)F zsA^;%&LrI4SxsJAWCpeKNvStIAs{I170*2m&ONXyG=DL!6E=dn8>^8hyYeSwWq}$h zY_jBCIvXZD_*`g4;86)Z(|$Q3CH>gx%TSSKCu2;(M*%!?3nqw=w{(qe(_|uYaR0^~ zu3w~?`?#?+t)Npo%KeNojckgb(Lr{O4!y5&&WE8!kH>X)`EklT>&>r@rJ2T^I7gYr zU4KtB%{duQ1hbng=*ntv-3r;KGcw#cklp5WEbBIVqZUX$(#z}?*Vm||fL$xEKjf70B3fMUM$K2%7emOI-u0Xc!Hd&~Plmwt)q~7Qf z(b+4niI@O`vC|+=+eOKEnAvq^^$hO)i^+BG=zBjidg#GzW=E!B?AP|kj&y8?o$6W~ zg%{IT>^zS^h%lN()DQ%Pr3Aa(=w@#c_@;{U%HIvXvu5h>gX>cA8caGR+m+tK9PG$m zdh`={X`A%+uQH&kp6=v|>me@RNg!c@!~-ch6J@tjP+*t-Z*gTW*8x1yD?oFBJ`JNf z_cuOZBD@nv!*OUOO++8m@$^eI1aM63J$caR7*e8hzOoAX677x70n;c5D2ViM97Qdw z`xO=c?A=lRIrv#jW|W`oz}48GxgcL2#@lGtA;|U^-XxZ51Lj+bph^&WAwV}cYsA-tG|$KuDA$fW z8jvT&_7AIXyeXAXONnY|jMhlw<${xSt9@p<;^$~KA*BbOhejW$yDV*ASBK#Arz{rL zXqIa?N4xWD(LamqV@pE!f&`cZL02a7w?@emrEVe(1C2Njkw^uD_$AqJ>?3if=*nZ> zi5F(=b6H!Jrq_C|rpDAiDkKNrjZz$Esu*2zMW__qa1#i%m#>-=wj0XAYaV#n#-Q0~ zC=ttMLe@!-q9vCjIzm8RVxr9j%ZN9pLF&EzCv-xZs-SyDhS6gU13Rq!KcSQSh%nPL zrA5|%eDTK;^eJEob8`ptW2CqmM@Nbffh{xxEW)f*hjjO-Ws9dAdwBN0$X7dbrquy4 zjdzNP^Ji5O_-DtkNgxwftePS{%4Ucrd`fUDa@U~pJ>kHFCt~wY#v?`5(`Utx!UU=P zJ_;|$CinrxLP8lt!-SGWr1MMCuHg_z`qL{?`V?;wD!n);wu+XN?^H+17UAGOR#9T=QbG)Cp(e%$f?7IQ>b@;Nw zam77Cq~Y4m03fxLCM2ilnUoVRuYkjp_|F1gv7Cq*yTcRq*UG_UCFxj6MN}YRED47r ze-MCC&=9Sdbk#2=UlA^^2R9V4wM5$83H#)Ipt?yzV_}4~WBn4tcewwF;~eYFDk#J+ zm|!44f4zoGt9O+DoVO6(z4>%Ejyy!*Z&xSdqov5uHO&Z_*naGKacaHFgmR2QQxt#rO5mY)*PEs=z;0+(!=TA^m6d*c5~HHxzLFJDH>V5Hmy0J zUp=uiWVOx6?@H$fs{5cDM}y)qs?3aFYY(GZ~EcaBD>>fd;=D!?R!E3N>`Bqj>BnK|~Rq#>(X z8cA!3k@5T~Q^>>?nAX@t!r5H>^t2u~j4y^^zy_~YL1x;cn#jYgDj+D_yjaZwwbI7U zjaE(@-wqVkmL0KKEhu&7q>G5FPBDS)ylb4C^kgs*3l6Pf9Sr1PUlzhKfwJ@>>;QMP zyL?b4(m3Pyv>BqIm`(Rglw+bUPMe>ZG1lPuv~Je>UcO@N6P*~SQ`WisUYU<$MfkP3 z#W2T?K7m>8~4yR{8Ru@a_uVNd7;VK}3UOIrL`!cO1IJ@`m5H8hB?2SOm;@ zkL^*ir~@V1j8R#^?*_5|4BVZkbInqX6op(0xlm~gW3-s4hmbnHsV7KHx6tslIDH+T0Y=qroinV&k7B($)+d1Q}s=9Z}VHW zHD}ngTKbq$nQYoOMi!5}YV?M!T8zF61EUo3CrGYcLl*g^t!WbLJsMqgaj6zrm6FHG zDoC7z0?^=?HF6(-^DSG0V${4tH}jqg!*Ud>l%XuBt)@LfyC{{KH$@));Ka zzje_SDWJ|fedW@pC=+xcsaln+Dab%U89bKBcvdn-B8()e?QO-1Q?WE6VR@b`~w`O%wxkO#Zt}w9tX- zoEzhcab=7#aQ!mV1~4$tacnxdN~;DCu1WBb2t@#A(aer z-tutp&OAx83T9;y2#VW9kh78nf|=YDgoL^W)Ce;He~1hQ_`PsYsd+>CN#f)j0;bnozW22&r=O)bZjduqI@ezM9MV_-GB)rI2 zDa=}$HanWX8PoOOr#q?{ipz#AqPkLWN#32ojbWx2C4u~D83DENMr4__7m{j z6;Rqi6YiP!wH3RxElQ=Ynj-5f8Dg9Ipy2>F!0llK$5yuUCiD8~9pwqPCC{e^+k>iE z(pe`5{bR;}VCkv7Hkc7%er7t^ok%swp9R=DHbm{Ip(#|wsbUSNhl=8N0@1{|L ziSfP0OvzP`hb;Xs(asi0y_ANhx9NEfkyIHsw26^GZsnAc`TfLyrc3Xn zyt~stNmLzA9-}TcwVhK)>@UIp(!&>?KW344F0?#*&z@y?pw^|35$<<&qZ85lQHpAs zzK1~e@3lo6gKmuMqA+lvAn)>Bwz46})6#}RBT6i2m$ua!DI4>DN=GM}iunWf z;{G_KMw7XtTqN)90UN}$y>B8thYHb*n;FH4+?65yDx* zJ#wr(+NMF*JV%&7g|f!CqQkNcZ3z2EM@2P-4zYn83aygT-T~Aa6Xv`uuTK0aYYg z(WonJ9CUW{f@SV>Dt`mUYEpb~*YD8Q4IiwDQAi;!o#r-juqTU5L@btl2wFaOVo5|Z zvp>Z7_e`S`6XCZpyGzXDfC`sO99p5=q2CHmM^yrwG?Q_Ls^<`~$CLID(M2JX1x*M+ z!bg*o?=ri~9`bbyRet>Kj@(hl0I+l;^psDeJhVO}8r;cgbz_3bcVEp5$t-H_<@*>% z7bj1%kZv%1R#i+U9Gp@JG4WA%B_9n?3R^jZFQIIg0Mw}&V=PO(6BLX2=XpV%!0+>= z4Rw}J2N*)3{4M(Tc*77`HHgzQs_~MH*mU~44`P-KeICEA5;lG_CrI*DdZt_Gqvd8| z^m2YK&d#y}>_S0(81-r@mI7GFA%%g8+Gdl)SpIZ$e>w;|-7#sIvffE{s_j$4zZy~B zH7$G}<@`Keg*4IPLj^RK09$0Paznun7=dtj1CD&Fzg8dwMN{3%r0LIWqYCV;aSv|X z8Ge6Nc};od+>~3AaC2IgNafs|zhvB$o7`wOQ=ftRhBT5-{Ih4c{%LZm|4p-6K*7I+ zl4JKqdd61-Ui4@?NDde?6W((Z*5C_V_(0X(EP8Q3mCql_8ax>RHnyYEkrkqQrV zJ_PN`-T17$ZYL$yzT@O_DM*e^L?^@DqdVZjYsHZk9_1oHydRDlvDij{IpfLotovP1 zC&jw(6YbD(6P2Js8A!I%DNxvp*j}HXTeRjoCj4r$Ry{t@LdvH8$kt8f?DJJNWmVN~Z`PzFo7(Q-uNyRy(Q)ta|v6;6_ zAvbDqtt{wTOqKb#O33LDBEIInOt>_p)~2!^5bGnp_q7_>-&Z9R9s_Eu_}<@&3Qt{eDcs>W}tUd+vh;} zt7q{eWU7iKB;w?smvzO0O9){@g0xCflvNT(j$tT+B-Sjo@%7}DX)ggK<(4BK9nq8Iyob^NkZ%}YbFCzLD|FO}EVq`gWJ zSKrD6gGf#?AUI<_nWisQHbTR^>L_7kSV`%Jt+Q~Bg;~s5eyw{KxKT;Kxl4yRQ;WiN zPyss_IwXe~1d8y`ze_TNG>-~ND;(xZ3WbA=jhYG3zXGzQ9Rf)gy83B(Ju2!`C{hFJ zo+KuoF`F55&k8C9Z()>P{81CyIl8qn^%PrJcD!LO`XE*~WwR(EI`IBA`_BKn^_)un zK0*rE*%*ByMEH!%B1i?R3d0uN%Q_JDXSQwnQ@ZV#48@zu_gOoAlZT?SmTMN|m0Dx| zclj#Oyn3hF%wFu2D$ayKiQP-p4ZS+~IB2NjQ|4<%m$`&#i&^Pr#i4>)#R0(jiT-)C zJeKNuLo3ibDV{2gYn7u&WQq5o$^$vi7A`c`7deJDn&9h6_(1Q-eG!J2hSR5vOGj+g zt8A_N=7=VRBzfOwgmLoFhkmGOpfIT)j0Im> z^U5_a#gd1aMu1)aVrjipq+#yrivXiZ*3eh-Xhn|tZRy%7i-uWY%yMg9guvQjJ#z>s&xJ$0&+9>d z=jY~XDIvA)o2`bMo+h=el_VjnT}AGC>|MZ};+eAywjWRu`oCtxwtv+aNI+%+&`DgB zeE>($s}1ktgY78ogt4YW9Hc8?0T^&1$#49j)Rh>C4Hli zno(_8{r||Vbi2aD{HungV}LL-`dG-ErPM`9d_~efN+DYDLuV4jZQM1GZF0(RxlG}a zpS>5e?b!13>iMXT><1l+kdE>UC5?$=sw4)>Gb=S^wd$(7w2Qwnw_#WQaJO~3%0Y^8 z?rixj3chfmQHb`y0`p-zs7gOz>c%k)-)b*fe%IVgWk<^gSuQk(UJD?C%h^9|va&q? z{M(vYp;&=wHu^{zF#lF*fBRnx+;IQRWaRuhA^0c#?|ujW#VloAIBl>Y_4e#ce!;hI zgLAGV0s-DGg)KN3c1%g{w)8g!S!hMkyi**_eO%Z9-qsNigx4P)k_CEOh$N`< zxS{{K4w(7-?#+(vJsCd4l5+#^69WUj<{hsmbHe^H06%eozrVLza^m~5(XjAH=9M;+ zvgX}}(JS;Y^nL5v*7@VWqA6|r>twLEB||RKJzA5pP11vXw6d}w!S>GaFJCP2)!8{k z_C)CEGUnf%^WU7Qyv>WwR;d(ddV1S&BDjaK5N-tMf3fz;#tqJpNjjUdH|X_^_~k z{2F-Edy%iDvEgt}pi9PF+;|b_pRi`b&b)+|D|v|6+kN>Wd;;os7ygPJibURr7hBg! zInv1#;e!XlQ#x1rGwk*iFJot$a?iID;ZF3;_$L~Y9I^Yxg%7Z@yi&a2~m9pxvKlZMPuP6@ihY5{S5b&Y{*bZkavdskQ=EL-!mqSZePE&c@n| z5_}?%Gj~c8iOG7gmXsXsprt`VLTGoK;G#}r0t!z#!N=EP5htq;DG+9e)--Z}ah#g@ z2|mPXf`=GO=G{ zpu?^pcbd3T`*+&OWo?YxjwIiG|A(Mxfwh7X}FiepYOl7o;MvkO7a*FM-$%3=$9Sja`rQ! z{koks5&1W*@SC6P#Z*Af=#k&hQQwwel(oG4Wo^}Q^;|fht1}0ftVsZ=0`nRkDVKzFfK9OO; zk1DLG8&bno74e&E(aGkU_*pW8Xs?6;lm9~A4+vFHWWMW~xsty}U@taItvRi6JNjY` z?=*W1F`N0e_(fyrn$*oNzaQ06be=TU7%o98Qw*L}jLK+4As%Z@&4gp3Q+%iN>HBjj zX7Q)!4aUy(qNt-P5u*P2NVto0MD^N+YP7u&b@*pZyofziM356t9XqQRACF1h9hzK7 zSXTuQz!4Ac2L&_*OywkUeP3Pv<|B`O3XJ*Q+r4+a`jq|E>$j8fGU^C!YPTIWPh>#r z4<;)lgb%GZtY`Wm($(ivJ15Z~CC&5M@n1&|7#ZWq`49jKP62fQ3OG~(KLIC4QTwE{ zMM-w&$=FtV0DddocT|COexuRytN0-6q1w{Xjz4EKk?kZXtc`%-^fy%+HYt*YpMI8= zn|>K?(P)13zK;llpcJ&5e`4CswWk`PPYKq!eJ`*U^O%x z?U+o@D z?w1Bc`>(NPX2EOYtDYS$;<5P6s4V#-wbrp{zb!g>SQ6HnSx>d9V0=ZJq2N>21*b-J zgipFr6nCKJ>AcmbpLl5k01l80siOZxS!q^%DmjsYh!N6o_O2DV?*6fKU6U***g-r2 zVW-qesdzjRxL2Y#6h%(6MuxWs1@SdukIrW>*WpJEJSJ&ybG1 zsC2rfM2!4I4E@BnlWT23wM!kc&YT;L&W3~ zJ4m%C8eTUhCNiA&c22Zt>?@JLx1PFCa$9-M{NSAwWlDohtHdgHiecHetU4EE?hUno zQAN51t?oDZyf<0#kW^-+>DnS@Vhrwy=*~|Nf*qBDRLT&| z>Myop0`4EsIfVUR{5 zDWD_ACxwXfHj+Kar?h*SELD^mgl@{J*ZV$uuawqyhds-b8H;_<9AE5o^*XDd<_MZD z&pSX@j3JH;J(oS3_2CU&7trK_!>#)OF#PkC>{TqH&RK9rrJ92#vx4T1wWi`0So6Tj z)aq8RI>9ILGqlIU{ap&{Z`mfzJVPI@(WqcZXLI1q=D(PSo69});{Y?GPIakO48WUn+zL&^6)C z0|u;w4=iJ&%Ag2Vo|ON+As#6RLkch1)747<8MV>;{hXU(GoXoZ1~YrHR{&gT_UA?n zH?^S(KuYaE{9~!EAnSmv zAUSmeMzvNpf^du}bj+89oeQQ%v`m&zx?Q?x2N-QIU5-=Pgn8ByBQ;;KmP&B|)nPB@ zU;&Pj#@&nxbqcTr_gH05#jv!i=U{0E3<$W8fHWYM1hF!B{e;+?Q+(mfvHO?=*NFJ- z>TkRGH}bGCqam^B!RLlLa>Rm8!P@=(TtZ#`$v?(qt%7OqGI@68vm7OXZ9vdtb}V%C zvi*fTGID2@6UwnbjEov@zATNEJFbn2kip@yE+98n-cDyQ#NweW6VH%dLlB~`J*%CP z3^2S<3bEnq`_4Ob-Tx6LLWPShx!qT4VBRpm=4DgpQocgYFxMoji(gEzs*7TkJgsZ} zy{)hw4NSW@5deihW z0XY9Hl}jh%sQ=~8QeSK6!E2qg0j!^oQYhD8E}9*bwsk&h^hRFhh!AI&UtL7#+cJ?M zjjg2^)YPzN9oVLcb^fy@)P+deHKtIpcz=QYKV4_LI&cC>0geRyY{qgICqJ78q zss}?AgkIgV32DLI-ewS-*}EcB>evSkju*HA(?kqpDxY{>2LOlQ>f9o^xA0jCYdJ_x zTLZJp5H0mz+$wviJ%|mK5M~v1P%OfJI^2jAC3U6g8V&Eu| zW>HY6s&cyV^`qzx6^6u70A`FKf|E@CP69@~Dp(hsiGyp^Nb{C^x=67$x#zV;CM;W# zgYd5%#i(~RS#TpN0^2l|iq%sBw#5)dm4qzeoF##D(Hlp!6>Fu2HeKT0K(YmE!%IJi zVYweBDRCNJAptj}Q=y}J0(2HKZgHg&X0mAslJQ+cX@A|x${WL49HQ|~ZZ>zrk0NNMnc29r~D#0sdj?{F>N#gxL8?W4BH8eTm$O%bKa`kT10 zovC@n=RgSQcGj#fJO>qZ%Ev0Tk=^VO%>8BcB&M&8RmSGRux9VT1|QmhNbYQ5YKm<< zz{BwY9f=TPM~J||^IN>fXHghzV5u&*L!)??pAvDKC`QUg6``CdAdN|VpzkVdy{Hkc z$5|Team&~b!Dj`E&kzX&m7|VAoCl1x%~cbTEWlcIk>YG3ALY{OMpSsr+&P&SD0Dl- zx%@u1;36HRfC%D%lkMPM+|O(>U0Q9_JjA@OWLe>SGwe=Aq2mQaZ|#B8*B4|?wc-wT z+>y*&Zi9Ra*LxJ%o~ghS*v;>mIDu(nlea7~n+jJ$8enP@A9wYsS;&RQt1>o;d2~hG z7%SIar)#|QLNhLesCE=tE zNBtT*;Hm}BS6R(M(&3}1;&y8wQqQRml5=aEL|mcUGtdIHhoi+oH&k7VJMK!c;WL`Q zKGc3Xa2^;?HM$jFez1Z`&Den1VynOelx{;f@Oa4{e^(nLy~+kuv2n+M8H4FF${oGC z&hcI=x~8uMK=}Lzp$B2@n`qX)2Y%L82yaji&dNW|zKUDI<8n(sF z<5msS!4S?$rrS+Osy=ulOOM}XKP-{$>x~k82-gF=hmuH8I2C-nF#w4&C3So zq@(EIRgc#3J9_h_Y1ak6o8!P7Df!Qclb>JJ?*E1-3%y0Y=>G2YCuIQu(0={ZjqQx& z9qsI$=$*}7Yz%D;EUf8FY)mgRZ|pXNF-CL<5$s;?0?<1*u}O4q|M(&NAq5i`_Yy$F zLW1xIi-d&~0kSZ^1+u8|W01+xx88SSVKqd`B3NH9%Z*NK6ggw7-?Nrzn7m4Fvrsxw zn|f)JqEo%(&_&|5Fq?3lp4sAj@pg2Z*?MybCXwLsE9izLzBT>=%7Ndcl(5?-l-R)A z`3@q1m6$UlJ!2aUvEK|dLWgVK+ea+ih#KWZu~>cXa!GmoY-y3=E-WcRx916I9Vz6U zr=I_q$DZGqzi4Wl*?l0~?CEArIU@Zv!Zpf3sUq(?=?=k0kE*S{kp85ahTrG#I~aAv ztKKmaZ_gZ42^bE_Pl`rB#$*Hp2a+)F2l+dsHB3xvChgX-f{9N8y43UsxuP8o zt1>>wL-!!fgdM6AqGNE-V2)MAA$5Mj*vD9LPPGL7YH&@;C(Bz6KP}f?Dd);wQ9Nb= z1_F7xqh6Oi_#2#;*`>J*!BfYXsp*>y)PSNFMyYjUM+3vyn6DZ&sa>uO z6j?5#ld+oXb>YmQ`0nOi%%bxqg#&#j(l?g--LQ9)UM)p zFb{XCQ)ClDh!?~}=F{P0RaBRS&a3eM8?|POqK41gopSRG6)+ZIlyjSSaHjDw$Q$;Q zmdf}p{XSi&sab=vLRBPaQjk7c^rpL28ecmU-JGCYbD#L8n5Vg%u9%*5uDGwk>%YD3 zXld{%e?K^~%8X3B_9y1fXYWyfu92sNI42?zB6WdgD!a6@#(AtSb&Hv-=yU#4jr)Lj z!1fa0-?-6YMMkZebn=O>Q($oGiD=s@EVz-bU1~12Kn3EF8}aPG@c}IIXDA=C@=#NK zvaU|2yAdGw<t_aG(QOFZ|Bz`jb-OFFTNrS^NxHKDgfSf^LS- z`>mDNNKdOvYOY1&6L{;=dDxs|6V$_7WvEX2*H9E0@%7p>I})h{_U-VsyM6?8(bJ)% zs`Hr*YKuf|QfesaKS&QK_|f%CwPQ^KMrH$9&)Zqz8KGk~j5gmD{s_VS~O1U=}EGf{mdhQ3sr%lkFE>8!zQ|u_Z-=+CUw1By9ObY;IcrXeb$D8=?Q41^#@$ zcGDu0BFPgAbOr+a`BWweX9J~|->y#-XAmLFJ}eUlpfq?z@Uu*onW?|BUvaL79>qqY zON5pCizadd+FPf`f$2IaEN_F#zX3TN1qA&|I*&-UAxDKI6Aiv|1#?ylmEfP*O9C;6 zg~%0ab&c|&2zJv71%?Hiia>E$uDPq;2CcHY}(~pr}dH zPK*Be%$t(;7c<~6(0HvHH2zsLa#`>lQ`89QryVesnP8Xpwb;sgPaf+u2r$!4V-CTM zX5o@*rW__$FJR+)sK*&`E$%j{7SMP6>M!&e=}zU`aqTuL(=qGsX6|FINh`Qnb-TQq z`vSh7jEKp~oDB7NnRoCtY{(wFiNv$xKZnG&FkFp+j@&`(%q6+Nr{JRx*%BV z`Exle-_`-d<{06rcoA^=Ws<&g*K?qc%=>-;N#k^fi7%(>wLYX-G;pH#itB_fTX2h8 zYMpa*Uz3xp>iO0K9st>O6czSI#^pj@ z6*6#ai{pAgV55tJ;`4v!nS2d+5%fa=01Wc}cSd%#aI&!bosLaxO#a*cS7g`vH5KMU z>i#tq7MShA`uYKJfq%>>l$j@xZ9gS7nrN0a9*aF}TpRKT=-PbYu(RJbec^Q#mt?Y- zbJ=JWi5LdOQh4XUnT9bF6*@n%!%t~@j8%0}MI+Ym${SbIlpeQGofNyjlF4taS7t9w z&F`d{kNZqrzPGFS{%%P*ZPh58P!9MO@re|@&$mz=5fgg?u`PHPX_JI@XQQqlwanF+ ziYZ2Y2XIb#i>oewoY>=>R*S6U(T+41%|7g`v3m z*v&v!0-geYjOuMntVS0v?*J{9T}T^={MO2WR^PJ*{xq%FWc{yP48XlmF(b~#qRv)?77cKIiqLwqt%t2x2H>2OQE!8lXPtrlBV_3Q6d+$St=bYN51>LP zYp+)`aw=g6IYD>}xcf*m^2FgSNaJY3{$D>;+6{;%v@Ic1lfP6!Udd@3xDPZ`U#pob zuw?LR^X=oJ_dU*Htlq>7iQ+M=Lo7sc4k{B0m#Yyt%&N!>k3X?`UEb!=VXP%)3RcJP zQ@ztEYlT!7j?0~?i4z5mY!hT>b3$Mjkd@jCF{4!etiqS{rEB)mU10vOm0><` z6til#6wW$_n&TLFUMVH2yMLgN>SE{0n;z!n4_X2LKHG0E3fL+{C3#8o zOeskd>=TX@VUUwQXt-KJQRn$WDQVsOfntK0jn1**zl$7>L>)`Q7&{rCEBWKv@_vcY zv8AEG!lEDUctrZ%Rf*)MZw?389GgC(!X<<}+9#A~=B5&?@y`L_A!s{&F;L5$Mcky^ z8Z>OK%$GA6bM)u?^Tqe)9sa5Vw$s2LT?dM^OSf?7lf}kkm#eG$p1w`i=A)@xl04x@qS&6oyI1sAbft_0PREA3bp&ugfPj#Lh8Xim6%B2u|*u4Vyk$? zJ)aCHPR}3igTeN?j+Zo)Txp89j0XLXx@=P^`H6y10eKGcj0iVH`Qv;Iu{&Hhp%5Qqx<{qW%`dS^hNIJ%T1*-8y7D)9d^BD zp-aDRN8bTO-(V^-uJrjH*F8QHL8x6Uf5FRgUHfpcuRUOSu?9n}5wu?eSA$(;VU}9z5m4BA)=)vKbqW=3@ zvW2D1Ho+2y9qnkJtEghXa*)~aBW)mr+gq4gv_|sD!7-zpR^B3lZwch)Aa7efuaa00 zIZmWitfZyhxgPDV;_%?EO>y3lFEF}{!z@6xMII_ck$*8| zmcJ3MIhdXhdSP=_Q>VU5D*Aj#oHaHYNy z03Jf`ks>O+cZ^aMrATj5MLI@AIzdB~-ive)rMC+R(j*87p(`jz5s)fH4DBLa1d;Mq zxjZE1{sr$P-xoGv=eKj_%ZHcZr!^|`MoM$@hiSpeq=KLHF zAgrzmMR3-fO#4BJAPTZY$7l;yJ6rP^i7mI5mQi`-vWMp(EZPX|>&D|$k|WHQ=4jb2 zcy)$}+?L;{CEwgIGJ3RWHg>zF#h*T=;Wh2us=CJTxQwyMuA$B@20aN=mgxPBa|z4C zIeKqz)xFDrIS8NOE|>ZMN;*3zMz&GxLe0Rzb;a&Z)RJNRJ118qS2afiNF686m9Iqs ze9?F>GUM!%YbZyu6g^1RP>Yj=X~jzp&+v7SLd37Yv@=a9u)p(dIZ4ti{KhAHku>6w zRIj&kpo8qX2=DqXe}8?0)A-v{6_VSsG09$g`*l-K-nvF3eaXEWot>amNvlb@Qx=1d z3l!@jGcE{JBX|7k@3&m`+ToaXV4-&2^}zK^a=gl^%_(#nSwqQ21K}xagjwHOjurjz zT9=RTQ-A9mLld{K&f;+OW9gc7_?G^w?WwsePHDoDR(!$XTg-~*QtBL;Dv* zNFs%T>W!^>E#Y)Ckm+e1X8Cc6!k0xIv?#tT0<&9dtao+^{Dx*JSBaS0<~M}gJ)1r` zjfoFuGrKbtQ+#l1dH}8=5$Mqt7>~9eFHeU;jTikzBsnka$h6R--_GrUytWL^0sX0Y@F4$GVDy{5ETpr&&>*j9bJ95pk8|0jo zR3C;uHVJ=OE|wk{Xpy|JsdA(ACLu9Ap)@jXic$DlTAP@4U-`|?sg;TZ(TISaEZ+)_ z*Qj*k8g&kyL5F$Bdl$LA2wV#sFIB=&ZDL*7O_VeS(bWUo3O~29q%6NBU#B9RZrS0W+ zv2bc}j_ykuJ!BTj9gmceEHJkmt+nFe8z!AqUx(ei$HK?bkOx!2WPK0b%lWFe_9pes zn39AVFXHd}P;w{ACpQt`s7RzsrTPSs^BJ~Wy5pwNscuRt`T1K)1NrX2-g7gB2lE_q z($3${v0j5A>DWw!uLbF!mtSY4nt`biYc3t=aoUm{ICZU3mSi0G)Jv;`wIMmzGee;S zTO&y|x?y6uDm8aSh)c{8(88kGocr>7Zs+GrHFq4GOs-@p1TCNDZF_Dm`Pi+owfiQX zxn=Q2KG!{ZTMF6$VfFg0{BXR5oxcyTX7L-dLcenYgFux)D*02u9*0-GZZ?j0;BJVY z8HWdSI~~WM5ER|K^n9D{W|bv{oW*NzP5bk9b!% zb(qPPz6iZdPLC? zlml#KIZi1B^d&{PR4YTEjx{Cbc05KzUf^}cC%na=&5t}`*WlB*)%iOa_Ws351xvG{ zLH#xDg`*=lMa3N8`_|DsMsI|N(dI^S8i`cVIoXX zd+#9!*;aJH+E7Lf@CI)DNJb_TB`2Bq=4~rT@;jYgjlacezKcEeX^vvqzBwr@lhS}Y z9xGL6&z69r8cAdHgSJ3@Qxv}HZpfspm5nh&BE;R zgu2m5TYBqm+F4XdmZeq5gu(+`y8SgJ?a<<=K-5G`N#JgI**uxZdyVu(YLUzt{$@Au z%|R=Ypp8(+p5n5*?f08scBI1LX{k|25-5v1-_}Q#H<=ZipIeuDxPS1>82-?D!a2lW zCXR<1fEbbZJk`}4yGvy9*9*r{cp#X(o}d0nohdWY>mb!$d}w5Rcd~HyK;y-r%f&r% zY~7?mxlS?mI3N%l=tQLk5#ju|o7BPu;S6{9>7Xn*csM*+AYiBe?H4LR!>$F&(6$oj z9UAZHaL%|OuVkPq0IE>c-72IrriZJc6F<*oG3ouhbQ)HmL2wCu(6Zslq`bQ(SrUbN zI^O9tsE*Lz->_M&r3%OWZT>9ejLuB)JG*WtP_#k7J$K)^^Z4*`Ej%?jHRxHtbe$+G z!-`>8N@oU>@YTYate1Ux!$zngWq)e3FT8g2dK8?O! zT49m96tZ8v{r>4wHcOBcmH2fkx>_z(rRO%l!waH!atWy^Smmi{G?lb>h$Ck!BmJ81 z7v+}S>@=*1Ws8HXus1?QvT<3uaFewu3Qn$Fd^J!l4g*$4!he9pyS=EWelZ`-YX|?(Fk7hQXsmoCOos(647Yc!`CSvfOzzU zG;y$zfudbX$|#XHpU#qWUNkJBWB_ut5=%cNt zgOw{U@*%%8+@-V2v;R1pd(VVeCxla#N{v1y>0`jb}?7|WQT?Z zp2?8LChZ_>x^k;F`V1HaU=Krn(AZ79@W^m=e7HCzmoC$m8cse4j?63hPWUxuZ$8?r zpY_qwHzwd2ZnZs0Sq?EYxt$0>Tcao{^44TNRU<>25feZ9?Mp-Y3A%&oDk`e|tCvk* zBv1ZT4!*ypNBJa}SXIZQKD;46I9A$|wC4l-`-4@MY)JT+WV_0OSy)QlsibcOmJ4E^ z@(vi(eYr^mn97+izM>LA={x0pTh<$iknsOFyBFMQ?%A8JW!2`Z?t&9PsMo)0+_{Or zE>k+VbNyn9%h|%0lGBfK7cP6${j${-0AeVnozQOdt4HZ=8y@IaFc-9Muy_NPiFH%ADT1|v; zUVC9)uRkmyZ4#uX0$p9Z))m^Q%KLa7QbosBmiy?F@M!eI2MrC7IN-XH$wuS1rSaXZ z^=^#r0}v{<5v{k5T@+!auRUT3p=<)mu)^(m)G6g`xH~sG!P<|`(6x&^OACxIjnnVQ zRYCVxyl{o&juTBGeL6!F0>tA2N);^*G?>gSg-kdGK1B6lv$8xC*n z<(#*mAMow=^*N}D%FQ3mK*cxx{V1N+);`;8ZHPU+Wo-x^E0I6vN75H4Gq)I3P6(6Y zlyqQV3PIbg!x}X@X1ZoA}2~qv!sLvb{YA z;Os&cp+h&4wL_`zfd}ph;$Qo`3r%603sbiVc8IQY6CHMLjB@QRlvtTj9r6X-_pnjH z0Skg?Km;Hll?jLy^bD6)s0{d@46x*b`nV$h*)o=cJ33oBI-BcxI9Vc0f4aJs+DSlx zLCXtH0AL2h2I&dFJn)P8eM@`9d7+=5n1W93?MvA-Aka&H5Qyr8pcF7@v`LM(w<|)G*IG`Mf|OBn3$Iy#IDwWl?;HK>_1ls9lv^n zuw%rr)m=@#vc(w+5QtX^6XSRhJLXriMNDl}4D|5W0Sh|-wmGRyy$p8DujkfdVoGJY ztgirrGIu2~F?4d+F~3G>Ffoy=0fHTXK^_B6$#QHMU@Jo72!mPYzd%?$=-+Aaz-*4g z3d5xRDjilD*H$@2J)p_CKXgmc{5RUKm0nnBMzbi@B*5me5KMzT(mJ9Y#mnK}U&)a$ z4aUlCu2hSX2761SM diff --git a/Drv/UartFramer/docs/img/Downlink.svg b/Drv/UartFramer/docs/img/Downlink.svg deleted file mode 100644 index ecd9189b3c..0000000000 --- a/Drv/UartFramer/docs/img/Downlink.svg +++ /dev/null @@ -1,142 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - Downlink - - - - Sheet.1 - - - - Sheet.2 - UART Driver - - - - UART Driver - - Sheet.3 - - - - Sheet.4 - UartFramer - - - - UartFramer - - Sheet.5 - - - - Sheet.6 - Buffer Manager - - - - Buffer Manager - - Sheet.7 - - - - Sheet.8 - Framer - - - - Framer - - Sheet.9 - - - - Sheet.10 - serialSend - - - - serialSend - - Sheet.11 - - - - Sheet.12 - Framer - - - - Framer - - Sheet.13 - - - - Sheet.14 - FramerDeallocate() - - - - FramerDeallocate() - - - - - - - - - - - - - - - - - - Dynamic connector - - - - - - diff --git a/Drv/UartFramer/docs/img/Topo.svg b/Drv/UartFramer/docs/img/Topo.svg deleted file mode 100644 index c82e4aa2a9..0000000000 --- a/Drv/UartFramer/docs/img/Topo.svg +++ /dev/null @@ -1,520 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - Component Connections - - - - Rounded Rectangle - UartFramer - - - - - - - - - - - - - - - - - - - - - - UartFramer - - Square - - - - - - - Sheet.3 - - - - Sheet.4 - - - - Sheet.5 - readBufferSend - - - - readBufferSend - - Square.20 - - - - - - - Sheet.7 - - - - Sheet.8 - serialRecv - - - - serialRecv - - Square.9 - - - - - - - Sheet.10 - - - - Sheet.11 - - - - Sheet.12 - serialSend - - - - serialSend - - Square.27 - - - - - - - Sheet.14 - - - - Sheet.15 - deframerAllocate - - - - deframerAllocate - - Square.37 - - - - - - - Sheet.17 - - - - Sheet.18 - framerDeallocate - - - - framerDeallocate - - Square.40 - - - - - - - Sheet.20 - - - - Sheet.21 - - - - Sheet.22 - Deframer - - - - Deframer - - Square.44 - - - - - - - Sheet.24 - - - - Sheet.25 - Framer - - - - Framer - - Rounded Rectangle.26 - LinuxSerial Driver - - - - - - - - - - - - - - - - - - - - - - LinuxSerialDriver - - Square.27 - - - - - - - Square.28 - - - - - - - Square.29 - - - - - - - Rounded Rectangle.36 - Buffer Manager - - - - - - - - - - - - - - - - - - - - - - BufferManager - - Rounded Rectangle.37 - Static Memory - - - - - - - - - - - - - - - - - - - - - - StaticMemory - - Square.38 - - - - - - - Square.39 - - - - - - - Sheet.40 - bufferGetCallee - - - - bufferGetCallee - - Sheet.41 - readBufferSend - - - - readBufferSend - - Sheet.42 - serialRecv - - - - serialRecv - - Sheet.43 - serialSend - - - - serialSend - - Sheet.44 - bufferDeallocate - - - - bufferDeallocate - - Rounded Rectangle.45 - Deframer - - - - - - - - - - - - - - - - - - - - - - Deframer - - Square.46 - - - - - - - Square.47 - - - - - - - Square.68 - - - - - - - Sheet.71 - - - - Sheet.72 - - - - Sheet.73 - bufferSendIn - - - - bufferSendIn - - Square.74 - - - - - - - Rounded Rectangle.75 - Framer - - - - - - - - - - - - - - - - - - - - - - Framer - - Square.76 - - - - - - - Square.77 - - - - - - - Sheet.79 - - - - Sheet.80 - - - - Sheet.81 - bufferAllocate - - - - bufferAllocate - - Sheet.82 - framedDeallocate - - - - framedDeallocate - - Sheet.83 - framedAllocate - - - - framedAllocate - - Sheet.84 - Framed Out - - - - FramedOut - - Sheet.85 - Framed In - - - - FramedIn - - diff --git a/Drv/UartFramer/docs/img/UartFramer.svg b/Drv/UartFramer/docs/img/UartFramer.svg deleted file mode 100644 index 03bfb074cb..0000000000 --- a/Drv/UartFramer/docs/img/UartFramer.svg +++ /dev/null @@ -1,204 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - Component Diagram - - - - Rounded Rectangle - UartFramer - - - - - - - - - - - - - - - - - - UartFramer - - Square - - - - - - - Sheet.16 - - - - Sheet.18 - - - - Sheet.19 - readBufferSend - - - - readBufferSend - - Square.20 - - - - - - - Sheet.21 - - - - Sheet.22 - serialRecv - - - - serialRecv - - Square.23 - - - - - - - Sheet.24 - - - - Sheet.25 - - - - Sheet.26 - serialSend - - - - serialSend - - Square.27 - - - - - - - Sheet.28 - - - - Sheet.30 - deframerAllocate - - - - deframerAllocate - - Square.37 - - - - - - - Sheet.38 - - - - Sheet.39 - framerDeallocate - - - - framerDeallocate - - Square.40 - - - - - - - Sheet.41 - - - - Sheet.42 - - - - Sheet.43 - Deframer - - - - Deframer - - Square.44 - - - - - - - Sheet.45 - - - - Sheet.46 - Framer - - - - Framer - - diff --git a/Drv/UartFramer/docs/img/UartFramerAllocate.svg b/Drv/UartFramer/docs/img/UartFramerAllocate.svg deleted file mode 100644 index 7c267a5b21..0000000000 --- a/Drv/UartFramer/docs/img/UartFramerAllocate.svg +++ /dev/null @@ -1,125 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - Initialization Scenario Diagram - - - Sheet.1 - - - - Sheet.2 - UART - - - - UART - - Sheet.4 - - - - Sheet.5 - UartFramer - - - - UartFramer - - Sheet.6 - - - - Sheet.7 - BufferManager - - - - BufferManager - - Sheet.8 - - - - Sheet.9 - allocate(number,size) - - - - allocate(number,size) - - Sheet.10 - - - - Sheet.11 - DeframerAllocate(size) - - - - DeframerAllocate(size) - - Sheet.13 - readBufferSend() - - - - readBufferSend() - - Sheet.14 - - - - Sheet.15 - - - - Sheet.16 - - - - Sheet.17 - - - - Sheet.18 - number - - - - number - - diff --git a/Drv/UartFramer/docs/img/Uplink.svg b/Drv/UartFramer/docs/img/Uplink.svg deleted file mode 100644 index 26b0704bb3..0000000000 --- a/Drv/UartFramer/docs/img/Uplink.svg +++ /dev/null @@ -1,130 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - Uplink - - - Sheet.1 - - - - Sheet.2 - UART Driver - - - - UART Driver - - Sheet.3 - - - - Sheet.4 - UART Relay - - - - UART Relay - - Sheet.5 - - - - Sheet.6 - Buffer Manager - - - - Buffer Manager - - Sheet.7 - - - - Sheet.8 - Deframer - - - - Deframer - - Sheet.9 - - - - Sheet.10 - serialRecv() - - - - serialRecv() - - Sheet.11 - - - - Sheet.12 - Deframer() - - - - Deframer() - - Sheet.13 - - - - Sheet.14 - DeframerAllocate() - - - - DeframerAllocate() - - Sheet.15 - - - - Sheet.16 - readBufferSend() - - - - readBufferSend() - - diff --git a/Drv/UartFramer/docs/sdd.md b/Drv/UartFramer/docs/sdd.md deleted file mode 100644 index 09a06df57e..0000000000 --- a/Drv/UartFramer/docs/sdd.md +++ /dev/null @@ -1,174 +0,0 @@ -\page DrvUartFramerComponent Drv::UartFramer Component -# Drv::UartFramer UART Framer Component - -The UART Framer Component is used to bridge the [Framer](../../Svc/Framer/docs/sdd.md) and -[Deframer](../../Svc/Deframer/docs/sdd.md) components to the [Linux Serial Driver](../LinuxSerialDriver/) component. -Another UART driver could be used as long as it supports the same interfaces as the Linux Serial Driver. -This allows a connection to the F Prime [ground system](https://github.com/fprime-community/fprime-gds) via a standard -UART connection. The component is defined as passive, since it acts as a pass-through and doesn't require its own -thread. - -## Design - -### Component Diagram - -![Component Diagram](img/UartFramer.svg) - -### Port List - -|Port Name|Description| -|---|---| -|DeframerAllocate|Allocates buffers for the UART driver to send to the deframer via the UartFramer.| -|FramerDeallocate|Deallocate buffers sent by the framer| -|Framer|Receives packets for downlink| -|Deframer|Sends received packets for uplink| -|readBufferSend|Sends buffers to UART driver receive buffer pool| -|serialRecv|Receives uplink buffers from UART driver| -|serialSend|Sends downlink buffers to UART driver| - -### Initialization - -During initialization, the `UartFramer` component supplies an initial set of buffers to the UART driver to act as a receive pool for received data. - -The initialization call is as follows: - -``` -void allocate(NATIVE_UINT_TYPE number, NATIVE_UINT_TYPE size); -``` - -The arguments are as follows: - -|Argument|Description| -|---|---| -|number|The number of buffers to allocate. This should be defined to cover any anticipated surges in data that could temporarily outpace processing| -|size|The size of each buffer. Should match the size of buffers used for `Framer` and `Deframer`. - -The component invokes the `DeframerAllocate` port enough times to allocate the number of buffers in the `number` parameter, with a requested size of `size`. For each of those invocations, the buffer is passed to the UART driver for the receive pool via the `readBufferSend` port. - -In order for the allocation call to work, all ports should be connected before invoking `allocate()`. - -![Initial Buffer Allocation](img/UartFramerAllocate.svg) - -## Uplink - -When packets arrive via the UART, the UART driver connected to `UartFramer` will get a buffer from the pool of buffers that were initially allocated and fill it with the packet data. The packets are then sent to `UartFramer` via the `serialRecv` port. The buffer is forwarded to the `Deframer` component for processing via the `Deframer` port. -The `Deframer` component will deallocate it when complete. After the packet is forwarded to the `Deframer` component, another packet is allocated via the `DeframerAllocate` port and sent to the UART driver to replenish the pool of receive buffers. - - -![Uplink](img/Uplink.svg) - -## Downlink - -The `Framer` component allocates a packet and fills it with data. The packet gets sent to `UartFramer`, which sends it to the UART driver via the `serialSend` port. When the port call returns (see requirement #4 below), the buffer is deallocated via an invocation of the `FramerDeallocate` port. - -![Downlink](img/Downlink.svg) - -## Error handling - -The `UartFramer` component converts the UART receive error status to the corresponding `Deframer` error status. - -If the `UartFramer` cannot allocate an additional buffer for the serial receive pool, it will issue a `WARNING_HI` event. In this case, the receive pool will permanently lose a buffer. - -## Interconnections - -The following is a diagram of how the `UartFramer` would be connected to the `Framer` and `Deframer` and LinuxSerialDriver components in a typical topology. Note that the types are in the diagram rather than instance names which would be in the actual topology specification. - -![Topology Example](img/Topo.svg) - -## FPP examples - -An example instance of the `LinuxSerialDriver` in the topology is as follows: - -``` -instance gndUart: Drv.LinuxSerialDriver \ - base id 2000 \ - { - - phase Fpp.ToCpp.Phases.configComponents """ - bool openStat = gndUart.open("/dev/ttyUL1", - Drv::LinuxSerialDriverComponentImpl::BAUD_115K, - Drv::LinuxSerialDriverComponentImpl::NO_FLOW, - Drv::LinuxSerialDriverComponentImpl::PARITY_NONE, - true - ); - FW_ASSERT(openStat); - - """ - - phase Fpp.ToCpp.Phases.startTasks """ - gndUart.startReadThread(); - """ - - phase Fpp.ToCpp.Phases.stopTasks """ - gndUart.quitReadThread(); - """ - - } -``` - -The `LinuxSerialDriver` FPP is included as an illustration of how to initialize the UART driver and to relate to the FPP topology code below. - -An example instance of the `UartFramer` in the topology FPP is as follows: - -``` -instance gndUartFramer: Drv.UartFramer \ - base id 2100 \ - { - - phase Fpp.ToCpp.Phases.startTasks """ - gndUartFramer.allocate(10,1024); - """ - - } -``` - -This code pre-allocates 10 1K buffers for the UART driver. It places this call in the initialization phase where component tasks are started, where we know all connections have been completed. - -An example set of connections in the topology FPP is as follows: - -``` - connections SomeDeployment { - - gndUart.serialRecv[0] -> gndUartFramer.serialRecv[0] - gndUartFramer.serialSend[0] -> gndUart.serialSend[0] - gndUartFramer.readBufferSend[0] -> gndUart.readBufferSend[0] - - gndUartFramer.DeframerAllocate[0] -> gndBufferManager.bufferGetCallee[0] - gndUartFramer.FramerDeallocate[0] -> staticMemory.bufferDeallocate[1] - - gndUartFramer.Deframer[0] -> uplink.framedIn[0] - uplink.framedDeallocate[0] -> gndBufferManager.bufferSendIn[0] - - downlink.framedOut[0] -> gndUartFramer.Framer[0] - downlink.framedAllocate[0] -> staticMemory.bufferAllocate[1] - - ... -``` - -This matches the diagram above where instance names are used as opposed to type names in the diagram. - -## Requirements - -| Name | Description | Validation | -|---|---|---| -| UART-FRAMER-COMP-001 | The `UartFramer` component shall pass the `Framer` downlink buffers to UART driver | unit test | -| UART-FRAMER-COMP-002 | The `UartFramer` component shall pass buffers received by the UART to the `Deframer` | unit test | -| UART-FRAMER-COMP-003 | The `UartFramer` component shall supply the UART driver with a specified number of receive buffers at initialization time| unit test | -| UART-FRAMER-COMP-003 | The `UartFramer` component shall pass any receive failure statuses to the `Deframer` | unit test | -| UART-FRAMER-COMP-003 | The `UartFramer` component shall allocate a buffer and pass it back to the UART for every buffer received| unit test | - -## Requirements on other components or topologies - -1\. Packets allocated for the UART receive pool with the `DeframerAllocate` port and sent to the UART driver are the same ones returned in the `serialRecv` port call. - -2\. Packets sent to the `Deframer` component are returned to the same buffer pool that is connected to the `DeframerAllocate` port. - -3\. Packets sent by the `Framer` component are allocated from the same pool as the `FramerDeallocate` port is connected to. - -4\. The UART driver is finished with the transmit buffer after the return of the `serialSend` port invocation so it can be returned to the buffer pool. - -## Change Log - -| Date | Description | -|---|---| -| 2021-02-03 | Initial Release | diff --git a/Drv/UartFramer/test/ut/TestMain.cpp b/Drv/UartFramer/test/ut/TestMain.cpp deleted file mode 100644 index e2642e8d27..0000000000 --- a/Drv/UartFramer/test/ut/TestMain.cpp +++ /dev/null @@ -1,35 +0,0 @@ -// ---------------------------------------------------------------------- -// TestMain.cpp -// ---------------------------------------------------------------------- - -#include "Tester.hpp" - -TEST(Nominal, toDo) { - Drv::Tester tester; - tester.initialization(); -} - -TEST(Nominal, send) { - Drv::Tester tester; - tester.packetSend(); -} - -TEST(Nominal, receive) { - Drv::Tester tester; - tester.packetReceive(); -} - -TEST(Error, receive) { - Drv::Tester tester; - tester.packetReceiveError(); -} - -TEST(Error, allocationError) { - Drv::Tester tester; - tester.packetAllocationError(); -} - -int main(int argc, char** argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/Drv/UartFramer/test/ut/Tester.cpp b/Drv/UartFramer/test/ut/Tester.cpp deleted file mode 100644 index 75ef4e86f7..0000000000 --- a/Drv/UartFramer/test/ut/Tester.cpp +++ /dev/null @@ -1,320 +0,0 @@ -// ====================================================================== -// \title UartFramer.hpp -// \author tcanham -// \brief cpp file for UartFramer test harness implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#include "Tester.hpp" - -#define INSTANCE 0 -#define MAX_HISTORY_SIZE 10 - -namespace Drv { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - Tester :: - Tester() : - UartFramerGTestBase("Tester", MAX_HISTORY_SIZE), - component("UartFramer") - ,m_currBuff(0) - ,m_emptyAlloc(false) - { - this->initComponents(); - this->connectPorts(); - } - - Tester :: - ~Tester() - { - - } - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - void Tester :: - initialization() - { - - this->component.allocate(NUM_INIT_BUFFERS,10); - ASSERT_EQ(NUM_INIT_BUFFERS,this->m_currBuff); - // two port calls; allocate and pass to UART driver - ASSERT_FROM_PORT_HISTORY_SIZE(NUM_INIT_BUFFERS*2); - // allocation calls - ASSERT_from_DeframerAllocate_SIZE(NUM_INIT_BUFFERS); - // UART driver calls - ASSERT_from_readBufferSend_SIZE(NUM_INIT_BUFFERS); - - } - - void Tester :: - packetSend() - { - - // do initialization - this->initialization(); - this->clearHistory(); - - // send a packet - Fw::Buffer sent(reinterpret_cast(1),0); - this->invoke_to_Framer(0,sent); - // verify forwarded to driver - // UART + deallocate - ASSERT_FROM_PORT_HISTORY_SIZE(2); - // Buffer deallocation - ASSERT_from_FramerDeallocate_SIZE(1); - // Send buffer to UART - ASSERT_from_serialSend_SIZE(1); - - } - - void Tester :: - packetReceive() - { - - // do initialization - this->initialization(); - this->clearHistory(); - - // receive a packet - Fw::Buffer received(reinterpret_cast(1),0); - Drv::SerialReadStatus stat = Drv::SerialReadStatus::SER_OK; - this->invoke_to_serialRecv(0,received,stat); - // verify forwarded to driver - // send to deframer + allocate a new packet + send to UART - ASSERT_FROM_PORT_HISTORY_SIZE(3); - // packet sent to deframer - ASSERT_from_Deframer_SIZE(1); - // verify good status to deframer - Drv::RecvStatus retStat = Drv::RecvStatus::RECV_OK; - ASSERT_from_Deframer(0,received,retStat); - // Buffer allocation for UART pool - ASSERT_from_DeframerAllocate_SIZE(1); - // Return buffer to UART for receive pool - ASSERT_from_readBufferSend_SIZE(1); - - } - - void Tester :: - packetReceiveError() - { - - // do initialization - this->initialization(); - this->clearHistory(); - - // receive a packet - Fw::Buffer received(reinterpret_cast(1),0); - Drv::SerialReadStatus stat = Drv::SerialReadStatus::SER_PARITY_ERR; - this->invoke_to_serialRecv(0,received,stat); - // verify forwarded to driver - // send to deframer + allocate a new packet + send to UART - ASSERT_FROM_PORT_HISTORY_SIZE(3); - // packet sent to deframer - ASSERT_from_Deframer_SIZE(1); - // verify good status to deframer - Drv::RecvStatus retStat = Drv::RecvStatus::RECV_ERROR; - ASSERT_from_Deframer(0,received,retStat); - // Buffer allocation for UART pool - ASSERT_from_DeframerAllocate_SIZE(1); - // Return buffer to UART for receive pool - ASSERT_from_readBufferSend_SIZE(1); - - } - - void Tester :: - packetAllocationError() - { - - // do initialization - this->initialization(); - this->clearHistory(); - - // receive a packet - Fw::Buffer received(reinterpret_cast(1),0); - Drv::SerialReadStatus stat = Drv::SerialReadStatus::SER_OK; - // set flag to return empty buffer - this->m_emptyAlloc = true; - this->invoke_to_serialRecv(0,received,stat); - // verify forwarded to driver - // send to deframer + allocate a new packet + send to UART - ASSERT_FROM_PORT_HISTORY_SIZE(2); - // packet sent to deframer - ASSERT_from_Deframer_SIZE(1); - // verify good status to deframer - Drv::RecvStatus retStat = Drv::RecvStatus::RECV_OK; - ASSERT_from_Deframer(0,received,retStat); - // Buffer allocation for UART pool - ASSERT_from_DeframerAllocate_SIZE(1); - // Shouldn't try to give a buffer to the UART if one wasn't allocated - ASSERT_from_readBufferSend_SIZE(0); - // Should have seen error event - ASSERT_EVENTS_SIZE(1); - ASSERT_EVENTS_BuffErr_SIZE(1); - - } - - // ---------------------------------------------------------------------- - // Handlers for typed from ports - // ---------------------------------------------------------------------- - - void Tester :: - from_Deframer_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &recvBuffer, - const Drv::RecvStatus &recvStatus - ) - { - this->pushFromPortEntry_Deframer(recvBuffer, recvStatus); - this->m_currBuff--; - } - - Fw::Buffer Tester :: - from_DeframerAllocate_handler( - const NATIVE_INT_TYPE portNum, - U32 size - ) - { - this->pushFromPortEntry_DeframerAllocate(size); - if (not this->m_emptyAlloc) { - this->m_buffPool[this->m_currBuff].setSize(size); - this->m_buffPool[this->m_currBuff].setData(reinterpret_cast(1)); - this->m_currBuff++; - return this->m_buffPool[this->m_currBuff-1]; - } else { - Fw::Buffer empty(reinterpret_cast(1),0); - return empty; - } - } - - void Tester :: - from_FramerDeallocate_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &fwBuffer - ) - { - this->pushFromPortEntry_FramerDeallocate(fwBuffer); - } - - void Tester :: - from_readBufferSend_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &fwBuffer - ) - { - this->pushFromPortEntry_readBufferSend(fwBuffer); - } - - void Tester :: - from_serialSend_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &serBuffer - ) - { - this->pushFromPortEntry_serialSend(serBuffer); - } - - void Tester::textLogIn(const FwEventIdType id, //!< The event ID - Fw::Time& timeTag, //!< The time - const Fw::LogSeverity severity, //!< The severity - const Fw::TextLogString& text //!< The event string - ) { - TextLogEntry e = { id, timeTag, severity, text }; - - printTextLogHistoryEntry(e, stdout); - } - - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - void Tester :: - connectPorts() - { - - // Framer - this->connect_to_Framer( - 0, - this->component.get_Framer_InputPort(0) - ); - - // serialRecv - this->connect_to_serialRecv( - 0, - this->component.get_serialRecv_InputPort(0) - ); - - // Deframer - this->component.set_Deframer_OutputPort( - 0, - this->get_from_Deframer(0) - ); - - // DeframerAllocate - this->component.set_DeframerAllocate_OutputPort( - 0, - this->get_from_DeframerAllocate(0) - ); - - // FramerDeallocate - this->component.set_FramerDeallocate_OutputPort( - 0, - this->get_from_FramerDeallocate(0) - ); - - // Log - this->component.set_Log_OutputPort( - 0, - this->get_from_Log(0) - ); - - // LogText - this->component.set_LogText_OutputPort( - 0, - this->get_from_LogText(0) - ); - - // Time - this->component.set_Time_OutputPort( - 0, - this->get_from_Time(0) - ); - - // readBufferSend - this->component.set_readBufferSend_OutputPort( - 0, - this->get_from_readBufferSend(0) - ); - - // serialSend - this->component.set_serialSend_OutputPort( - 0, - this->get_from_serialSend(0) - ); - - - - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init( - INSTANCE - ); - } - -} // end namespace Drv diff --git a/Drv/UartFramer/test/ut/Tester.hpp b/Drv/UartFramer/test/ut/Tester.hpp deleted file mode 100644 index 4368507f5d..0000000000 --- a/Drv/UartFramer/test/ut/Tester.hpp +++ /dev/null @@ -1,150 +0,0 @@ -// ====================================================================== -// \title UartFramer/test/ut/Tester.hpp -// \author tcanham -// \brief hpp file for UartFramer test harness implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef TESTER_HPP -#define TESTER_HPP - -#include "GTestBase.hpp" -#include "Drv/UartFramer/UartFramer.hpp" - -#define NUM_INIT_BUFFERS 5 - -namespace Drv { - - class Tester : - public UartFramerGTestBase - { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - public: - - //! Construct object Tester - //! - Tester(); - - //! Destroy object Tester - //! - ~Tester(); - - public: - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - //! Initialization - //! - void initialization(); - - //! packet send - //! - void packetSend(); - - //! packet receive - //! - void packetReceive(); - - //! packet receive error - //! - void packetReceiveError(); - - //! error allocating UART receive buffer - //! - void packetAllocationError(); - - - private: - - // ---------------------------------------------------------------------- - // Handlers for typed from ports - // ---------------------------------------------------------------------- - - //! Handler for from_Deframer - //! - void from_Deframer_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &recvBuffer, - const Drv::RecvStatus &recvStatus - ); - - //! Handler for from_DeframerAllocate - //! - Fw::Buffer from_DeframerAllocate_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U32 size - ); - - //! Handler for from_FramerDeallocate - //! - void from_FramerDeallocate_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &fwBuffer - ); - - //! Handler for from_readBufferSend - //! - void from_readBufferSend_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &fwBuffer - ); - - //! Handler for from_serialSend - //! - void from_serialSend_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &serBuffer - ); - - void textLogIn( - const FwEventIdType id, //!< The event ID - Fw::Time& timeTag, //!< The time - const Fw::LogSeverity severity, //!< The severity - const Fw::TextLogString& text //!< The event string - ); - - - private: - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - //! Connect ports - //! - void connectPorts(); - - //! Initialize components - //! - void initComponents(); - - private: - - // ---------------------------------------------------------------------- - // Variables - // ---------------------------------------------------------------------- - - //! The component under test - //! - UartFramer component; - - Fw::Buffer m_buffPool[NUM_INIT_BUFFERS]; - NATIVE_UINT_TYPE m_currBuff; - bool m_emptyAlloc; - - }; - -} // end namespace Drv - -#endif diff --git a/RPI/RpiDemo/RpiDemo.fpp b/RPI/RpiDemo/RpiDemo.fpp index c323acfe8c..5bbcd2d206 100644 --- a/RPI/RpiDemo/RpiDemo.fpp +++ b/RPI/RpiDemo/RpiDemo.fpp @@ -35,7 +35,7 @@ module RPI { async input port Run: Svc.Sched @ Input port for receiving UART data - async input port UartRead: Drv.SerialRead + async input port UartRead: Drv.ByteStreamRecv @ Output Port for reading GPIO values output port GpioRead: [2] Drv.GpioRead @@ -47,7 +47,7 @@ module RPI { output port GpioWrite: [3] Drv.GpioWrite @ Output Port for writing UART data - output port UartWrite: Drv.SerialWrite + output port UartWrite: Drv.ByteStreamSend @ Output port for sending UART buffers to use for reading output port UartBuffers: Fw.BufferSend diff --git a/RPI/RpiDemo/RpiDemoComponentImpl.cpp b/RPI/RpiDemo/RpiDemoComponentImpl.cpp index 901209f30b..618c27dfb2 100644 --- a/RPI/RpiDemo/RpiDemoComponentImpl.cpp +++ b/RPI/RpiDemo/RpiDemoComponentImpl.cpp @@ -54,13 +54,6 @@ namespace RPI { } void RpiDemoComponentImpl::preamble() { - // send buffers to UART driver - for (NATIVE_INT_TYPE buffer = 0; buffer < NUM_RPI_UART_BUFFERS; buffer++) { - // assign buffers to buffer containers - this->m_recvBuffers[buffer].setData(this->m_uartBuffers[buffer]); - this->m_recvBuffers[buffer].setSize(RPI_UART_READ_BUFF_SIZE); - this->UartBuffers_out(0, this->m_recvBuffers[buffer]); - } // check initial state parameter Fw::ParamValid valid; RpiDemo_LedState initState = paramGet_RD_PrmLedInitState(valid); @@ -122,26 +115,25 @@ namespace RPI { UartRead_handler( const NATIVE_INT_TYPE portNum, Fw::Buffer &serBuffer, - Drv::SerialReadStatus &status + const Drv::RecvStatus &status ) { - // convert incoming data to string. If it is not printable, set character to '*' - char uMsg[serBuffer.getSize()+1]; - char* bPtr = reinterpret_cast(serBuffer.getData()); - - for (NATIVE_UINT_TYPE byte = 0; byte < serBuffer.getSize(); byte++) { - uMsg[byte] = isalpha(bPtr[byte])?bPtr[byte]:'*'; - } - uMsg[sizeof(uMsg)-1] = 0; + if (Drv::RecvStatus::RECV_OK == status.e) { + // convert incoming data to string. If it is not printable, set character to '*' + char uMsg[serBuffer.getSize() + 1]; + char *bPtr = reinterpret_cast(serBuffer.getData()); - Fw::LogStringArg evrMsg(uMsg); - this->log_ACTIVITY_HI_RD_UartMsgIn(evrMsg); - this->m_lastUartMsg = uMsg; - this->m_uartReadBytes += serBuffer.getSize(); + for (NATIVE_UINT_TYPE byte = 0; byte < serBuffer.getSize(); byte++) { + uMsg[byte] = isalpha(bPtr[byte]) ? bPtr[byte] : '*'; + } + uMsg[sizeof(uMsg) - 1] = 0; - // reset buffer size - serBuffer.setSize(RPI_UART_READ_BUFF_SIZE); - // return buffer to driver + Fw::LogStringArg evrMsg(uMsg); + this->log_ACTIVITY_HI_RD_UartMsgIn(evrMsg); + this->m_lastUartMsg = uMsg; + this->m_uartReadBytes += serBuffer.getSize(); + } + // return buffer to buffer manager this->UartBuffers_out(0, serBuffer); } @@ -159,12 +151,13 @@ namespace RPI { Fw::Buffer txt; txt.setSize(text.length()); txt.setData(reinterpret_cast(const_cast(text.toChar()))); - this->UartWrite_out(0, txt); - this->m_uartWriteBytes += text.length(); - - Fw::LogStringArg arg = text; - this->log_ACTIVITY_HI_RD_UartMsgOut(arg); + Drv::SendStatus status = this->UartWrite_out(0, txt); + if (Drv::SendStatus::SEND_OK == status.e) { + this->m_uartWriteBytes += text.length(); + Fw::LogStringArg arg = text; + this->log_ACTIVITY_HI_RD_UartMsgOut(arg); + } this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); } diff --git a/RPI/RpiDemo/RpiDemoComponentImpl.hpp b/RPI/RpiDemo/RpiDemoComponentImpl.hpp index da42773048..7c02977b27 100644 --- a/RPI/RpiDemo/RpiDemoComponentImpl.hpp +++ b/RPI/RpiDemo/RpiDemoComponentImpl.hpp @@ -75,7 +75,7 @@ namespace RPI { void UartRead_handler( const NATIVE_INT_TYPE portNum, /*!< The port number*/ Fw::Buffer &serBuffer, /*!< Buffer containing data*/ - Drv::SerialReadStatus &status /*!< Status of read*/ + const Drv::RecvStatus &status /*!< Status of read*/ ) override; PRIVATE: diff --git a/RPI/Top/instances.fpp b/RPI/Top/instances.fpp index 39cfec4c38..e5086b25ed 100644 --- a/RPI/Top/instances.fpp +++ b/RPI/Top/instances.fpp @@ -312,16 +312,15 @@ module RPI { instance textLogger: Svc.PassiveTextLogger base id 1900 - instance uartDrv: Drv.LinuxSerialDriver base id 2000 \ + instance uartDrv: Drv.LinuxUartDriver base id 2000 \ { phase Fpp.ToCpp.Phases.configComponents """ { const bool status = uartDrv.open("/dev/serial0", - Drv::LinuxSerialDriverComponentImpl::BAUD_19200, - Drv::LinuxSerialDriverComponentImpl::NO_FLOW, - Drv::LinuxSerialDriverComponentImpl::PARITY_NONE, - true + Drv::LinuxUartDriver::BAUD_19200, + Drv::LinuxUartDriver::NO_FLOW, + Drv::LinuxUartDriver::PARITY_NONE ); if (!status) { Fw::Logger::logMsg("[ERROR] Could not open UART driver\\n"); @@ -435,4 +434,38 @@ module RPI { } + instance uartBufferManager: Svc.BufferManager base id 2800 \ + { + + phase Fpp.ToCpp.Phases.configConstants """ + enum { + STORE_SIZE = 3000, + QUEUE_SIZE = 30, + MGR_ID = 300 + }; + """ + + phase Fpp.ToCpp.Phases.configComponents """ + { + Svc::BufferManager::BufferBins bufferBins; + memset(&bufferBins, 0, sizeof(bufferBins)); + using namespace ConfigConstants::uartBufferManager; + bufferBins.bins[0].bufferSize = STORE_SIZE; + bufferBins.bins[0].numBuffers = QUEUE_SIZE; + uartBufferManager.setup( + MGR_ID, + 0, + Allocation::mallocator, + // OK to supply a local object here: BufferManager makes a copy + bufferBins + ); + } + """ + + phase Fpp.ToCpp.Phases.tearDownComponents """ + uartBufferManager.cleanup(); + """ + } + + } diff --git a/RPI/Top/topology.fpp b/RPI/Top/topology.fpp index d54e3a1630..ba61be34b7 100644 --- a/RPI/Top/topology.fpp +++ b/RPI/Top/topology.fpp @@ -35,6 +35,7 @@ module RPI { instance textLogger instance uartDrv instance uplink + instance uartBufferManager # ---------------------------------------------------------------------- # Pattern graph specifiers @@ -121,9 +122,10 @@ module RPI { } connections UART { - rpiDemo.UartBuffers -> uartDrv.readBufferSend - rpiDemo.UartWrite -> uartDrv.serialSend - uartDrv.serialRecv -> rpiDemo.UartRead + rpiDemo.UartBuffers -> uartBufferManager.bufferSendIn + rpiDemo.UartWrite -> uartDrv.send + uartDrv.$recv -> rpiDemo.UartRead + uartDrv.allocate -> uartBufferManager.bufferGetCallee } connections Uplink { diff --git a/config/LinuxSerialDriverComponentImplCfg.hpp b/config/LinuxSerialDriverComponentImplCfg.hpp deleted file mode 100644 index f703e19c9c..0000000000 --- a/config/LinuxSerialDriverComponentImplCfg.hpp +++ /dev/null @@ -1,15 +0,0 @@ -/* - * LinuxSerialDriverComponentImplCfg.hpp - * - * Created on: Nov 29, 2016 - * Author: tcanham - */ - -#ifndef LINUXSERIALDRIVER_BLSPSERIALDRIVERCOMPONENTIMPLCFG_HPP_ -#define LINUXSERIALDRIVER_BLSPSERIALDRIVERCOMPONENTIMPLCFG_HPP_ - -enum { - DR_MAX_NUM_BUFFERS = 20, // Increasing this from 10 b/c RceAdapter couldn't always keep up with just 10 for reads -}; - -#endif /* LINUXSERIALDRIVER_BLSPSERIALDRIVERCOMPONENTIMPLCFG_HPP_ */ diff --git a/config/LinuxUartDriverCfg.hpp b/config/LinuxUartDriverCfg.hpp new file mode 100644 index 0000000000..b2b3bd326d --- /dev/null +++ b/config/LinuxUartDriverCfg.hpp @@ -0,0 +1,16 @@ +/* + * LinuxSerialDriverComponentImplCfg.hpp + * + * Created on: Nov 29, 2016 + * Author: tcanham + */ + +#ifndef DRV_LINUXUARTDRIVER_CFG_HPP_ +#define DRV_LINUXUARTDRIVER_CFG_HPP_ + +namespace Drv { +enum UartDriverConfig { + UART_READ_ALLOCATION_REQUEST_SIZE = 1024, // Size of requests on allocation port +}; +}; +#endif /* DRV_LINUXUARTDRIVER_CFG_HPP_ */ From 6822a4fd2118652dc316eb8d2f2ef3aa7eac83ba Mon Sep 17 00:00:00 2001 From: M Starch Date: Sun, 7 Aug 2022 20:07:27 -0700 Subject: [PATCH 046/169] lestarch: adding baud rate values to enum and fixing read size int buffer (#1610) * lestarch: adding baud rate values to enum and fixing read size int buffer * lestarch: moving configuration into open call --- Drv/LinuxUartDriver/LinuxUartDriver.cpp | 15 +++++++-------- Drv/LinuxUartDriver/LinuxUartDriver.hpp | 6 +++--- RPI/Top/instances.fpp | 3 ++- config/LinuxUartDriverCfg.hpp | 16 ---------------- 4 files changed, 12 insertions(+), 28 deletions(-) delete mode 100644 config/LinuxUartDriverCfg.hpp diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.cpp b/Drv/LinuxUartDriver/LinuxUartDriver.cpp index 5ef78a26df..6a6aeffddb 100644 --- a/Drv/LinuxUartDriver/LinuxUartDriver.cpp +++ b/Drv/LinuxUartDriver/LinuxUartDriver.cpp @@ -32,7 +32,7 @@ namespace Drv { // ---------------------------------------------------------------------- LinuxUartDriver ::LinuxUartDriver(const char* const compName) - : LinuxUartDriverComponentBase(compName), m_fd(-1), m_device("NOT_EXIST"), m_quitReadThread(false) { + : LinuxUartDriverComponentBase(compName), m_fd(-1), m_allocationSize(-1), m_device("NOT_EXIST"), m_quitReadThread(false) { } void LinuxUartDriver ::init(const NATIVE_INT_TYPE instance) { @@ -42,10 +42,12 @@ void LinuxUartDriver ::init(const NATIVE_INT_TYPE instance) { bool LinuxUartDriver::open(const char* const device, UartBaudRate baud, UartFlowControl fc, - UartParity parity) { + UartParity parity, + NATIVE_INT_TYPE allocationSize) { FW_ASSERT(device != nullptr); NATIVE_INT_TYPE fd = -1; NATIVE_INT_TYPE stat = -1; + this->m_allocationSize = allocationSize; this->m_device = device; @@ -309,12 +311,8 @@ void LinuxUartDriver ::serialReadTaskEntry(void* ptr) { FW_ASSERT(ptr != nullptr); Drv::RecvStatus status = RecvStatus::RECV_ERROR; // added by m.chase 03.06.2017 LinuxUartDriver* comp = reinterpret_cast(ptr); - while (!comp->m_quitReadThread) { - // wait for data - int sizeRead = 0; - - Fw::Buffer buff = comp->allocate_out(0, Drv::UART_READ_ALLOCATION_REQUEST_SIZE); + Fw::Buffer buff = comp->allocate_out(0, comp->m_allocationSize); // On failed allocation, error and deallocate if (buff.getData() == nullptr) { @@ -338,6 +336,7 @@ void LinuxUartDriver ::serialReadTaskEntry(void* ptr) { while ((stat == 0) && !comp->m_quitReadThread) { stat = ::read(comp->m_fd, buff.getData(), buff.getSize()); } + buff.setSize(0); // On error stat (-1) must mark the read as error // On normal stat (>0) pass a recv ok @@ -347,7 +346,7 @@ void LinuxUartDriver ::serialReadTaskEntry(void* ptr) { comp->log_WARNING_HI_ReadError(_arg, stat); status = RecvStatus::RECV_ERROR; } else if (stat > 0) { - buff.setSize(sizeRead); + buff.setSize(stat); status = RecvStatus::RECV_OK; // added by m.chase 03.06.2017 } else { status = RecvStatus::RECV_ERROR; // Simply to return the buffer diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.hpp b/Drv/LinuxUartDriver/LinuxUartDriver.hpp index 2beaedc81c..5786c3c1a5 100644 --- a/Drv/LinuxUartDriver/LinuxUartDriver.hpp +++ b/Drv/LinuxUartDriver/LinuxUartDriver.hpp @@ -14,7 +14,6 @@ #define LinuxUartDriver_HPP #include -#include #include #include @@ -37,14 +36,14 @@ class LinuxUartDriver : public LinuxUartDriverComponentBase { ); //! Configure UART parameters - enum UartBaudRate { BAUD_9600, BAUD_19200, BAUD_38400, BAUD_57600, BAUD_115K, BAUD_230K, BAUD_460K, BAUD_921K }; + enum UartBaudRate { BAUD_9600=9600, BAUD_19200=19200, BAUD_38400=38400, BAUD_57600=57600, BAUD_115K=115200, BAUD_230K=230400, BAUD_460K=460800, BAUD_921K=921600}; enum UartFlowControl { NO_FLOW, HW_FLOW }; enum UartParity { PARITY_NONE, PARITY_ODD, PARITY_EVEN }; // Open device with specified baud and flow control. - bool open(const char* const device, UartBaudRate baud, UartFlowControl fc, UartParity parity); + bool open(const char* const device, UartBaudRate baud, UartFlowControl fc, UartParity parity, NATIVE_INT_TYPE allocationSize); //! start the serial poll thread. //! buffSize is the max receive buffer size @@ -72,6 +71,7 @@ class LinuxUartDriver : public LinuxUartDriverComponentBase { NATIVE_INT_TYPE m_fd; //!< file descriptor returned for I/O device + NATIVE_INT_TYPE m_allocationSize; //!< size of allocation request to memory manager const char* m_device; //!< original device path //! This method will be called by the new thread to wait for input on the serial port. diff --git a/RPI/Top/instances.fpp b/RPI/Top/instances.fpp index e5086b25ed..8157c439fe 100644 --- a/RPI/Top/instances.fpp +++ b/RPI/Top/instances.fpp @@ -320,7 +320,8 @@ module RPI { const bool status = uartDrv.open("/dev/serial0", Drv::LinuxUartDriver::BAUD_19200, Drv::LinuxUartDriver::NO_FLOW, - Drv::LinuxUartDriver::PARITY_NONE + Drv::LinuxUartDriver::PARITY_NONE, + 1024 ); if (!status) { Fw::Logger::logMsg("[ERROR] Could not open UART driver\\n"); diff --git a/config/LinuxUartDriverCfg.hpp b/config/LinuxUartDriverCfg.hpp deleted file mode 100644 index b2b3bd326d..0000000000 --- a/config/LinuxUartDriverCfg.hpp +++ /dev/null @@ -1,16 +0,0 @@ -/* - * LinuxSerialDriverComponentImplCfg.hpp - * - * Created on: Nov 29, 2016 - * Author: tcanham - */ - -#ifndef DRV_LINUXUARTDRIVER_CFG_HPP_ -#define DRV_LINUXUARTDRIVER_CFG_HPP_ - -namespace Drv { -enum UartDriverConfig { - UART_READ_ALLOCATION_REQUEST_SIZE = 1024, // Size of requests on allocation port -}; -}; -#endif /* DRV_LINUXUARTDRIVER_CFG_HPP_ */ From cd61f1322ffad14dda69dd384393d70dc788b8f5 Mon Sep 17 00:00:00 2001 From: Simon Waldherr Date: Mon, 15 Aug 2022 23:28:22 +0200 Subject: [PATCH 047/169] fix dead links to CCSDS 727.0-B-4 standard document (#1614) * fix dead links to the CCSDS 727.0-B-4 standard document CCSDS 727.0-B-4 is now a historical document and available at https://public.ccsds.org/Pubs/727x0b4s.pdf since july 2020 the new CCSDS 727.0-B-5 is vaild and available at https://public.ccsds.org/Pubs/727x0b5.pdf * Update sdd.md --- Fw/FilePacket/docs/sdd.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Fw/FilePacket/docs/sdd.md b/Fw/FilePacket/docs/sdd.md index 99ca1e1dd2..544333e9f8 100644 --- a/Fw/FilePacket/docs/sdd.md +++ b/Fw/FilePacket/docs/sdd.md @@ -11,7 +11,7 @@ It represents an ISF file packet. The file packet format is similar to the Protocol Data Unit (PDU) format defined in the CCSDS File Delivery Protocol (CFDP). See § 5 of the -[CCSDS File Delivery Protocol (CFDP) Recommended Standard](http://public.ccsds.org/publications/archive/727x0b4.pdf). +[CCSDS File Delivery Protocol (CFDP) Recommended Standard](https://public.ccsds.org/Pubs/727x0b4s.pdf). Each file packet contains the following data: From 6a2e0d1f42c33f6c8c197946d8f6d990070f44a5 Mon Sep 17 00:00:00 2001 From: Ani Date: Mon, 15 Aug 2022 18:08:21 -0700 Subject: [PATCH 048/169] Remove extern "C" { ... } construct in FakeLogger (#1613) --- Fw/Logger/test/ut/FakeLogger.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Fw/Logger/test/ut/FakeLogger.cpp b/Fw/Logger/test/ut/FakeLogger.cpp index 866a373392..f4652d4dc1 100644 --- a/Fw/Logger/test/ut/FakeLogger.cpp +++ b/Fw/Logger/test/ut/FakeLogger.cpp @@ -9,9 +9,6 @@ #include #include -extern "C" { - #include -} namespace MockLogging { Fw::Logger* FakeLogger::s_current = nullptr; @@ -85,4 +82,4 @@ namespace MockLogging { m_last.a8 = 0; m_last.a9 = 0; } -} \ No newline at end of file +} From f339118a25694df6902cbc4cbcbf9d930ca03af9 Mon Sep 17 00:00:00 2001 From: Ani Date: Mon, 15 Aug 2022 18:08:57 -0700 Subject: [PATCH 049/169] Minor refactoring for LoggerRules.cpp (#1609) * Use an array for the ten platform specific ints that get a random U32 assigned within the range (0, 0xffffffff) * Fix numerals representing the arg count --- Fw/Logger/test/ut/LoggerRules.cpp | 89 ++++++++++++++----------------- 1 file changed, 39 insertions(+), 50 deletions(-) diff --git a/Fw/Logger/test/ut/LoggerRules.cpp b/Fw/Logger/test/ut/LoggerRules.cpp index 3e54f3ad79..547f44f181 100644 --- a/Fw/Logger/test/ut/LoggerRules.cpp +++ b/Fw/Logger/test/ut/LoggerRules.cpp @@ -50,60 +50,55 @@ namespace LoggerRules { // Log valid messages void LogGood::action(MockLogging::FakeLogger& truth) { NATIVE_INT_TYPE random = STest::Pick::lowerUpper(0, 10); - NATIVE_INT_TYPE ra1 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra2 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra3 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra4 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra5 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra6 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra7 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra8 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra9 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra10 = STest::Pick::lowerUpper(0, 0xffffffff); + NATIVE_INT_TYPE ra[10]; + for (int i = 0; i < 10; ++i) { + ra[i] = STest::Pick::lowerUpper(0, 0xffffffff); + } + switch (random) { case 0: Fw::Logger::logMsg("No args"); truth.check("No args"); break; case 1: - Fw::Logger::logMsg("One arg: %lu", ra1); - truth.check("One arg: %lu", ra1); + Fw::Logger::logMsg("One arg: %lu", ra[0]); + truth.check("One arg: %lu", ra[0]); break; case 2: - Fw::Logger::logMsg("Two arg: %lu", ra1, ra2); - truth.check("Two arg: %lu", ra1, ra2); + Fw::Logger::logMsg("Two arg: %lu", ra[0], ra[1]); + truth.check("Two arg: %lu", ra[0], ra[1]); break; case 3: - Fw::Logger::logMsg("Three arg: %lu", ra1, ra2, ra3); - truth.check("Three arg: %lu", ra1, ra2, ra3); + Fw::Logger::logMsg("Three arg: %lu", ra[0], ra[1], ra[2]); + truth.check("Three arg: %lu", ra[0], ra[1], ra[2]); break; case 4: - Fw::Logger::logMsg("Four arg: %lu", ra1, ra2, ra3, ra4); - truth.check("Four arg: %lu", ra1, ra2, ra3, ra4); + Fw::Logger::logMsg("Four arg: %lu", ra[0], ra[1], ra[2], ra[3]); + truth.check("Four arg: %lu", ra[0], ra[1], ra[2], ra[3]); break; case 5: - Fw::Logger::logMsg("Five arg: %lu", ra1, ra2, ra3, ra4, ra5); - truth.check("Five arg: %lu", ra1, ra2, ra3, ra4, ra5); + Fw::Logger::logMsg("Five arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4]); + truth.check("Five arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4]); break; case 6: - Fw::Logger::logMsg("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6); - truth.check("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6); + Fw::Logger::logMsg("Six arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5]); + truth.check("Six arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5]); break; case 7: - Fw::Logger::logMsg("Seven arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7); - truth.check("Seven arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7); + Fw::Logger::logMsg("Seven arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6]); + truth.check("Seven arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6]); break; case 8: - Fw::Logger::logMsg("Eight arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8); - truth.check("Eight arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8); + Fw::Logger::logMsg("Eight arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7]); + truth.check("Eight arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7]); break; case 9: - Fw::Logger::logMsg("Nine arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8, ra9); - truth.check("Nine arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8, ra9); + Fw::Logger::logMsg("Nine arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7], ra[8]); + truth.check("Nine arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7], ra[8]); break; case 10: - Fw::Logger::logMsg("Ten arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8, ra9, ra10); - truth.check("Ten arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8, ra9, ra10); + Fw::Logger::logMsg("Ten arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7], ra[8], ra[9]); + truth.check("Ten arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7], ra[8], ra[9]); break; default: @@ -123,16 +118,10 @@ namespace LoggerRules { // Log valid messages void LogBad::action(MockLogging::FakeLogger& truth) { NATIVE_INT_TYPE random = STest::Pick::lowerUpper(0, 10); - NATIVE_INT_TYPE ra1 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra2 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra3 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra4 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra5 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra6 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra7 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra8 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra9 = STest::Pick::lowerUpper(0, 0xffffffff); - NATIVE_INT_TYPE ra10 = STest::Pick::lowerUpper(0, 0xffffffff); + NATIVE_INT_TYPE ra[10]; + for (int i = 0; i < 10; ++i) { + ra[i] = STest::Pick::lowerUpper(0, 0xffffffff); + } switch (random) { case 0: @@ -140,43 +129,43 @@ namespace LoggerRules { truth.check(nullptr); break; case 1: - Fw::Logger::logMsg("One arg: %lu", ra1); + Fw::Logger::logMsg("One arg: %lu", ra[0]); truth.check(nullptr); break; case 2: - Fw::Logger::logMsg("Two arg: %lu", ra1, ra2); + Fw::Logger::logMsg("Two arg: %lu", ra[0], ra[1]); truth.check(nullptr); break; case 3: - Fw::Logger::logMsg("Three arg: %lu", ra1, ra2, ra3); + Fw::Logger::logMsg("Three arg: %lu", ra[0], ra[1], ra[2]); truth.check(nullptr); break; case 4: - Fw::Logger::logMsg("Four arg: %lu", ra1, ra2, ra3, ra4); + Fw::Logger::logMsg("Four arg: %lu", ra[0], ra[1], ra[2], ra[3]); truth.check(nullptr); break; case 5: - Fw::Logger::logMsg("Five arg: %lu", ra1, ra2, ra3, ra4, ra5); + Fw::Logger::logMsg("Five arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4]); truth.check(nullptr); break; case 6: - Fw::Logger::logMsg("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6); + Fw::Logger::logMsg("Six arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5]); truth.check(nullptr); break; case 7: - Fw::Logger::logMsg("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7); + Fw::Logger::logMsg("Seven arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6]); truth.check(nullptr); break; case 8: - Fw::Logger::logMsg("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8); + Fw::Logger::logMsg("Eight arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7]); truth.check(nullptr); break; case 9: - Fw::Logger::logMsg("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8, ra9); + Fw::Logger::logMsg("Nine arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7], ra[8]); truth.check(nullptr); break; case 10: - Fw::Logger::logMsg("Six arg: %lu", ra1, ra2, ra3, ra4, ra5, ra6, ra7, ra8, ra9, ra10); + Fw::Logger::logMsg("Ten arg: %lu", ra[0], ra[1], ra[2], ra[3], ra[4], ra[5], ra[6], ra[7], ra[8], ra[9]); truth.check(nullptr); break; default: From 2344ecce13998679f2106c06edd8013f60e18d28 Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 16 Aug 2022 13:44:19 -0700 Subject: [PATCH 050/169] Update INSTALL.md (#1618) --- docs/INSTALL.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/INSTALL.md b/docs/INSTALL.md index b1f502afad..bfc45c0d85 100644 --- a/docs/INSTALL.md +++ b/docs/INSTALL.md @@ -22,7 +22,7 @@ Requirements: 1. Linux or macOS operating system 2. git 3. [CMake 3.16](https://cmake.org/download/) or newer. CLI tool must be available on the system path. -4. CLang or GCC compiler +4. CLang or GNU C and C++ compilers (e.g. gcc and g++) 5. [Python 3.7+](https://www.python.org/downloads/), virtual environments, and PIP **Note:** operating system specific notes are in the [Troubleshooting](#Troubleshooting) section below. From 892df7f5ff029b6f113b118d15dde6ce221f2918 Mon Sep 17 00:00:00 2001 From: M Starch Date: Wed, 17 Aug 2022 13:09:25 -0700 Subject: [PATCH 051/169] lestarch: returning open error rather than asserting when I2C driver fails to open (#1619) --- Drv/I2cDriverPorts/I2cDriverPorts.fpp | 3 ++- Drv/LinuxI2cDriver/LinuxI2cDriver.cpp | 13 ++++++++++--- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/Drv/I2cDriverPorts/I2cDriverPorts.fpp b/Drv/I2cDriverPorts/I2cDriverPorts.fpp index a540e7e1c0..6ceee79157 100644 --- a/Drv/I2cDriverPorts/I2cDriverPorts.fpp +++ b/Drv/I2cDriverPorts/I2cDriverPorts.fpp @@ -16,7 +16,8 @@ module Drv { I2C_ADDRESS_ERR = 1 @< I2C address invalid I2C_WRITE_ERR = 2 @< I2C write failed I2C_READ_ERR = 3 @< I2C read failed - I2C_OTHER_ERR = 4 @< Other errors that don't fit + I2C_OPEN_ERR = 4 @< I2C driver failed to open device + I2C_OTHER_ERR = 5 @< Other errors that don't fit } } diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp index b821dd44a0..49af977849 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp @@ -76,7 +76,9 @@ namespace Drv { ) { // Make sure file has been opened - FW_ASSERT(-1 != this->m_fd); + if (-1 == this->m_fd) { + return I2cStatus::I2C_OPEN_ERR; + } #if DEBUG_PRINT Fw::Logger::logMsg("I2c addr: 0x%02X\n",addr); @@ -115,7 +117,9 @@ namespace Drv { ) { // Make sure file has been opened - FW_ASSERT(-1 != this->m_fd); + if (-1 == this->m_fd) { + return I2cStatus::I2C_OPEN_ERR; + } #if DEBUG_PRINT Fw::Logger::logMsg("I2c addr: 0x%02X\n",addr); @@ -157,6 +161,9 @@ namespace Drv { ){ // Make sure file has been opened + if (-1 == this->m_fd) { + return I2cStatus::I2C_OPEN_ERR; + } FW_ASSERT(-1 != this->m_fd); // make sure they are not null pointers @@ -195,7 +202,7 @@ namespace Drv { Fw::Logger::logMsg("Status: %d Errno: %d\n", stat, errno); #endif //Because we're using ioctl to perform the transaction we dont know exactly the type of error that occurred - return Drv::I2cStatus::I2C_OTHER_ERR; + return I2cStatus::I2C_OTHER_ERR; } #if DEBUG_PRINT From b76d8c9a0c0e2317c211dd6c3ef33b11538c79e3 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 18 Aug 2022 13:25:56 -0700 Subject: [PATCH 052/169] Update/types refactor as constants (#1623) * lestarch: adding logical types implementation into Linux/StandardTypes.hpp * lestarch: removing VxWorks StandardTypes from repository * updated fprime types for correct compilation with vxworks and baremetal * lestarch: refactoring types and configuration header w.r.t type design * lestarch: replacing usages of AssertArg with FwAssertArgType * lestarch: missspelled configuration * lestarch: minor compilation fixes * lestarch: renaming StandardTypes.hpp -> PlatformTypes.hpp * lestarch: updating PRI tokens * lestarch: replacing BasicTypes.hpp includes with FpConfig.hpp * lestarch: UT and compilation fixes for types refactor * lestarch: sp * lestarch: fixing RPI issues in PassiveConsoleTextLogger * lestarch: converting RPI build to debug * lestarch: removing duplicate config imports * lestarch: fixing documentation * lestarch: fixing up multiple definitions and RPI compilation problems * lestarch: reverting debug build * lestarch: reverting platform types to class-based constants * lestarch: reworking basic types * lestarch: configured types refactor into classes * lestarch: fixing bugs with static constants in classes * lestarch: fixing platform types spelling and documentation * lestarch: adding include guards to types headers Co-authored-by: Kevin F Ortega --- .github/actions/spelling/expect.txt | 1 + Autocoders/Python/bin/tlm_packet_gen.py | 2 +- .../templates/arrays/array_hpp.tmpl | 2 +- .../generators/templates/component/cpp.tmpl | 92 +++++------ .../generators/templates/enums/enum_hpp.tmpl | 2 +- .../generators/templates/impl/cpp.tmpl | 2 +- .../templates/port/finishPortCpp.tmpl | 4 +- .../templates/port/includes1PortH.tmpl | 2 +- .../serialize/includes1SerialCpp.tmpl | 2 +- .../templates/serialize/includes1SerialH.tmpl | 2 +- .../generators/templates/test/cpp.tmpl | 38 ++--- Autocoders/Python/templates/ExampleType.hpp | 2 +- .../test/array_xml/ExampleArrayImpl.cpp | 2 +- .../Python/test/array_xml/test/ut/main.cpp | 2 +- .../command2/TestCommandComponentImpl.cpp | 2 +- .../test/command_res/Test1ComponentImpl.cpp | 2 +- .../test/enum1port/DrvTimingSignalPort.hpp | 2 +- .../Python/test/enum_xml/Component1Impl.cpp | 2 +- Autocoders/Python/test/enum_xml/main.cpp | 12 +- .../Python/test/ext_dict/ExampleType.hpp | 2 +- .../MathSenderComponentImpl_cpp-template.txt | 2 +- .../Python/test/interface1/SomeStruct.hpp | 2 +- .../Python/test/interface1/UserSerializer.hpp | 2 +- .../test/noargport/ExampleComponentImpl.cpp | 2 +- .../Python/test/partition/DuckDuckImpl.cpp | 2 +- .../Python/test/partition/PartitionImpl.cpp | 2 +- .../Python/test/pass_by_attrib/Msg1Port.hpp | 2 +- .../Python/test/pass_by_kind/Component1.cpp | 2 +- .../port_loopback/ExampleComponentImpl.cpp | 2 +- .../Python/test/port_loopback/ExampleType.hpp | 2 +- .../Python/test/port_nogen/ExampleType.hpp | 2 +- .../test/serial_passive/TestSerialImpl.cpp | 2 +- .../Python/test/serialize_user/SomeStruct.hpp | 2 +- .../test/serialize_user/UserSerializer.hpp | 2 +- .../test/testgen/MathSenderComponentImpl.cpp | 2 +- CFDP/Checksum/Checksum.hpp | 2 +- Drv/BlockDriver/BlockDriverImpl.cpp | 2 +- Drv/DataTypes/DataBuffer.hpp | 2 +- Drv/Ip/IpSocket.cpp | 2 +- Drv/Ip/IpSocket.hpp | 2 +- Drv/Ip/TcpClientSocket.cpp | 2 +- Drv/Ip/TcpClientSocket.hpp | 2 +- Drv/Ip/TcpServerSocket.cpp | 2 +- Drv/Ip/TcpServerSocket.hpp | 2 +- Drv/Ip/UdpSocket.cpp | 2 +- Drv/Ip/UdpSocket.hpp | 2 +- Drv/Ip/test/ut/PortSelector.hpp | 2 +- Drv/Ip/test/ut/SocketTestHelper.hpp | 2 +- .../LinuxGpioDriverComponentImpl.cpp | 2 +- .../LinuxGpioDriverComponentImplCommon.cpp | 2 +- .../LinuxGpioDriverComponentImplStub.cpp | 2 +- Drv/LinuxI2cDriver/LinuxI2cDriver.cpp | 2 +- Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp | 2 +- .../LinuxSpiDriverComponentImpl.cpp | 2 +- .../LinuxSpiDriverComponentImplCommon.cpp | 2 +- .../LinuxSpiDriverComponentImplStub.cpp | 2 +- Drv/TcpClient/TcpClientComponentImpl.cpp | 2 +- Drv/TcpServer/TcpServerComponentImpl.cpp | 2 +- Drv/Udp/UdpComponentImpl.cpp | 2 +- Fw/Buffer/Buffer.cpp | 2 +- Fw/Buffer/Buffer.hpp | 2 +- Fw/Buffer/test/ut/TestBuffer.cpp | 2 +- Fw/Cfg/ConfigCheck.cpp | 1 - Fw/Cmd/CmdArgBuffer.hpp | 3 +- Fw/Cmd/CmdString.hpp | 3 +- Fw/Com/ComBuffer.hpp | 1 - Fw/FilePacket/FilePacket.hpp | 2 +- Fw/Log/LogBuffer.hpp | 1 - Fw/Log/LogString.hpp | 3 +- Fw/Log/TextLogString.hpp | 3 +- Fw/Logger/LogAssert.cpp | 12 +- Fw/Logger/LogAssert.hpp | 12 +- Fw/Logger/Logger.hpp | 2 +- Fw/Logger/test/ut/FakeLogger.hpp | 2 +- Fw/Logger/test/ut/LoggerRules.hpp | 2 +- Fw/Obj/ObjBase.hpp | 1 - Fw/Obj/SimpleObjRegistry.hpp | 1 - Fw/Port/InputPortBase.cpp | 2 - Fw/Port/InputPortBase.hpp | 2 - Fw/Port/OutputPortBase.cpp | 2 - Fw/Port/OutputPortBase.hpp | 2 - Fw/Port/PortBase.cpp | 2 +- Fw/Port/PortBase.hpp | 2 +- Fw/Prm/PrmBuffer.hpp | 1 - Fw/Prm/PrmString.hpp | 3 +- Fw/SerializableFile/test/ut/Test.cpp | 2 +- Fw/Test/String.hpp | 2 +- Fw/Test/UnitTestAssert.cpp | 28 ++-- Fw/Test/UnitTestAssert.hpp | 36 ++-- Fw/Time/Time.cpp | 2 +- Fw/Time/Time.hpp | 3 +- Fw/Tlm/TlmBuffer.hpp | 1 - Fw/Tlm/TlmString.hpp | 3 +- Fw/Trap/TrapHandler.hpp | 1 - Fw/Types/Assert.cpp | 70 ++++---- Fw/Types/Assert.hpp | 25 ++- Fw/Types/BasicTypes.hpp | 109 ++++++------ Fw/Types/ByteArray.hpp | 2 +- Fw/Types/CAssert.hpp | 1 - Fw/Types/CMakeLists.txt | 5 +- Fw/Types/ConstByteArray.hpp | 2 +- Fw/Types/EightyCharString.hpp | 2 +- Fw/Types/GTest/Bytes.hpp | 2 +- Fw/Types/InternalInterfaceString.hpp | 3 +- Fw/Types/Linux/StandardTypes.hpp | 2 - Fw/Types/MemAllocator.hpp | 2 +- Fw/Types/PolyType.cpp | 5 +- Fw/Types/PolyType.hpp | 3 +- Fw/Types/SerialBuffer.hpp | 2 +- Fw/Types/Serializable.cpp | 2 +- Fw/Types/Serializable.hpp | 2 +- Fw/Types/String.hpp | 2 +- Fw/Types/StringType.hpp | 2 +- Fw/Types/StringUtils.hpp | 2 +- Fw/Types/VxWorks/StandardTypes.hpp | 19 --- Fw/Types/default/DefaultTypes.hpp | 97 +++++++++++ Fw/Types/test/ut/TypesTest.cpp | 38 ++--- Os/Baremetal/File.cpp | 1 - Os/Baremetal/FileSystem.cpp | 1 - Os/Baremetal/Queue.cpp | 2 +- Os/Baremetal/TaskRunner/TaskRunner.cpp | 2 +- Os/Directory.hpp | 1 - Os/Event.hpp | 2 +- Os/File.hpp | 1 - Os/FileCommon.cpp | 1 - Os/FileSystem.hpp | 1 - Os/InterruptLock.hpp | 2 +- Os/IntervalTimer.hpp | 2 +- Os/Linux/Directory.cpp | 1 - Os/Linux/File.cpp | 1 - Os/Linux/FileSystem.cpp | 1 - Os/LocklessQueue.hpp | 2 +- Os/Log.hpp | 2 +- Os/Mem.hpp | 2 +- Os/Mutex.hpp | 2 +- Os/Pthreads/BufferQueue.hpp | 2 +- Os/Pthreads/MaxHeap/MaxHeap.cpp | 2 +- Os/Pthreads/MaxHeap/MaxHeap.hpp | 2 +- Os/Queue.hpp | 2 +- Os/QueueString.hpp | 3 +- Os/Stubs/Linux/FileStub.cpp | 1 - Os/SystemResources.hpp | 2 +- Os/Task.hpp | 1 - Os/TaskLock.hpp | 2 +- Os/TaskString.hpp | 3 +- Os/ValidatedFile.hpp | 2 +- Os/WatchdogTimer.hpp | 2 +- RPI/RpiDemo/RpiDemoComponentImpl.cpp | 2 +- .../PingReceiverComponentImpl.cpp | 2 +- Ref/RecvBuffApp/RecvBuffComponentImpl.cpp | 2 +- Ref/SendBuffApp/SendBuffComponentImpl.cpp | 2 +- Ref/Top/FppConstantsAc.hpp | 2 +- Svc/ActiveRateGroup/ActiveRateGroup.cpp | 2 +- Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp | 2 +- Svc/ActiveTextLogger/ActiveTextLoggerImpl.cpp | 6 +- Svc/ActiveTextLogger/LogFile.cpp | 2 +- .../AssertFatalAdapterComponentImpl.cpp | 38 ++--- .../AssertFatalAdapterComponentImpl.hpp | 24 +-- Svc/BufferAccumulator/ArrayFIFOBuffer.cpp | 2 +- Svc/BufferAccumulator/BufferAccumulator.cpp | 2 +- Svc/BufferAccumulator/test/ut/Tester.cpp | 2 +- .../BufferManagerComponentImpl.cpp | 2 +- Svc/ComLogger/ComLogger.cpp | 10 +- Svc/ComLogger/ComLogger.hpp | 9 +- Svc/ComSplitter/ComSplitter.cpp | 2 +- Svc/Deframer/Deframer.cpp | 2 +- .../ut-fprime-protocol/GenerateFrames.hpp | 2 +- .../test/ut-fprime-protocol/SendBuffer.hpp | 2 +- .../FatalHandlerComponentBaremetalImpl.cpp | 2 +- .../FatalHandlerComponentCommonImpl.cpp | 2 +- .../FatalHandlerComponentLinuxImpl.cpp | 2 +- .../FatalHandlerComponentVxWorksImpl.cpp | 2 +- Svc/FileDownlink/File.cpp | 2 +- Svc/FileDownlink/FileDownlink.cpp | 2 +- Svc/FileManager/FileManager.cpp | 2 +- Svc/FileUplink/FileUplink.cpp | 2 +- Svc/Framer/Framer.cpp | 2 +- Svc/GenericHub/GenericHubComponentImpl.cpp | 2 +- .../GenericRepeaterComponentImpl.cpp | 2 +- Svc/GroundInterface/GroundInterface.cpp | 2 +- Svc/GroundInterface/test/ut/DeframerRules.hpp | 2 +- .../test/ut/GroundInterfaceRules.hpp | 2 +- Svc/Health/HealthComponentImpl.cpp | 2 +- Svc/Health/Stub/HealthComponentStubChecks.cpp | 2 +- .../VxWorks/HealthComponentVxWorksChecks.cpp | 2 +- .../LinuxTimerComponentImplCommon.cpp | 2 +- .../LinuxTimerComponentImplTaskDelay.cpp | 2 +- .../LinuxTimerComponentImplTimerFd.cpp | 2 +- .../ConsoleTextLoggerImplCommon.cpp | 8 +- Svc/PolyDb/PolyDbImpl.cpp | 2 +- Svc/RateGroupDriver/RateGroupDriver.cpp | 2 +- Svc/RateGroupDriver/RateGroupDriver.hpp | 2 +- .../StaticMemoryComponentImpl.cpp | 2 +- Svc/SystemResources/SystemResources.cpp | 2 +- Svc/TlmChan/TlmChanImpl.cpp | 2 +- Svc/TlmChan/TlmChanImplGet.cpp | 2 +- Svc/TlmChan/TlmChanImplRecv.cpp | 2 +- Svc/TlmChan/TlmChanImplTask.cpp | 2 +- Svc/TlmPacketizer/TlmPacketizer.cpp | 2 +- .../TlmPacketizerComponentImplCfg.hpp | 2 +- Svc/UdpReceiver/UdpReceiverComponentImpl.cpp | 2 +- Svc/UdpSender/UdpSenderComponentImpl.cpp | 2 +- Utils/CRCChecker.hpp | 2 +- Utils/Hash/HashBuffer.hpp | 2 +- Utils/LockGuard.hpp | 2 +- Utils/RateLimiter.hpp | 2 +- Utils/TokenBucket.hpp | 2 +- Utils/Types/CircularBuffer.cpp | 2 +- Utils/Types/CircularBuffer.hpp | 1 - .../test/ut/CircularBuffer/CircularRules.hpp | 2 +- .../test/ut/CircularBuffer/CircularState.hpp | 2 +- Utils/test/ut/LockGuardTester.hpp | 2 +- Utils/test/ut/RateLimiterTester.hpp | 2 +- Utils/test/ut/TokenBucketTester.hpp | 2 +- ci/tests/RPI.bash | 2 +- cmake/platform/Darwin.cmake | 4 +- cmake/platform/Linux.cmake | 3 +- cmake/platform/platform.cmake.template | 6 +- cmake/platform/types/PlatformTypes.hpp | 129 +++++++++++++++ config/BufferManagerComponentImplCfg.hpp | 2 +- config/DeframerCfg.hpp | 2 +- config/FileDownlinkCfg.hpp | 2 +- config/FpConfig.hpp | 156 ++++++++++-------- config/UdpReceiverComponentImplCfg.hpp | 2 +- config/UdpSenderComponentImplCfg.hpp | 2 +- docs/Design/numerical-types.md | 95 ++++++----- docs/Tutorials/GpsTutorial/Tutorial.md | 2 +- .../MathReceiver/MathReceiver.cpp | 2 +- .../MathComponent/MathSender/MathSender.cpp | 2 +- docs/UsersGuide/cmake/cmake-platforms.md | 2 +- 230 files changed, 842 insertions(+), 641 deletions(-) delete mode 100644 Fw/Types/Linux/StandardTypes.hpp delete mode 100644 Fw/Types/VxWorks/StandardTypes.hpp create mode 100644 Fw/Types/default/DefaultTypes.hpp create mode 100644 cmake/platform/types/PlatformTypes.hpp diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index e1bc9d9d10..62c5b9d029 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -644,6 +644,7 @@ instrlen integertypename intlimits ints +Inttype inttype invisi ioc diff --git a/Autocoders/Python/bin/tlm_packet_gen.py b/Autocoders/Python/bin/tlm_packet_gen.py index f2d5d815d2..b1c82b0e07 100755 --- a/Autocoders/Python/bin/tlm_packet_gen.py +++ b/Autocoders/Python/bin/tlm_packet_gen.py @@ -63,7 +63,7 @@ \#include <${output_header}> \#include -\#include +\#include \#include // Verify packets not too large for ComBuffer diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/arrays/array_hpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/arrays/array_hpp.tmpl index 96c83429e1..2313b77de7 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/arrays/array_hpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/arrays/array_hpp.tmpl @@ -15,7 +15,7 @@ \#define ${namespace}_${name}_HPP \#include "Fw/Types/String.hpp" -\#include "Fw/Types/BasicTypes.hpp" +\#include \#include "Fw/Types/Serializable.hpp" #for $t in $include_headers: \#include <${t}> diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl index e475948005..0974c86792 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl @@ -131,7 +131,7 @@ namespace ${namespace} { #end if get_${instance}_InputPort(NATIVE_INT_TYPE portNum) { - FW_ASSERT(portNum < this->getNum_${instance}_InputPorts(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_${instance}_InputPorts(),static_cast(portNum)); return &this->m_${instance}_InputPort[portNum]; } @@ -157,7 +157,7 @@ namespace ${namespace} { #end if ) { - FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); #if $type == "Serial": this->m_${instance}_OutputPort[portNum].registerSerialPort(port); #else: @@ -189,7 +189,7 @@ namespace ${namespace} { #end if ) { - FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); return this->m_${instance}_OutputPort[portNum].registerSerialPort(port); } #if $role == "LogTextEvent": @@ -507,7 +507,7 @@ namespace ${namespace} { #end if FW_ASSERT( Os::Queue::QUEUE_OK == qStat, - static_cast(qStat) + static_cast(qStat) ); #end if @@ -538,7 +538,7 @@ namespace ${namespace} { Fw::SerializeBufferBase &Buffer ) { - FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); return this->m_${instance}_OutputPort[portNum].invokeSerial(Buffer); } #else @@ -552,7 +552,7 @@ namespace ${namespace} { ) { #end if - FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_${instance}_OutputPorts(),static_cast(portNum)); #if $void_return: this->m_${instance}_OutputPort[portNum].invoke($args); #else: @@ -596,7 +596,7 @@ namespace ${namespace} { { FW_ASSERT( portNum < this->getNum_${instance}_OutputPorts(), - static_cast(portNum) + static_cast(portNum) ); return this->m_${instance}_OutputPort[portNum].isConnected(); } @@ -813,7 +813,7 @@ namespace ${namespace} { #end if FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // Fake port number to make message dequeue work @@ -821,25 +821,25 @@ namespace ${namespace} { _status = msg.serialize(port); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); _status = msg.serialize(opCode); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); _status = msg.serialize(cmdSeq); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); _status = msg.serialize(args); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // send message @@ -859,7 +859,7 @@ namespace ${namespace} { #end if FW_ASSERT( qStatus == Os::Queue::QUEUE_OK, - static_cast(qStatus) + static_cast(qStatus) ); #end if @@ -925,7 +925,7 @@ namespace ${namespace} { #end if FW_ASSERT( _stat == Fw::FW_SERIALIZE_OK, - static_cast(_stat) + static_cast(_stat) ); FwChanIdType _id; @@ -1206,25 +1206,25 @@ namespace ${namespace} { _status = _logBuff.serialize(static_cast($len($args)+1)); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // For FATAL, add stack size of 4 and a dummy entry. No support for stacks yet. _status = _logBuff.serialize(static_cast(4)); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); _status = _logBuff.serialize(static_cast(0)); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #else // Serialize the number of arguments _status = _logBuff.serialize(static_cast($len($args))); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #end if \#endif @@ -1235,7 +1235,7 @@ namespace ${namespace} { _zero_status = _logBuff.serialize(static_cast(0)); FW_ASSERT( _zero_status == Fw::FW_SERIALIZE_OK, - static_cast(_zero_status) + static_cast(_zero_status) ); \#endif #end if @@ -1247,7 +1247,7 @@ namespace ${namespace} { _status = _logBuff.serialize(static_cast(sizeof(FwEnumStoreType))); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); \#endif @@ -1264,14 +1264,14 @@ namespace ${namespace} { ); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); \#endif _status = _logBuff.serialize($arg_name); #end if FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #end for @@ -1369,14 +1369,14 @@ namespace ${namespace} { _status = msg.serialize(static_cast(INT_IF_${ifname.upper})); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // Fake port number to make message dequeue work _status = msg.serialize(static_cast(0)); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #for $argname, $argtype, $comment, $typeinfo in $internal_interface_args[$ifname]: @@ -1385,7 +1385,7 @@ namespace ${namespace} { #else _status = msg.serialize($argname); #end if - FW_ASSERT(_status == Fw::FW_SERIALIZE_OK, static_cast(_status)); + FW_ASSERT(_status == Fw::FW_SERIALIZE_OK, static_cast(_status)); #end for // send message @@ -1405,7 +1405,7 @@ namespace ${namespace} { #end if FW_ASSERT( qStatus == Os::Queue::QUEUE_OK, - static_cast(qStatus) + static_cast(qStatus) ); } @@ -1481,21 +1481,21 @@ namespace ${namespace} { ); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // serialize port number _status = msgSerBuff.serialize(portNum); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // serialize buffer _status = msgSerBuff.serialize(buffer); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // send message @@ -1515,7 +1515,7 @@ namespace ${namespace} { #end if FW_ASSERT( qStatus == Os::Queue::QUEUE_OK, - static_cast(qStatus) + static_cast(qStatus) ); #end if @@ -1583,7 +1583,7 @@ namespace ${namespace} { { // Make sure port number is valid - FW_ASSERT(portNum < this->getNum_${instance}_InputPorts(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_${instance}_InputPorts(),static_cast(portNum)); #if not $void_return_type: ${return_type} retVal; #end if @@ -1607,13 +1607,13 @@ namespace ${namespace} { ); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); _status = msg.serialize(portNum); FW_ASSERT ( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #set $args = $port_args[$instance] @@ -1628,7 +1628,7 @@ namespace ${namespace} { #end if FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #end for @@ -1650,7 +1650,7 @@ namespace ${namespace} { #end if FW_ASSERT( qStatus == Os::Queue::QUEUE_OK, - static_cast(qStatus) + static_cast(qStatus) ); #else: @@ -1732,7 +1732,7 @@ namespace ${namespace} { Os::Queue::QueueStatus msgStatus = this->m_queue.receive(msg,priority,Os::Queue::QUEUE_BLOCKING); FW_ASSERT( msgStatus == Os::Queue::QUEUE_OK, - static_cast(msgStatus) + static_cast(msgStatus) ); #else Os::Queue::QueueStatus msgStatus = this->m_queue.receive(msg,priority,Os::Queue::QUEUE_NONBLOCKING); @@ -1741,7 +1741,7 @@ namespace ${namespace} { } else { FW_ASSERT( msgStatus == Os::Queue::QUEUE_OK, - static_cast(msgStatus) + static_cast(msgStatus) ); } #end if @@ -1753,7 +1753,7 @@ namespace ${namespace} { Fw::SerializeStatus deserStatus = msg.deserialize(desMsg); FW_ASSERT( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); MsgTypeEnum msgType = static_cast(desMsg); @@ -1766,7 +1766,7 @@ namespace ${namespace} { deserStatus = msg.deserialize(portNum); FW_ASSERT( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); switch (msgType) { @@ -1795,7 +1795,7 @@ namespace ${namespace} { #end if FW_ASSERT( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); #end for @@ -1806,7 +1806,7 @@ namespace ${namespace} { deserStatus = msg.deserialize(serHandBuff); FW_ASSERT( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); this->${instance}_handler(portNum, serHandBuff); #else: @@ -1846,7 +1846,7 @@ namespace ${namespace} { deserStatus = msg.deserialize(opCode); FW_ASSERT ( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); // Deserialize command sequence @@ -1854,7 +1854,7 @@ namespace ${namespace} { deserStatus = msg.deserialize(cmdSeq); FW_ASSERT ( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); // Deserialize command argument buffer @@ -1862,7 +1862,7 @@ namespace ${namespace} { deserStatus = msg.deserialize(args); FW_ASSERT ( deserStatus == Fw::FW_SERIALIZE_OK, - static_cast(deserStatus) + static_cast(deserStatus) ); // Reset buffer @@ -1939,7 +1939,7 @@ namespace ${namespace} { // Internal interfaces should always deserialize FW_ASSERT( Fw::FW_SERIALIZE_OK == deserStatus, - static_cast(deserStatus) + static_cast(deserStatus) ); #end for @@ -1947,7 +1947,7 @@ namespace ${namespace} { // That means the buffer size was incorrect. FW_ASSERT( msg.getBuffLeft() == 0, - static_cast(msg.getBuffLeft()) + static_cast(msg.getBuffLeft()) ); // Call handler function diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/enums/enum_hpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/enums/enum_hpp.tmpl index 2d9df6a7c0..defe4540fb 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/enums/enum_hpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/enums/enum_hpp.tmpl @@ -15,7 +15,7 @@ \#define ${namespace}_${name}_HPP \#include "Fw/Types/String.hpp" -\#include "Fw/Types/BasicTypes.hpp" +\#include \#include "Fw/Types/Serializable.hpp" #if $namespace diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/impl/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/impl/cpp.tmpl index 2fdb13bad1..2d641b8914 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/impl/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/impl/cpp.tmpl @@ -6,7 +6,7 @@ \#include <${include_path}/${name}.hpp> -\#include "Fw/Types/BasicTypes.hpp" +\#include #if $namespace_list != None #for $namespace in $namespace_list diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/port/finishPortCpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/port/finishPortCpp.tmpl index feee95aa01..c0aae49b91 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/port/finishPortCpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/port/finishPortCpp.tmpl @@ -50,11 +50,11 @@ ${return_type}Output${name}Port::invoke(${args_proto_string}) { _status = _buffer.serialize($arg[0]); #end if #set $num = $num + 1 - FW_ASSERT(Fw::FW_SERIALIZE_OK == _status,static_cast(_status)); + FW_ASSERT(Fw::FW_SERIALIZE_OK == _status,static_cast(_status)); #end for _status = this->m_serPort->invokeSerial(_buffer); - FW_ASSERT(Fw::FW_SERIALIZE_OK == _status,static_cast(_status)); + FW_ASSERT(Fw::FW_SERIALIZE_OK == _status,static_cast(_status)); } \#else } diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/port/includes1PortH.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/port/includes1PortH.tmpl index 47a7d3ec3f..c772e94d00 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/port/includes1PortH.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/port/includes1PortH.tmpl @@ -4,6 +4,6 @@ \#include \#include \#include -\#include +\#include \#include \#include diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialCpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialCpp.tmpl index 0d11c2af0e..02a96490a0 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialCpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialCpp.tmpl @@ -1,6 +1,6 @@ \#include <${include_path}/${namespace}${name}SerializableAc.hpp> \#include -\#include +\#include \#include \#if FW_SERIALIZABLE_TO_STRING \#include diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialH.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialH.tmpl index 394fb1a265..8593a29087 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialH.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialH.tmpl @@ -1,4 +1,4 @@ -\#include +\#include \#include \#if FW_SERIALIZABLE_TO_STRING \#include diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl index a69e7c5744..a148bbfa0b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl @@ -222,7 +222,7 @@ $emit_cpp_params([ $param_instance ]) $emit_cpp_params([ $param_portNum, $param_port ]) ) { - FW_ASSERT(portNum < this->getNum_to_${instance}(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_to_${instance}(),static_cast(portNum)); #if $type == "Serial": this->m_to_${instance}[portNum].registerSerialPort($instance); #else: @@ -259,11 +259,11 @@ $emit_cpp_port_params([ $param_portNum ] + $port_params[$instance]) ) #end if { - FW_ASSERT(portNum < this->getNum_to_${instance}(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_to_${instance}(),static_cast(portNum)); #if $serial_type: this->m_to_${instance}[portNum].invokeSerial(Buffer); #else - FW_ASSERT(portNum < this->getNum_to_${instance}(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_to_${instance}(),static_cast(portNum)); #if $void_return_type this->m_to_${instance}[portNum].invoke( #else: @@ -285,7 +285,7 @@ $emit_cpp_port_params([ $param_portNum ] + $port_params[$instance]) bool ${tester_base} :: isConnected_to_${instance}(const NATIVE_INT_TYPE portNum) { - FW_ASSERT(portNum < this->getNum_to_${instance}(), static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_to_${instance}(), static_cast(portNum)); return this->m_to_${instance}[portNum].isConnected(); } @@ -308,7 +308,7 @@ $emit_cpp_port_params([ $param_portNum ] + $port_params[$instance]) #end if get_from_${instance}(const NATIVE_INT_TYPE portNum) { - FW_ASSERT(portNum < this->getNum_from_${instance}(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_from_${instance}(),static_cast(portNum)); return &this->m_from_${instance}[portNum]; } #if $role == "LogTextEvent": @@ -378,7 +378,7 @@ $emit_cpp_port_params([ $param_callComp, $param_portNum] + $params) Fw::SerializeBufferBase &Buffer $doxygen_post_comment("The serialization buffer") ) { - FW_ASSERT(portNum < this->getNum_from_${instance}(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_from_${instance}(),static_cast(portNum)); this->from_${instance}_handler( portNum, Buffer @@ -514,7 +514,7 @@ $emit_cpp_port_params([ $param_callComp, $param_portNum] + $params) _ret = _testerBase->m_param_${prm_name}_valid; FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); } break; @@ -559,7 +559,7 @@ $emit_cpp_port_params([ $param_callComp, $param_portNum] + $params) _status = val.deserialize(${prmname}Val); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); FW_ASSERT( ${prmname}Val == @@ -569,7 +569,7 @@ $emit_cpp_port_params([ $param_callComp, $param_portNum] + $params) Fw::ParamString ${prmname}Val; _status = val.deserialize(${prmname}Val); FW_ASSERT( - _status == Fw::FW_SERIALIZE_OK,static_cast(_status) + _status == Fw::FW_SERIALIZE_OK,static_cast(_status) ); FW_ASSERT( ${prmname}Val == @@ -580,7 +580,7 @@ $emit_cpp_port_params([ $param_callComp, $param_portNum] + $params) _status = val.deserialize(${prmname}Val); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); FW_ASSERT( ${prmname}Val == @@ -664,7 +664,7 @@ $emit_cpp_port_params([ $param_portNum ] + $port_params[$instance]) #end if ) { - FW_ASSERT(portNum < this->getNum_from_${instance}(),static_cast(portNum)); + FW_ASSERT(portNum < this->getNum_from_${instance}(),static_cast(portNum)); #if $void_params and $void_return_type: this->from_${instance}_handler(portNum); #else if $void_params @@ -725,7 +725,7 @@ $emit_cpp_params([ $param_instance, $param_cmdSeq ] + $get_command_params($mnemo #else _status = buff.serialize($arg_name); #end if - FW_ASSERT(_status == Fw::FW_SERIALIZE_OK,static_cast(_status)); + FW_ASSERT(_status == Fw::FW_SERIALIZE_OK,static_cast(_status)); #end for // Call output command port @@ -950,7 +950,7 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) _status = args.deserialize(_numArgs); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); // verify they match expected. #if $severity == "FATAL" @@ -960,14 +960,14 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) _status = args.deserialize(stackArgLen); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); FW_ASSERT(4 == stackArgLen,stackArgLen); U32 dummyStackArg; _status = args.deserialize(dummyStackArg); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); FW_ASSERT(0 == dummyStackArg,dummyStackArg); #else @@ -983,7 +983,7 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) _zero_status = args.deserialize(_noArgs); FW_ASSERT( _zero_status == Fw::FW_SERIALIZE_OK, - static_cast(_zero_status) + static_cast(_zero_status) ); \#endif #end if @@ -996,7 +996,7 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) _status = args.deserialize(_argSize); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); FW_ASSERT(_argSize == sizeof(FwEnumStoreType),_argSize,sizeof(FwEnumStoreType)); } @@ -1017,7 +1017,7 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) _status = args.deserialize(_argSize); FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); FW_ASSERT(_argSize == sizeof(${type}),_argSize,sizeof(${type})); } @@ -1026,7 +1026,7 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) #end if FW_ASSERT( _status == Fw::FW_SERIALIZE_OK, - static_cast(_status) + static_cast(_status) ); #end for diff --git a/Autocoders/Python/templates/ExampleType.hpp b/Autocoders/Python/templates/ExampleType.hpp index ecc2762ccd..91883bbbd7 100644 --- a/Autocoders/Python/templates/ExampleType.hpp +++ b/Autocoders/Python/templates/ExampleType.hpp @@ -2,7 +2,7 @@ #define EXAMPLE_TYPE_HPP // A hand-coded serializable -#include +#include #include #if FW_SERIALIZABLE_TO_STRING #include diff --git a/Autocoders/Python/test/array_xml/ExampleArrayImpl.cpp b/Autocoders/Python/test/array_xml/ExampleArrayImpl.cpp index b055302ec4..d56216b7ea 100644 --- a/Autocoders/Python/test/array_xml/ExampleArrayImpl.cpp +++ b/Autocoders/Python/test/array_xml/ExampleArrayImpl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include #include diff --git a/Autocoders/Python/test/array_xml/test/ut/main.cpp b/Autocoders/Python/test/array_xml/test/ut/main.cpp index 6d0cfc6463..3f95f88783 100644 --- a/Autocoders/Python/test/array_xml/test/ut/main.cpp +++ b/Autocoders/Python/test/array_xml/test/ut/main.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include diff --git a/Autocoders/Python/test/command2/TestCommandComponentImpl.cpp b/Autocoders/Python/test/command2/TestCommandComponentImpl.cpp index 8c94288e73..3e5ff44765 100644 --- a/Autocoders/Python/test/command2/TestCommandComponentImpl.cpp +++ b/Autocoders/Python/test/command2/TestCommandComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace AcTest { diff --git a/Autocoders/Python/test/command_res/Test1ComponentImpl.cpp b/Autocoders/Python/test/command_res/Test1ComponentImpl.cpp index e3b7586c9c..61f8a570fe 100644 --- a/Autocoders/Python/test/command_res/Test1ComponentImpl.cpp +++ b/Autocoders/Python/test/command_res/Test1ComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Cmd { diff --git a/Autocoders/Python/test/enum1port/DrvTimingSignalPort.hpp b/Autocoders/Python/test/enum1port/DrvTimingSignalPort.hpp index 2db34fd0d6..193576f0b8 100644 --- a/Autocoders/Python/test/enum1port/DrvTimingSignalPort.hpp +++ b/Autocoders/Python/test/enum1port/DrvTimingSignalPort.hpp @@ -4,7 +4,7 @@ #include #include #include -#include +#include namespace Drv { diff --git a/Autocoders/Python/test/enum_xml/Component1Impl.cpp b/Autocoders/Python/test/enum_xml/Component1Impl.cpp index c471aab6bb..95b80dbadd 100644 --- a/Autocoders/Python/test/enum_xml/Component1Impl.cpp +++ b/Autocoders/Python/test/enum_xml/Component1Impl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include diff --git a/Autocoders/Python/test/enum_xml/main.cpp b/Autocoders/Python/test/enum_xml/main.cpp index 601a18b068..079b282405 100644 --- a/Autocoders/Python/test/enum_xml/main.cpp +++ b/Autocoders/Python/test/enum_xml/main.cpp @@ -130,12 +130,12 @@ void checkAssertionFailure( Test::UnitTestAssert::File file = Test::UnitTestAssert::fileInit; NATIVE_UINT_TYPE lineNo = 0; NATIVE_UINT_TYPE numArgs = 0; - AssertArg arg1 = 0; - AssertArg arg2 = 0; - AssertArg arg3 = 0; - AssertArg arg4 = 0; - AssertArg arg5 = 0; - AssertArg arg6 = 0; + FwAssertArgType arg1 = 0; + FwAssertArgType arg2 = 0; + FwAssertArgType arg3 = 0; + FwAssertArgType arg4 = 0; + FwAssertArgType arg5 = 0; + FwAssertArgType arg6 = 0; uta.retrieveAssert(file, lineNo, numArgs, arg1, arg2, arg3, arg4, arg5, arg6); ASSERT_EQ(expectedLineNumber, lineNo); ASSERT_EQ(1U, numArgs); diff --git a/Autocoders/Python/test/ext_dict/ExampleType.hpp b/Autocoders/Python/test/ext_dict/ExampleType.hpp index 1c8f104d06..c67f30aee7 100644 --- a/Autocoders/Python/test/ext_dict/ExampleType.hpp +++ b/Autocoders/Python/test/ext_dict/ExampleType.hpp @@ -2,7 +2,7 @@ #define EXAMPLE_TYPE_HPP // A hand-coded serializable -#include +#include #include #if FW_SERIALIZABLE_TO_STRING #include diff --git a/Autocoders/Python/test/implgen/templates/MathSenderComponentImpl_cpp-template.txt b/Autocoders/Python/test/implgen/templates/MathSenderComponentImpl_cpp-template.txt index 4b5678a73e..7ad49e9d0c 100644 --- a/Autocoders/Python/test/implgen/templates/MathSenderComponentImpl_cpp-template.txt +++ b/Autocoders/Python/test/implgen/templates/MathSenderComponentImpl_cpp-template.txt @@ -1,5 +1,5 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Ref { diff --git a/Autocoders/Python/test/interface1/SomeStruct.hpp b/Autocoders/Python/test/interface1/SomeStruct.hpp index 110fc5ff55..df60193f9c 100644 --- a/Autocoders/Python/test/interface1/SomeStruct.hpp +++ b/Autocoders/Python/test/interface1/SomeStruct.hpp @@ -1,7 +1,7 @@ #ifndef SOME_STRUCT_HPP #define SOME_STRUCT_HPP -#include +#include extern "C" { typedef struct { diff --git a/Autocoders/Python/test/interface1/UserSerializer.hpp b/Autocoders/Python/test/interface1/UserSerializer.hpp index b6ea7948f4..c6c730aca0 100644 --- a/Autocoders/Python/test/interface1/UserSerializer.hpp +++ b/Autocoders/Python/test/interface1/UserSerializer.hpp @@ -2,7 +2,7 @@ #define EXAMPLE_TYPE_HPP // A hand-coded serializable -#include +#include #include #include #if FW_SERIALIZABLE_TO_STRING diff --git a/Autocoders/Python/test/noargport/ExampleComponentImpl.cpp b/Autocoders/Python/test/noargport/ExampleComponentImpl.cpp index 4cba2dc177..7c96b21ea6 100644 --- a/Autocoders/Python/test/noargport/ExampleComponentImpl.cpp +++ b/Autocoders/Python/test/noargport/ExampleComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace ExampleComponents { diff --git a/Autocoders/Python/test/partition/DuckDuckImpl.cpp b/Autocoders/Python/test/partition/DuckDuckImpl.cpp index 091f9654ce..10145e5d7a 100644 --- a/Autocoders/Python/test/partition/DuckDuckImpl.cpp +++ b/Autocoders/Python/test/partition/DuckDuckImpl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include diff --git a/Autocoders/Python/test/partition/PartitionImpl.cpp b/Autocoders/Python/test/partition/PartitionImpl.cpp index e43fae07c9..d90c2fd23a 100644 --- a/Autocoders/Python/test/partition/PartitionImpl.cpp +++ b/Autocoders/Python/test/partition/PartitionImpl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include diff --git a/Autocoders/Python/test/pass_by_attrib/Msg1Port.hpp b/Autocoders/Python/test/pass_by_attrib/Msg1Port.hpp index ab2bb158b9..85ab6e77d0 100644 --- a/Autocoders/Python/test/pass_by_attrib/Msg1Port.hpp +++ b/Autocoders/Python/test/pass_by_attrib/Msg1Port.hpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #include diff --git a/Autocoders/Python/test/pass_by_kind/Component1.cpp b/Autocoders/Python/test/pass_by_kind/Component1.cpp index a7d5c33e97..5965125c18 100644 --- a/Autocoders/Python/test/pass_by_kind/Component1.cpp +++ b/Autocoders/Python/test/pass_by_kind/Component1.cpp @@ -1,6 +1,6 @@ #include #include -#include +#include #include #include #include diff --git a/Autocoders/Python/test/port_loopback/ExampleComponentImpl.cpp b/Autocoders/Python/test/port_loopback/ExampleComponentImpl.cpp index f9760799ba..ace6e94c1b 100644 --- a/Autocoders/Python/test/port_loopback/ExampleComponentImpl.cpp +++ b/Autocoders/Python/test/port_loopback/ExampleComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include #include namespace ExampleComponents { diff --git a/Autocoders/Python/test/port_loopback/ExampleType.hpp b/Autocoders/Python/test/port_loopback/ExampleType.hpp index ecc2762ccd..91883bbbd7 100644 --- a/Autocoders/Python/test/port_loopback/ExampleType.hpp +++ b/Autocoders/Python/test/port_loopback/ExampleType.hpp @@ -2,7 +2,7 @@ #define EXAMPLE_TYPE_HPP // A hand-coded serializable -#include +#include #include #if FW_SERIALIZABLE_TO_STRING #include diff --git a/Autocoders/Python/test/port_nogen/ExampleType.hpp b/Autocoders/Python/test/port_nogen/ExampleType.hpp index 8809099da4..6a60913da9 100644 --- a/Autocoders/Python/test/port_nogen/ExampleType.hpp +++ b/Autocoders/Python/test/port_nogen/ExampleType.hpp @@ -2,7 +2,7 @@ #define EXAMPLE_TYPE_HPP // A hand-coded serializable -#include +#include #include #if FW_SERIALIZABLE_TO_STRING #include diff --git a/Autocoders/Python/test/serial_passive/TestSerialImpl.cpp b/Autocoders/Python/test/serial_passive/TestSerialImpl.cpp index 073e4276c8..657e7a9ad9 100644 --- a/Autocoders/Python/test/serial_passive/TestSerialImpl.cpp +++ b/Autocoders/Python/test/serial_passive/TestSerialImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace TestComponents { diff --git a/Autocoders/Python/test/serialize_user/SomeStruct.hpp b/Autocoders/Python/test/serialize_user/SomeStruct.hpp index 110fc5ff55..df60193f9c 100644 --- a/Autocoders/Python/test/serialize_user/SomeStruct.hpp +++ b/Autocoders/Python/test/serialize_user/SomeStruct.hpp @@ -1,7 +1,7 @@ #ifndef SOME_STRUCT_HPP #define SOME_STRUCT_HPP -#include +#include extern "C" { typedef struct { diff --git a/Autocoders/Python/test/serialize_user/UserSerializer.hpp b/Autocoders/Python/test/serialize_user/UserSerializer.hpp index d46584ff18..c460623999 100644 --- a/Autocoders/Python/test/serialize_user/UserSerializer.hpp +++ b/Autocoders/Python/test/serialize_user/UserSerializer.hpp @@ -2,7 +2,7 @@ #define EXAMPLE_TYPE_HPP // A hand-coded serializable -#include +#include #include #include #if FW_SERIALIZABLE_TO_STRING diff --git a/Autocoders/Python/test/testgen/MathSenderComponentImpl.cpp b/Autocoders/Python/test/testgen/MathSenderComponentImpl.cpp index 1e5d4a8ba6..f6b6d9c465 100644 --- a/Autocoders/Python/test/testgen/MathSenderComponentImpl.cpp +++ b/Autocoders/Python/test/testgen/MathSenderComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Ref { diff --git a/CFDP/Checksum/Checksum.hpp b/CFDP/Checksum/Checksum.hpp index 7ccfe2e8fd..7f444a3cf2 100644 --- a/CFDP/Checksum/Checksum.hpp +++ b/CFDP/Checksum/Checksum.hpp @@ -13,7 +13,7 @@ #ifndef CFDP_Checksum_HPP #define CFDP_Checksum_HPP -#include "Fw/Types/BasicTypes.hpp" +#include namespace CFDP { diff --git a/Drv/BlockDriver/BlockDriverImpl.cpp b/Drv/BlockDriver/BlockDriverImpl.cpp index bf8f40fb88..ecd20c2083 100644 --- a/Drv/BlockDriver/BlockDriverImpl.cpp +++ b/Drv/BlockDriver/BlockDriverImpl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include namespace Drv { diff --git a/Drv/DataTypes/DataBuffer.hpp b/Drv/DataTypes/DataBuffer.hpp index 99215f5006..5530a5bbd0 100644 --- a/Drv/DataTypes/DataBuffer.hpp +++ b/Drv/DataTypes/DataBuffer.hpp @@ -1,7 +1,7 @@ #ifndef _DrvDataBuffer_hpp_ #define _DrvDataBuffer_hpp_ -#include +#include #include namespace Drv { diff --git a/Drv/Ip/IpSocket.cpp b/Drv/Ip/IpSocket.cpp index f5cf42d2b6..f7cfb7ecea 100644 --- a/Drv/Ip/IpSocket.cpp +++ b/Drv/Ip/IpSocket.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #include diff --git a/Drv/Ip/IpSocket.hpp b/Drv/Ip/IpSocket.hpp index 870ea2e2fe..fe2f57993f 100644 --- a/Drv/Ip/IpSocket.hpp +++ b/Drv/Ip/IpSocket.hpp @@ -12,7 +12,7 @@ #ifndef DRV_IP_IPHELPER_HPP_ #define DRV_IP_IPHELPER_HPP_ -#include +#include #include #include diff --git a/Drv/Ip/TcpClientSocket.cpp b/Drv/Ip/TcpClientSocket.cpp index 9699b0a6c1..99f7d5017c 100644 --- a/Drv/Ip/TcpClientSocket.cpp +++ b/Drv/Ip/TcpClientSocket.cpp @@ -12,7 +12,7 @@ #include #include -#include +#include #ifdef TGT_OS_TYPE_VXWORKS #include diff --git a/Drv/Ip/TcpClientSocket.hpp b/Drv/Ip/TcpClientSocket.hpp index 079be73718..ebe1aa53b2 100644 --- a/Drv/Ip/TcpClientSocket.hpp +++ b/Drv/Ip/TcpClientSocket.hpp @@ -12,7 +12,7 @@ #ifndef DRV_TCPCLIENT_TCPHELPER_HPP_ #define DRV_TCPCLIENT_TCPHELPER_HPP_ -#include +#include #include #include diff --git a/Drv/Ip/TcpServerSocket.cpp b/Drv/Ip/TcpServerSocket.cpp index 10cc355350..ac4be73401 100644 --- a/Drv/Ip/TcpServerSocket.cpp +++ b/Drv/Ip/TcpServerSocket.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include #include -#include +#include #ifdef TGT_OS_TYPE_VXWORKS diff --git a/Drv/Ip/TcpServerSocket.hpp b/Drv/Ip/TcpServerSocket.hpp index 94ea98d3a2..9410d040d2 100644 --- a/Drv/Ip/TcpServerSocket.hpp +++ b/Drv/Ip/TcpServerSocket.hpp @@ -12,7 +12,7 @@ #ifndef DRV_TCPSERVER_TCPHELPER_HPP_ #define DRV_TCPSERVER_TCPHELPER_HPP_ -#include +#include #include #include diff --git a/Drv/Ip/UdpSocket.cpp b/Drv/Ip/UdpSocket.cpp index a748667fc9..6996e52b4b 100644 --- a/Drv/Ip/UdpSocket.cpp +++ b/Drv/Ip/UdpSocket.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #ifdef TGT_OS_TYPE_VXWORKS diff --git a/Drv/Ip/UdpSocket.hpp b/Drv/Ip/UdpSocket.hpp index afdec15378..c73126bd5c 100644 --- a/Drv/Ip/UdpSocket.hpp +++ b/Drv/Ip/UdpSocket.hpp @@ -12,7 +12,7 @@ #ifndef DRV_IP_UDPSOCKET_HPP_ #define DRV_IP_UDPSOCKET_HPP_ -#include +#include #include #include diff --git a/Drv/Ip/test/ut/PortSelector.hpp b/Drv/Ip/test/ut/PortSelector.hpp index fa7f6ef73b..07a1a5de5a 100644 --- a/Drv/Ip/test/ut/PortSelector.hpp +++ b/Drv/Ip/test/ut/PortSelector.hpp @@ -1,7 +1,7 @@ // // Created by mstarch on 12/10/20. // -#include +#include #ifndef DRV_TEST_PORTSELECTOR_HPP #define DRV_TEST_PORTSELECTOR_HPP diff --git a/Drv/Ip/test/ut/SocketTestHelper.hpp b/Drv/Ip/test/ut/SocketTestHelper.hpp index ec02921b63..71f6f12b84 100644 --- a/Drv/Ip/test/ut/SocketTestHelper.hpp +++ b/Drv/Ip/test/ut/SocketTestHelper.hpp @@ -1,7 +1,7 @@ // // Created by mstarch on 12/10/20. // -#include +#include #include #include diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp index ca87395036..3b4eec017f 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include +#include #include // TODO make proper static constants for these diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplCommon.cpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplCommon.cpp index 0df4643e2a..3fc402d806 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplCommon.cpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplCommon.cpp @@ -12,7 +12,7 @@ #include -#include +#include namespace Drv { diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp index d439cf095f..761b36dab7 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Drv { diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp index 49af977849..9afb610d75 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include "Fw/Types/Assert.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include #include diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp index 780491ae6d..b3346aed89 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include "Fw/Types/Assert.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include #define DEBUG_PRINT 0 diff --git a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp index c84567ccae..0090095d5e 100644 --- a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp +++ b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include diff --git a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplCommon.cpp b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplCommon.cpp index 9de8bbd5e8..7a8b03f451 100644 --- a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplCommon.cpp +++ b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplCommon.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Drv { diff --git a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplStub.cpp b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplStub.cpp index ab030c8ca2..3b3ebe0aa6 100644 --- a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplStub.cpp +++ b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImplStub.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Drv { diff --git a/Drv/TcpClient/TcpClientComponentImpl.cpp b/Drv/TcpClient/TcpClientComponentImpl.cpp index 8b75d881bd..05aec9270b 100644 --- a/Drv/TcpClient/TcpClientComponentImpl.cpp +++ b/Drv/TcpClient/TcpClientComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Assert.hpp" diff --git a/Drv/TcpServer/TcpServerComponentImpl.cpp b/Drv/TcpServer/TcpServerComponentImpl.cpp index f8115b26e9..86f65abd70 100644 --- a/Drv/TcpServer/TcpServerComponentImpl.cpp +++ b/Drv/TcpServer/TcpServerComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Assert.hpp" namespace Drv { diff --git a/Drv/Udp/UdpComponentImpl.cpp b/Drv/Udp/UdpComponentImpl.cpp index 6072098e1e..e45cd9fd87 100644 --- a/Drv/Udp/UdpComponentImpl.cpp +++ b/Drv/Udp/UdpComponentImpl.cpp @@ -12,7 +12,7 @@ #include #include -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Assert.hpp" diff --git a/Fw/Buffer/Buffer.cpp b/Fw/Buffer/Buffer.cpp index e1a2890d00..010c2dc963 100644 --- a/Fw/Buffer/Buffer.cpp +++ b/Fw/Buffer/Buffer.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include #include -#include +#include #if FW_SERIALIZABLE_TO_STRING #include diff --git a/Fw/Buffer/Buffer.hpp b/Fw/Buffer/Buffer.hpp index 1ac3bc11d8..50d021216b 100644 --- a/Fw/Buffer/Buffer.hpp +++ b/Fw/Buffer/Buffer.hpp @@ -12,7 +12,7 @@ #ifndef BUFFER_HPP_ #define BUFFER_HPP_ -#include +#include #include #if FW_SERIALIZABLE_TO_STRING #include diff --git a/Fw/Buffer/test/ut/TestBuffer.cpp b/Fw/Buffer/test/ut/TestBuffer.cpp index e0bbb514d4..fd2d11aaf5 100644 --- a/Fw/Buffer/test/ut/TestBuffer.cpp +++ b/Fw/Buffer/test/ut/TestBuffer.cpp @@ -2,7 +2,7 @@ // Created by mstarch on 11/13/20. // #include "Fw/Buffer/Buffer.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include diff --git a/Fw/Cfg/ConfigCheck.cpp b/Fw/Cfg/ConfigCheck.cpp index 43350e05cf..da218bcccf 100644 --- a/Fw/Cfg/ConfigCheck.cpp +++ b/Fw/Cfg/ConfigCheck.cpp @@ -11,7 +11,6 @@ */ #include -#include // Check that command/telemetry strings are not larger than an argument buffer diff --git a/Fw/Cmd/CmdArgBuffer.hpp b/Fw/Cmd/CmdArgBuffer.hpp index 8e72f220bc..4744c6124c 100644 --- a/Fw/Cmd/CmdArgBuffer.hpp +++ b/Fw/Cmd/CmdArgBuffer.hpp @@ -12,9 +12,8 @@ #ifndef FW_CMD_ARG_BUFFER_HPP #define FW_CMD_ARG_BUFFER_HPP -#include -#include #include +#include #include namespace Fw { diff --git a/Fw/Cmd/CmdString.hpp b/Fw/Cmd/CmdString.hpp index d9d283f188..4e3a9dfe7d 100644 --- a/Fw/Cmd/CmdString.hpp +++ b/Fw/Cmd/CmdString.hpp @@ -1,9 +1,8 @@ #ifndef FW_CMD_STRING_TYPE_HPP #define FW_CMD_STRING_TYPE_HPP -#include -#include #include +#include #include namespace Fw { diff --git a/Fw/Com/ComBuffer.hpp b/Fw/Com/ComBuffer.hpp index dc52506566..a9d552a630 100644 --- a/Fw/Com/ComBuffer.hpp +++ b/Fw/Com/ComBuffer.hpp @@ -13,7 +13,6 @@ #define FW_COM_BUFFER_HPP #include -#include #include namespace Fw { diff --git a/Fw/FilePacket/FilePacket.hpp b/Fw/FilePacket/FilePacket.hpp index 8f6cf995dc..09b58cffca 100644 --- a/Fw/FilePacket/FilePacket.hpp +++ b/Fw/FilePacket/FilePacket.hpp @@ -15,7 +15,7 @@ #include #include -#include +#include #include #include diff --git a/Fw/Log/LogBuffer.hpp b/Fw/Log/LogBuffer.hpp index e33fed20a6..8e310f8f3c 100644 --- a/Fw/Log/LogBuffer.hpp +++ b/Fw/Log/LogBuffer.hpp @@ -13,7 +13,6 @@ #define FW_LOG_BUFFER_HPP #include -#include #include #include diff --git a/Fw/Log/LogString.hpp b/Fw/Log/LogString.hpp index 2c3e4e14be..533e2ddf24 100644 --- a/Fw/Log/LogString.hpp +++ b/Fw/Log/LogString.hpp @@ -1,9 +1,8 @@ #ifndef FW_LOG_STRING_TYPE_HPP #define FW_LOG_STRING_TYPE_HPP -#include -#include #include +#include #include namespace Fw { diff --git a/Fw/Log/TextLogString.hpp b/Fw/Log/TextLogString.hpp index 43c0c602b8..e25f7273f2 100644 --- a/Fw/Log/TextLogString.hpp +++ b/Fw/Log/TextLogString.hpp @@ -1,9 +1,8 @@ #ifndef FW_TEXT_LOG_STRING_TYPE_HPP #define FW_TEXT_LOG_STRING_TYPE_HPP -#include -#include #include +#include #include namespace Fw { diff --git a/Fw/Logger/LogAssert.cpp b/Fw/Logger/LogAssert.cpp index 488b17e6b9..4eca41f9b0 100644 --- a/Fw/Logger/LogAssert.cpp +++ b/Fw/Logger/LogAssert.cpp @@ -36,12 +36,12 @@ namespace Fw { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ) { // Assumption is that file (when string) goes back to static macro in the code and will persist switch (numArgs) { diff --git a/Fw/Logger/LogAssert.hpp b/Fw/Logger/LogAssert.hpp index 03401e4786..6927b06d90 100644 --- a/Fw/Logger/LogAssert.hpp +++ b/Fw/Logger/LogAssert.hpp @@ -22,12 +22,12 @@ namespace Fw { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ); void printAssert(const CHAR* msg); void doAssert(); diff --git a/Fw/Logger/Logger.hpp b/Fw/Logger/Logger.hpp index bca6b273ce..981612b09c 100644 --- a/Fw/Logger/Logger.hpp +++ b/Fw/Logger/Logger.hpp @@ -9,7 +9,7 @@ #ifndef _Fw_Logger_hpp_ #define _Fw_Logger_hpp_ -#include +#include namespace Fw { class Logger { diff --git a/Fw/Logger/test/ut/FakeLogger.hpp b/Fw/Logger/test/ut/FakeLogger.hpp index 439b374a97..125023d4b9 100644 --- a/Fw/Logger/test/ut/FakeLogger.hpp +++ b/Fw/Logger/test/ut/FakeLogger.hpp @@ -7,7 +7,7 @@ * @author mstarch */ -#include +#include #include #ifndef FPRIME_FAKELOGGER_HPP diff --git a/Fw/Logger/test/ut/LoggerRules.hpp b/Fw/Logger/test/ut/LoggerRules.hpp index 0b8405264d..a0f34a4948 100644 --- a/Fw/Logger/test/ut/LoggerRules.hpp +++ b/Fw/Logger/test/ut/LoggerRules.hpp @@ -15,7 +15,7 @@ #ifndef FPRIME_LOGGERRULES_HPP #define FPRIME_LOGGERRULES_HPP -#include +#include #include #include #include diff --git a/Fw/Obj/ObjBase.hpp b/Fw/Obj/ObjBase.hpp index 629fbeb740..ac06088d83 100644 --- a/Fw/Obj/ObjBase.hpp +++ b/Fw/Obj/ObjBase.hpp @@ -13,7 +13,6 @@ #ifndef FW_OBJ_BASE_HPP #define FW_OBJ_BASE_HPP -#include #include namespace Fw { diff --git a/Fw/Obj/SimpleObjRegistry.hpp b/Fw/Obj/SimpleObjRegistry.hpp index b0cd805f86..4d700b698e 100644 --- a/Fw/Obj/SimpleObjRegistry.hpp +++ b/Fw/Obj/SimpleObjRegistry.hpp @@ -21,7 +21,6 @@ #include #include -#include #if FW_OBJECT_REGISTRATION == 1 diff --git a/Fw/Port/InputPortBase.cpp b/Fw/Port/InputPortBase.cpp index 40168bce71..b82aedcf94 100644 --- a/Fw/Port/InputPortBase.cpp +++ b/Fw/Port/InputPortBase.cpp @@ -1,8 +1,6 @@ #include - #include #include -#include #include namespace Fw { diff --git a/Fw/Port/InputPortBase.hpp b/Fw/Port/InputPortBase.hpp index 1752d47177..5499c7c610 100644 --- a/Fw/Port/InputPortBase.hpp +++ b/Fw/Port/InputPortBase.hpp @@ -2,9 +2,7 @@ #define FW_INPUT_PORT_BASE_HPP #include - #include -#include #include #include #include diff --git a/Fw/Port/OutputPortBase.cpp b/Fw/Port/OutputPortBase.cpp index 44e67034d3..0ac06fd3ae 100644 --- a/Fw/Port/OutputPortBase.cpp +++ b/Fw/Port/OutputPortBase.cpp @@ -1,7 +1,5 @@ #include - #include -#include #include #include #include diff --git a/Fw/Port/OutputPortBase.hpp b/Fw/Port/OutputPortBase.hpp index 1a8d75f154..c64e11fc14 100644 --- a/Fw/Port/OutputPortBase.hpp +++ b/Fw/Port/OutputPortBase.hpp @@ -2,9 +2,7 @@ #define FW_OUTPUT_PORT_BASE_HPP #include - #include -#include #include #include diff --git a/Fw/Port/PortBase.cpp b/Fw/Port/PortBase.cpp index 6d775be222..34b51322a2 100644 --- a/Fw/Port/PortBase.cpp +++ b/Fw/Port/PortBase.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include #include "Fw/Types/Assert.hpp" diff --git a/Fw/Port/PortBase.hpp b/Fw/Port/PortBase.hpp index 4573d7589b..e9b9a6b8e8 100644 --- a/Fw/Port/PortBase.hpp +++ b/Fw/Port/PortBase.hpp @@ -2,7 +2,7 @@ #define FW_PORT_BASE_HPP #include -#include +#include #include #if FW_PORT_TRACING == 1 diff --git a/Fw/Prm/PrmBuffer.hpp b/Fw/Prm/PrmBuffer.hpp index 29739fa846..51b21c94cc 100644 --- a/Fw/Prm/PrmBuffer.hpp +++ b/Fw/Prm/PrmBuffer.hpp @@ -13,7 +13,6 @@ #define FW_PRM_BUFFER_HPP #include -#include #include #include diff --git a/Fw/Prm/PrmString.hpp b/Fw/Prm/PrmString.hpp index deb4fdac48..8972c49a7a 100644 --- a/Fw/Prm/PrmString.hpp +++ b/Fw/Prm/PrmString.hpp @@ -1,9 +1,8 @@ #ifndef FW_PRM_STRING_TYPE_HPP #define FW_PRM_STRING_TYPE_HPP -#include -#include #include +#include #include namespace Fw { diff --git a/Fw/SerializableFile/test/ut/Test.cpp b/Fw/SerializableFile/test/ut/Test.cpp index 38d407adda..eb569ede48 100644 --- a/Fw/SerializableFile/test/ut/Test.cpp +++ b/Fw/SerializableFile/test/ut/Test.cpp @@ -4,7 +4,7 @@ #include #include -#include +#include #include #include #include diff --git a/Fw/Test/String.hpp b/Fw/Test/String.hpp index 3d293d50b2..ddc525bcd2 100644 --- a/Fw/Test/String.hpp +++ b/Fw/Test/String.hpp @@ -1,7 +1,7 @@ #ifndef TEST_STRING_TYPE_HPP #define TEST_STRING_TYPE_HPP -#include +#include #include #include diff --git a/Fw/Test/UnitTestAssert.cpp b/Fw/Test/UnitTestAssert.cpp index 81ba878087..95c343e3fb 100644 --- a/Fw/Test/UnitTestAssert.cpp +++ b/Fw/Test/UnitTestAssert.cpp @@ -43,9 +43,9 @@ namespace Test { void UnitTestAssert::doAssert() { this->m_assertFailed = true; #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT - (void)fprintf(stderr,"Assert File: 0x%x, Line: %u\n", this->m_file, this->m_lineNo); + (void)fprintf(stderr,"Assert File: 0x%x, Line: %" PRI_FwAssertArgType "\n", this->m_file, this->m_lineNo); #else - (void)fprintf(stderr,"Assert File: %s, Line: %u\n", this->m_file.toChar(), this->m_lineNo); + (void)fprintf(stderr,"Assert File: %s, Line: %" PRI_FwAssertArgType "\n", this->m_file.toChar(), this->m_lineNo); #endif } @@ -53,12 +53,12 @@ namespace Test { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ) { #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT @@ -82,12 +82,12 @@ namespace Test { File& file, NATIVE_UINT_TYPE& lineNo, NATIVE_UINT_TYPE& numArgs, - AssertArg& arg1, - AssertArg& arg2, - AssertArg& arg3, - AssertArg& arg4, - AssertArg& arg5, - AssertArg& arg6 + FwAssertArgType& arg1, + FwAssertArgType& arg2, + FwAssertArgType& arg3, + FwAssertArgType& arg4, + FwAssertArgType& arg5, + FwAssertArgType& arg6 ) const { file = this->m_file; diff --git a/Fw/Test/UnitTestAssert.hpp b/Fw/Test/UnitTestAssert.hpp index 71e7d77266..4aed203847 100644 --- a/Fw/Test/UnitTestAssert.hpp +++ b/Fw/Test/UnitTestAssert.hpp @@ -34,24 +34,24 @@ namespace Test { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ); // retrieves assertion failure values void retrieveAssert( File& file, NATIVE_UINT_TYPE& lineNo, NATIVE_UINT_TYPE& numArgs, - AssertArg& arg1, - AssertArg& arg2, - AssertArg& arg3, - AssertArg& arg4, - AssertArg& arg5, - AssertArg& arg6 + FwAssertArgType& arg1, + FwAssertArgType& arg2, + FwAssertArgType& arg3, + FwAssertArgType& arg4, + FwAssertArgType& arg5, + FwAssertArgType& arg6 ) const; // check whether assertion failure occurred @@ -64,12 +64,12 @@ namespace Test { File m_file; NATIVE_UINT_TYPE m_lineNo; NATIVE_INT_TYPE m_numArgs; - AssertArg m_arg1; - AssertArg m_arg2; - AssertArg m_arg3; - AssertArg m_arg4; - AssertArg m_arg5; - AssertArg m_arg6; + FwAssertArgType m_arg1; + FwAssertArgType m_arg2; + FwAssertArgType m_arg3; + FwAssertArgType m_arg4; + FwAssertArgType m_arg5; + FwAssertArgType m_arg6; // Whether an assertion failed bool m_assertFailed; diff --git a/Fw/Time/Time.cpp b/Fw/Time/Time.cpp index d75f506e17..422e46ede4 100644 --- a/Fw/Time/Time.cpp +++ b/Fw/Time/Time.cpp @@ -1,5 +1,5 @@ #include -#include +#include namespace Fw { const Time ZERO_TIME = Time(); diff --git a/Fw/Time/Time.hpp b/Fw/Time/Time.hpp index 249f389137..60591fc1fe 100644 --- a/Fw/Time/Time.hpp +++ b/Fw/Time/Time.hpp @@ -1,10 +1,9 @@ #ifndef FW_TIME_HPP #define FW_TIME_HPP -#include +#include #include #include -#include namespace Fw { class Time: public Serializable { diff --git a/Fw/Tlm/TlmBuffer.hpp b/Fw/Tlm/TlmBuffer.hpp index 9fc9cf6d8c..4de7a67867 100644 --- a/Fw/Tlm/TlmBuffer.hpp +++ b/Fw/Tlm/TlmBuffer.hpp @@ -12,7 +12,6 @@ #define FW_TLM_BUFFER_HPP #include -#include #include #include diff --git a/Fw/Tlm/TlmString.hpp b/Fw/Tlm/TlmString.hpp index 10977deb0b..e9a1a988b8 100644 --- a/Fw/Tlm/TlmString.hpp +++ b/Fw/Tlm/TlmString.hpp @@ -1,9 +1,8 @@ #ifndef FW_TLM_STRING_TYPE_HPP #define FW_TLM_STRING_TYPE_HPP -#include -#include #include +#include #include namespace Fw { diff --git a/Fw/Trap/TrapHandler.hpp b/Fw/Trap/TrapHandler.hpp index 09ee8bf60e..004b1f0acd 100644 --- a/Fw/Trap/TrapHandler.hpp +++ b/Fw/Trap/TrapHandler.hpp @@ -1,7 +1,6 @@ #ifndef FW_TRAP_HPP #define FW_TRAP_HPP #include -#include namespace Fw { /** diff --git a/Fw/Types/Assert.cpp b/Fw/Types/Assert.cpp index af6deb0327..fe7ac60dba 100644 --- a/Fw/Types/Assert.cpp +++ b/Fw/Types/Assert.cpp @@ -10,9 +10,9 @@ #else #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define fileIdFs "Assert file ID 0x%08X: Line: %d " +#define fileIdFs "Assert file ID 0x%08X: Line: %" PRI_FwAssertArgType #else -#define fileIdFs "Assert file \"%s\": Line: %d " +#define fileIdFs "Assert file \"%s\": Line: %" PRI_FwAssertArgType #endif namespace Fw { @@ -26,12 +26,12 @@ namespace Fw { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6, + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6, CHAR* destBuffer, NATIVE_INT_TYPE buffSize ) { @@ -82,12 +82,12 @@ namespace Fw { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ) { CHAR destBuffer[FW_ASSERT_DFL_MSG_LEN]; @@ -149,7 +149,7 @@ namespace Fw { } NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, - AssertArg arg1) { + FwAssertArgType arg1) { if (nullptr == s_assertHook) { CHAR assertMsg[FW_ASSERT_DFL_MSG_LEN]; defaultReportAssert( @@ -174,8 +174,8 @@ namespace Fw { } NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, - AssertArg arg1, - AssertArg arg2) { + FwAssertArgType arg1, + FwAssertArgType arg2) { if (nullptr == s_assertHook) { CHAR assertMsg[FW_ASSERT_DFL_MSG_LEN]; defaultReportAssert( @@ -199,9 +199,9 @@ namespace Fw { } NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3) { + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3) { if (nullptr == s_assertHook) { CHAR assertMsg[FW_ASSERT_DFL_MSG_LEN]; defaultReportAssert( @@ -225,10 +225,10 @@ namespace Fw { } NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4) { + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4) { if (nullptr == s_assertHook) { CHAR assertMsg[FW_ASSERT_DFL_MSG_LEN]; defaultReportAssert( @@ -252,11 +252,11 @@ namespace Fw { } NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5) { + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5) { if (nullptr == s_assertHook) { CHAR assertMsg[FW_ASSERT_DFL_MSG_LEN]; defaultReportAssert( @@ -280,12 +280,12 @@ namespace Fw { } NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6) { + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6) { if (nullptr == s_assertHook) { CHAR assertMsg[FW_ASSERT_DFL_MSG_LEN]; defaultReportAssert( diff --git a/Fw/Types/Assert.hpp b/Fw/Types/Assert.hpp index 2ccea32f04..5d3780aacd 100644 --- a/Fw/Types/Assert.hpp +++ b/Fw/Types/Assert.hpp @@ -2,7 +2,6 @@ #define FW_ASSERT_HPP #include -#include #if FW_ASSERT_LEVEL == FW_NO_ASSERT #define FW_ASSERT(...) @@ -36,12 +35,12 @@ namespace Fw { NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo) CLANG_ANALYZER_NORETURN; //!< Assert with no arguments - NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, AssertArg arg1) CLANG_ANALYZER_NORETURN; //!< Assert with one argument - NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, AssertArg arg1, AssertArg arg2) CLANG_ANALYZER_NORETURN; //!< Assert with two arguments - NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, AssertArg arg1, AssertArg arg2, AssertArg arg3) CLANG_ANALYZER_NORETURN; //!< Assert with three arguments - NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, AssertArg arg1, AssertArg arg2, AssertArg arg3, AssertArg arg4) CLANG_ANALYZER_NORETURN; //!< Assert with four arguments - NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, AssertArg arg1, AssertArg arg2, AssertArg arg3, AssertArg arg4, AssertArg arg5) CLANG_ANALYZER_NORETURN; //!< Assert with five arguments - NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, AssertArg arg1, AssertArg arg2, AssertArg arg3, AssertArg arg4, AssertArg arg5, AssertArg arg6) CLANG_ANALYZER_NORETURN; //!< Assert with six arguments + NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, FwAssertArgType arg1) CLANG_ANALYZER_NORETURN; //!< Assert with one argument + NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, FwAssertArgType arg1, FwAssertArgType arg2) CLANG_ANALYZER_NORETURN; //!< Assert with two arguments + NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, FwAssertArgType arg1, FwAssertArgType arg2, FwAssertArgType arg3) CLANG_ANALYZER_NORETURN; //!< Assert with three arguments + NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, FwAssertArgType arg1, FwAssertArgType arg2, FwAssertArgType arg3, FwAssertArgType arg4) CLANG_ANALYZER_NORETURN; //!< Assert with four arguments + NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, FwAssertArgType arg1, FwAssertArgType arg2, FwAssertArgType arg3, FwAssertArgType arg4, FwAssertArgType arg5) CLANG_ANALYZER_NORETURN; //!< Assert with five arguments + NATIVE_INT_TYPE SwAssert(FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, FwAssertArgType arg1, FwAssertArgType arg2, FwAssertArgType arg3, FwAssertArgType arg4, FwAssertArgType arg5, FwAssertArgType arg6) CLANG_ANALYZER_NORETURN; //!< Assert with six arguments } // Base class for declaring an assert hook @@ -59,12 +58,12 @@ namespace Fw { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ); // default reportAssert() will call this when the message is built // override it to do another kind of print. printf by default diff --git a/Fw/Types/BasicTypes.hpp b/Fw/Types/BasicTypes.hpp index 7b01d0e9d5..c6c25323ba 100644 --- a/Fw/Types/BasicTypes.hpp +++ b/Fw/Types/BasicTypes.hpp @@ -1,7 +1,7 @@ /** * \file * \author T. Canham - * \brief Declares ISF basic types + * \brief Declares fprime basic types * * \copyright * Copyright 2009-2016, by the California Institute of Technology. @@ -13,90 +13,52 @@ #ifndef FW_BASIC_TYPES_HPP #define FW_BASIC_TYPES_HPP -#include -#include // This header will be found be include paths by target. This hides different header files for each target. +#include #ifdef __cplusplus extern "C" { #endif // __cplusplus -// Define native integer/unsigned integer types -#ifdef _WRS_KERNEL -typedef int32_t NATIVE_INT_TYPE; -typedef uint32_t NATIVE_UINT_TYPE; -#else -// Allow overriding of native types for systems whose stdint.h is malformed -#ifndef FPRIME_OVERRIDE_NATIVE_TYPES -typedef int NATIVE_INT_TYPE; //!< native integer type declaration -typedef unsigned int NATIVE_UINT_TYPE; //!< native unsigned integer type declaration -#endif -#endif - #if defined __GNUC__ || __llvm__ - -// This is used to cast pointers to integers -// when a pointer needs to be stored generically. -// In order to avoid chopping off bits, -// the integer bit size needs to match -// the pointer bit size. - -#ifdef __SIZEOF_POINTER__ - #if __SIZEOF_POINTER__ == 8 - #define POINTER_CAST U64 - #elif __SIZEOF_POINTER__ == 4 - #define POINTER_CAST U32 - #elif __SIZEOF_POINTER__ == 2 - #define POINTER_CAST U16 - #else - #define POINTER_CAST U8 - #endif -#elif defined (__i386) && __i386 == 1 // GCC 4.1.2 - #define POINTER_CAST U32 -#elif defined (__x86_64) && __x86_64 == 1 // GCC 4.1.2 - #define POINTER_CAST U64 -#elif defined (CPU) && defined (PPC604) && CPU == PPC604 // VxWorks 6.7 RAD750 - #define POINTER_CAST U32 -#elif defined (CPU) && defined(SPARC) && CPU == SPARC - #define POINTER_CAST U32 #else - #error Cannot get size of pointer cast! + #error Unsupported compiler! #endif -#else - #error Unsupported compiler! -#endif - -// compile-time assert -#define COMPILE_TIME_ASSERT( condition, name )\ - do { \ - enum { assert_failed_ ## name = 1/(condition) }; \ - } while(0) - /*----------------------------------------------------------------------------*/ typedef int8_t I8; //!< 8-bit signed integer typedef uint8_t U8; //!< 8-bit unsigned integer typedef U8 BYTE; //!< byte type +typedef char CHAR; #if FW_HAS_16_BIT - typedef int16_t I16; //!< 16-bit signed integer - typedef uint16_t U16; //!< 16-bit unsigned integer + typedef int16_t I16; //!< 16-bit signed integer + typedef uint16_t U16; //!< 16-bit unsigned integer #endif #if FW_HAS_32_BIT - typedef uint32_t U32; //!< 32-bit signed integer - typedef int32_t I32; //!< 32-bit unsigned integer + typedef uint32_t U32; //!< 32-bit signed integer + typedef int32_t I32; //!< 32-bit unsigned integer #endif #if FW_HAS_64_BIT - typedef int64_t I64; //!< 64-bit signed integer - typedef uint64_t U64; //!< 64-bit unsigned integer + typedef int64_t I64; //!< 64-bit signed integer + typedef uint64_t U64; //!< 64-bit unsigned integer #endif typedef float F32; //!< 32-bit floating point #if FW_HAS_F64 - typedef double F64; //!< 64-bit floating point + typedef double F64; //!< 64-bit floating point #endif -typedef char CHAR; +typedef PlatformIntType NATIVE_INT_TYPE; +typedef PlatformUIntType NATIVE_UINT_TYPE; +typedef PlatformPointerCastType POINTER_CAST; + + // compile-time assert +#define COMPILE_TIME_ASSERT( condition, name )\ + do { \ + enum { assert_failed_ ## name = 1/(condition) }; \ + } while(0) + #define FW_NUM_ARRAY_ELEMENTS(a) (sizeof(a)/sizeof((a)[0])) //!< number of elements in an array @@ -121,4 +83,33 @@ typedef char CHAR; #endif // __cplusplus +/** + * BasicLimits: + * + * Limits for the fprime provided types. Implemented as a class with static + * constants to ensure that storage is not allocated although the definitions + * exist. + */ +struct BasicLimits : PlatformLimits { + static const int8_t I8_MIN = INT8_MIN; + static const int8_t I8_MAX = INT8_MAX; + static const uint8_t U8_MIN = 0; + static const uint8_t U8_MAX = UINT8_MAX; + + static const I16 I16_MIN = INT16_MIN; + static const I16 I16_MAX = INT16_MAX; + static const U16 U16_MIN = 0; + static const U16 U16_MAX = UINT16_MAX; + + static const I32 I32_MIN = INT32_MIN; + static const I32 I32_MAX = INT32_MAX; + static const U32 U32_MIN = 0; + static const U32 U32_MAX = UINT32_MAX; + + static const I64 I64_MIN = INT64_MIN; + static const I64 I64_MAX = INT64_MAX; + static const U64 U64_MIN = 0; + static const U64 U64_MAX = UINT64_MAX; +}; + #endif diff --git a/Fw/Types/ByteArray.hpp b/Fw/Types/ByteArray.hpp index 701bab4395..206dfba66c 100644 --- a/Fw/Types/ByteArray.hpp +++ b/Fw/Types/ByteArray.hpp @@ -13,7 +13,7 @@ #ifndef Fw_ByteArray_HPP #define Fw_ByteArray_HPP -#include "Fw/Types/BasicTypes.hpp" +#include namespace Fw { diff --git a/Fw/Types/CAssert.hpp b/Fw/Types/CAssert.hpp index 83392cfa66..93ef16871f 100644 --- a/Fw/Types/CAssert.hpp +++ b/Fw/Types/CAssert.hpp @@ -9,7 +9,6 @@ #define FWCASSERT_HPP_ #include -#include #if FW_ASSERT_LEVEL == FW_NO_ASSERT diff --git a/Fw/Types/CMakeLists.txt b/Fw/Types/CMakeLists.txt index b8d9b020ba..f784ab85d1 100644 --- a/Fw/Types/CMakeLists.txt +++ b/Fw/Types/CMakeLists.txt @@ -6,8 +6,9 @@ # # Note: using PROJECT_NAME as EXECUTABLE_NAME #### -set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Assert.cpp" - "${CMAKE_CURRENT_LIST_DIR}/Types.fpp" + +set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Types.fpp" + "${CMAKE_CURRENT_LIST_DIR}/Assert.cpp" "${CMAKE_CURRENT_LIST_DIR}/String.cpp" "${CMAKE_CURRENT_LIST_DIR}/InternalInterfaceString.cpp" "${CMAKE_CURRENT_LIST_DIR}/MallocAllocator.cpp" diff --git a/Fw/Types/ConstByteArray.hpp b/Fw/Types/ConstByteArray.hpp index 84e13bf33c..d1673d1568 100644 --- a/Fw/Types/ConstByteArray.hpp +++ b/Fw/Types/ConstByteArray.hpp @@ -13,7 +13,7 @@ #ifndef Fw_ConstByteArray_HPP #define Fw_ConstByteArray_HPP -#include "Fw/Types/BasicTypes.hpp" +#include namespace Fw { diff --git a/Fw/Types/EightyCharString.hpp b/Fw/Types/EightyCharString.hpp index f6ad97d5d1..48d4d893d9 100644 --- a/Fw/Types/EightyCharString.hpp +++ b/Fw/Types/EightyCharString.hpp @@ -1,7 +1,7 @@ #ifndef FW_EIGHTY_CHAR_STRING_TYPE_HPP #define FW_EIGHTY_CHAR_STRING_TYPE_HPP -#include +#include #include #include diff --git a/Fw/Types/GTest/Bytes.hpp b/Fw/Types/GTest/Bytes.hpp index 481989e783..0bc64b4273 100644 --- a/Fw/Types/GTest/Bytes.hpp +++ b/Fw/Types/GTest/Bytes.hpp @@ -14,7 +14,7 @@ #define Fw_GTest_Bytes_HPP #include -#include +#include namespace Fw { diff --git a/Fw/Types/InternalInterfaceString.hpp b/Fw/Types/InternalInterfaceString.hpp index 87505c5ff0..f8b9628100 100644 --- a/Fw/Types/InternalInterfaceString.hpp +++ b/Fw/Types/InternalInterfaceString.hpp @@ -1,10 +1,9 @@ #ifndef FW_INTERNAL_INTERFACE_STRING_TYPE_HPP #define FW_INTERNAL_INTERFACE_STRING_TYPE_HPP -#include +#include #include #include -#include namespace Fw { diff --git a/Fw/Types/Linux/StandardTypes.hpp b/Fw/Types/Linux/StandardTypes.hpp deleted file mode 100644 index 256a908d27..0000000000 --- a/Fw/Types/Linux/StandardTypes.hpp +++ /dev/null @@ -1,2 +0,0 @@ -#include -#include diff --git a/Fw/Types/MemAllocator.hpp b/Fw/Types/MemAllocator.hpp index 0d3fbac60d..521300f3a5 100644 --- a/Fw/Types/MemAllocator.hpp +++ b/Fw/Types/MemAllocator.hpp @@ -16,7 +16,7 @@ #ifndef TYPES_MEMALLOCATOR_HPP_ #define TYPES_MEMALLOCATOR_HPP_ -#include +#include /*! * diff --git a/Fw/Types/PolyType.cpp b/Fw/Types/PolyType.cpp index 0a5492b956..d0fb11a573 100644 --- a/Fw/Types/PolyType.cpp +++ b/Fw/Types/PolyType.cpp @@ -2,7 +2,6 @@ #include #include #define __STDC_FORMAT_MACROS -#include namespace Fw { @@ -411,7 +410,7 @@ namespace Fw { valIsEqual = false; break; default: - FW_ASSERT(0,static_cast(this->m_dataType)); + FW_ASSERT(0,static_cast(this->m_dataType)); return false; // for compiler } return valIsEqual; @@ -474,7 +473,7 @@ namespace Fw { result = false; break; default: - FW_ASSERT(0,static_cast(this->m_dataType)); + FW_ASSERT(0,static_cast(this->m_dataType)); return false; // for compiler } return result; diff --git a/Fw/Types/PolyType.hpp b/Fw/Types/PolyType.hpp index 29d616c928..8d16d97367 100644 --- a/Fw/Types/PolyType.hpp +++ b/Fw/Types/PolyType.hpp @@ -1,10 +1,9 @@ #ifndef FW_POLY_TYPE_HPP #define FW_POLY_TYPE_HPP -#include +#include #include #include -#include #include namespace Fw { diff --git a/Fw/Types/SerialBuffer.hpp b/Fw/Types/SerialBuffer.hpp index 97b935f904..f10b245f9d 100644 --- a/Fw/Types/SerialBuffer.hpp +++ b/Fw/Types/SerialBuffer.hpp @@ -13,7 +13,7 @@ #ifndef Fw_SerialBuffer_HPP #define Fw_SerialBuffer_HPP -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Serializable.hpp" namespace Fw { diff --git a/Fw/Types/Serializable.cpp b/Fw/Types/Serializable.cpp index d2afac76b9..ac0087fc9b 100644 --- a/Fw/Types/Serializable.cpp +++ b/Fw/Types/Serializable.cpp @@ -3,7 +3,7 @@ #include #include #include - +#include #ifdef BUILD_UT #include #include diff --git a/Fw/Types/Serializable.hpp b/Fw/Types/Serializable.hpp index 3a099d2fd6..ca48511925 100644 --- a/Fw/Types/Serializable.hpp +++ b/Fw/Types/Serializable.hpp @@ -5,7 +5,7 @@ #include #endif -#include +#include namespace Fw { diff --git a/Fw/Types/String.hpp b/Fw/Types/String.hpp index b9b60064d1..4c829f63a6 100644 --- a/Fw/Types/String.hpp +++ b/Fw/Types/String.hpp @@ -1,7 +1,7 @@ #ifndef FW_FIXED_LENGTH_STRING_TYPE_HPP #define FW_FIXED_LENGTH_STRING_TYPE_HPP -#include +#include #include #include diff --git a/Fw/Types/StringType.hpp b/Fw/Types/StringType.hpp index f411df79d2..4264e3fc96 100644 --- a/Fw/Types/StringType.hpp +++ b/Fw/Types/StringType.hpp @@ -13,7 +13,7 @@ #ifndef FW_STRING_TYPE_HPP #define FW_STRING_TYPE_HPP -#include +#include #include #ifdef BUILD_UT #include diff --git a/Fw/Types/StringUtils.hpp b/Fw/Types/StringUtils.hpp index d0aaba021a..26ecc8fceb 100644 --- a/Fw/Types/StringUtils.hpp +++ b/Fw/Types/StringUtils.hpp @@ -1,6 +1,6 @@ #ifndef FW_STRINGUTILS_HPP #define FW_STRINGUTILS_HPP -#include "Fw/Types/BasicTypes.hpp" +#include namespace Fw { namespace StringUtils { diff --git a/Fw/Types/VxWorks/StandardTypes.hpp b/Fw/Types/VxWorks/StandardTypes.hpp deleted file mode 100644 index ce32a75345..0000000000 --- a/Fw/Types/VxWorks/StandardTypes.hpp +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef VXWORKS_STD_TYPES_H -#define VXWORKS_STD_TYPES_H - -#include -#include - -// Covert VxWorks OK and ERROR macros to enums -enum { - VXWORKS_OK = OK, - VXWORKS_ERROR = ERROR -}; -#undef OK -#undef ERROR -enum { - OK = VXWORKS_OK, - ERROR = VXWORKS_ERROR -}; - -#endif diff --git a/Fw/Types/default/DefaultTypes.hpp b/Fw/Types/default/DefaultTypes.hpp new file mode 100644 index 0000000000..7815fda0f3 --- /dev/null +++ b/Fw/Types/default/DefaultTypes.hpp @@ -0,0 +1,97 @@ +/** + * \brief DefaultTypes.hpp provides fallback defaults for the platform types + * + * This fill contains default implementations for types typically defined in + * PlatformTypes.hpp. These default implementations are based on x86_64 Linux + * but are often appropriate for most systems. + */ +#include +/** +* Default implementation for deprecated (see note) + */ +#ifndef PLATFORM_INT_TYPE_DEFINED +typedef int PlatformIntType; +extern const PlatformIntType PlatformIntType_MIN; +extern const PlatformIntType PlatformIntType_MAX; +#define PLATFORM_INT_TYPE_DEFINED +#define PRI_PlatformIntType "d" +#endif + + +/** +* Default implementation for deprecated (see note) + */ +#ifndef PLATFORM_UINT_TYPE_DEFINED +typedef unsigned int PlatformUIntType; +extern const PlatformUIntType PlatformUIntType_MIN; +extern const PlatformUIntType PlatformUIntType_MAX; +#define PLATFORM_UINT_TYPE_DEFINED +#define PRI_PlatformUIntType "ud" +#endif + +/** +* Default implementation for ports indices +*/ +#ifndef PLATFORM_INDEX_TYPE_DEFINED +typedef PlatformIntType PlatformIndexType; +extern const PlatformIndexType PlatformIndexType_MIN; +extern const PlatformIndexType PlatformIndexType_MAX; +#define PLATFORM_INDEX_TYPE_DEFINED +#define PRI_PlatformIndexType PRI_PlatformIntType +#endif + +/** +* Default implementation for sizes +*/ +#ifndef PLATFORM_SIZE_TYPE_DEFINED +typedef PlatformUIntType PlatformSizeType; +extern const PlatformSizeType PlatformSizeType_MIN; +extern const PlatformSizeType PlatformSizeType_MAX; +#define PLATFORM_SIZE_TYPE_DEFINED +#define PRI_PlatformSizeType PRI_PlatformUIntType +#endif + +/** +* Default implementation for argument to fw_assert +*/ +#ifndef PLATFORM_ASSERT_ARG_TYPE_DEFINED +typedef PlatformIntType PlatformAssertArgType; +extern const PlatformAssertArgType PlatformAssertArgType_MIN; +extern const PlatformAssertArgType PlatformAssertArgType_MAX; +#define PLATFORM_ASSERT_ARG_TYPE_DEFINED +#define PRI_PlatformAssertArgType PRI_PlatformIntType +#endif + +/** +* Default implementation for pointers stored as integers +*/ +#ifndef PLATFORM_POINTER_CAST_TYPE_DEFINED + // Check for __SIZEOF_POINTER__ or cause error + #ifndef __SIZEOF_POINTER__ + #error "Compiler does not support __SIZEOF_POINTER__, cannot use default for PlatformPointerCastType" + #endif + + // Pointer sizes are determined by size of compiler + #if __SIZEOF_POINTER__ == 8 + typedef uint64_t PlatformPointerCastType; + extern const PlatformPointerCastType PlatformPointerCastType_MIN; + extern const PlatformPointerCastType PlatformPointerCastType_MAX; + #define PRI_PlatformPointerCastType PRIx64 + #elif __SIZEOF_POINTER__ == 4 + typedef uint32_t PlatformPointerCastType; + extern const PlatformPointerCastType PlatformPointerCastType_MIN; + extern const PlatformPointerCastType PlatformPointerCastType_MAX; + #define PRI_PlatformPointerCastType PRIx32 + #elif __SIZEOF_POINTER__ == 2 + typedef uint16_t PlatformPointerCastType; + extern const PlatformPointerCastType PlatformPointerCastType_MIN; + extern const PlatformPointerCastType PlatformPointerCastType_MAX; + #define PRI_PlatformPointerCastType PRIx16 + #else + typedef uint8_t PlatformPointerCastType; + extern const PlatformPointerCastType PlatformPointerCastType_MIN; + extern const PlatformPointerCastType PlatformPointerCastType_MAX; + #define PRI_PlatformPointerCastType PRIx8 + #endif + #define PLATFORM_POINTER_CAST_TYPE_DEFINED +#endif diff --git a/Fw/Types/test/ut/TypesTest.cpp b/Fw/Types/test/ut/TypesTest.cpp index f60a1da0f6..f0d96211ea 100644 --- a/Fw/Types/test/ut/TypesTest.cpp +++ b/Fw/Types/test/ut/TypesTest.cpp @@ -1,4 +1,4 @@ -#include +#include #include #include #include @@ -727,12 +727,12 @@ void AssertTest() { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ) { this->m_file = file; this->m_lineNo = lineNo; @@ -762,27 +762,27 @@ void AssertTest() { return this->m_numArgs; } - AssertArg getArg1() { + FwAssertArgType getArg1() { return this->m_arg1; } - AssertArg getArg2() { + FwAssertArgType getArg2() { return this->m_arg2; } - AssertArg getArg3() { + FwAssertArgType getArg3() { return this->m_arg3; } - AssertArg getArg4() { + FwAssertArgType getArg4() { return this->m_arg4; } - AssertArg getArg5() { + FwAssertArgType getArg5() { return this->m_arg5; } - AssertArg getArg6() { + FwAssertArgType getArg6() { return this->m_arg6; } @@ -798,12 +798,12 @@ void AssertTest() { FILE_NAME_ARG m_file = nullptr; NATIVE_UINT_TYPE m_lineNo = 0; NATIVE_UINT_TYPE m_numArgs = 0; - AssertArg m_arg1 = 0; - AssertArg m_arg2 = 0; - AssertArg m_arg3 = 0; - AssertArg m_arg4 = 0; - AssertArg m_arg5 = 0; - AssertArg m_arg6 = 0; + FwAssertArgType m_arg1 = 0; + FwAssertArgType m_arg2 = 0; + FwAssertArgType m_arg3 = 0; + FwAssertArgType m_arg4 = 0; + FwAssertArgType m_arg5 = 0; + FwAssertArgType m_arg6 = 0; bool m_asserted = false; }; diff --git a/Os/Baremetal/File.cpp b/Os/Baremetal/File.cpp index b516c227b1..fed6dee7b3 100644 --- a/Os/Baremetal/File.cpp +++ b/Os/Baremetal/File.cpp @@ -1,5 +1,4 @@ #include -#include #include #include diff --git a/Os/Baremetal/FileSystem.cpp b/Os/Baremetal/FileSystem.cpp index c2b87d0070..00ba4b9a83 100644 --- a/Os/Baremetal/FileSystem.cpp +++ b/Os/Baremetal/FileSystem.cpp @@ -1,5 +1,4 @@ #include -#include #include #include #include diff --git a/Os/Baremetal/Queue.cpp b/Os/Baremetal/Queue.cpp index fca6b74767..bfec97ae1f 100644 --- a/Os/Baremetal/Queue.cpp +++ b/Os/Baremetal/Queue.cpp @@ -5,7 +5,7 @@ // safety is implemented as this intended for baremetal devices. // Based on Os/Pthreads/Queue.cpp from @dinkel // ====================================================================== -#include +#include #include #include #include diff --git a/Os/Baremetal/TaskRunner/TaskRunner.cpp b/Os/Baremetal/TaskRunner/TaskRunner.cpp index 1b0b2b8610..d60eb97ee0 100644 --- a/Os/Baremetal/TaskRunner/TaskRunner.cpp +++ b/Os/Baremetal/TaskRunner/TaskRunner.cpp @@ -5,7 +5,7 @@ * Author: lestarch */ #include -#include +#include #include #include namespace Os { diff --git a/Os/Directory.hpp b/Os/Directory.hpp index 6d47e277f9..2aec3cf1ce 100644 --- a/Os/Directory.hpp +++ b/Os/Directory.hpp @@ -2,7 +2,6 @@ #define _Directory_hpp_ #include -#include namespace Os { diff --git a/Os/Event.hpp b/Os/Event.hpp index 3f28c22223..e8e41b8a46 100644 --- a/Os/Event.hpp +++ b/Os/Event.hpp @@ -7,7 +7,7 @@ #ifndef EVENT_HPP #define EVENT_HPP -#include +#include #include namespace Os { diff --git a/Os/File.hpp b/Os/File.hpp index 29b2752be4..f0082209fa 100644 --- a/Os/File.hpp +++ b/Os/File.hpp @@ -2,7 +2,6 @@ #define _File_hpp_ #include -#include namespace Os { diff --git a/Os/FileCommon.cpp b/Os/FileCommon.cpp index 6391c7f75e..47189248e9 100644 --- a/Os/FileCommon.cpp +++ b/Os/FileCommon.cpp @@ -1,5 +1,4 @@ #include -#include #include #include diff --git a/Os/FileSystem.hpp b/Os/FileSystem.hpp index c287a532ef..d6b6473359 100644 --- a/Os/FileSystem.hpp +++ b/Os/FileSystem.hpp @@ -2,7 +2,6 @@ #define _FileSystem_hpp_ #include -#include #include #define FILE_SYSTEM_CHUNK_SIZE (256u) diff --git a/Os/InterruptLock.hpp b/Os/InterruptLock.hpp index f39dc21e49..924a41e82e 100644 --- a/Os/InterruptLock.hpp +++ b/Os/InterruptLock.hpp @@ -1,7 +1,7 @@ #ifndef _InterruptLock_hpp_ #define _InterruptLock_hpp_ -#include +#include namespace Os { class InterruptLock { diff --git a/Os/IntervalTimer.hpp b/Os/IntervalTimer.hpp index 180fab068a..a606590408 100644 --- a/Os/IntervalTimer.hpp +++ b/Os/IntervalTimer.hpp @@ -7,7 +7,7 @@ #ifndef _IntervalTimer_hpp_ #define _IntervalTimer_hpp_ -#include +#include namespace Os { class IntervalTimer { diff --git a/Os/Linux/Directory.cpp b/Os/Linux/Directory.cpp index a554e1a9d5..6794e56e40 100644 --- a/Os/Linux/Directory.cpp +++ b/Os/Linux/Directory.cpp @@ -1,5 +1,4 @@ #include -#include #include #include diff --git a/Os/Linux/File.cpp b/Os/Linux/File.cpp index 48115784e9..8f63964957 100644 --- a/Os/Linux/File.cpp +++ b/Os/Linux/File.cpp @@ -1,5 +1,4 @@ #include -#include #include #include diff --git a/Os/Linux/FileSystem.cpp b/Os/Linux/FileSystem.cpp index 8cf9935bd0..df72e226a7 100644 --- a/Os/Linux/FileSystem.cpp +++ b/Os/Linux/FileSystem.cpp @@ -1,5 +1,4 @@ #include -#include #include #include #include diff --git a/Os/LocklessQueue.hpp b/Os/LocklessQueue.hpp index 9bc686a69d..2eb8f6044b 100644 --- a/Os/LocklessQueue.hpp +++ b/Os/LocklessQueue.hpp @@ -1,7 +1,7 @@ #ifndef _LOCKLESS_QUEUE_H_ #define _LOCKLESS_QUEUE_H_ -#include +#include #include #ifndef BUILD_DARWIN // Allow compiling #include diff --git a/Os/Log.hpp b/Os/Log.hpp index 38e36933a8..0690b19cd4 100644 --- a/Os/Log.hpp +++ b/Os/Log.hpp @@ -6,7 +6,7 @@ #ifndef _Log_hpp_ #define _Log_hpp_ -#include +#include #include namespace Os { diff --git a/Os/Mem.hpp b/Os/Mem.hpp index 05207d899b..2ef49c81a2 100644 --- a/Os/Mem.hpp +++ b/Os/Mem.hpp @@ -1,7 +1,7 @@ #ifndef _Mem_hpp_ #define _Mem_hpp_ -#include +#include #include #include diff --git a/Os/Mutex.hpp b/Os/Mutex.hpp index 692daf7ae6..9fc6507ff9 100644 --- a/Os/Mutex.hpp +++ b/Os/Mutex.hpp @@ -1,7 +1,7 @@ #ifndef _Mutex_hpp_ #define _Mutex_hpp_ -#include +#include namespace Os { diff --git a/Os/Pthreads/BufferQueue.hpp b/Os/Pthreads/BufferQueue.hpp index 222a3dff5e..78b3c73d0c 100644 --- a/Os/Pthreads/BufferQueue.hpp +++ b/Os/Pthreads/BufferQueue.hpp @@ -13,7 +13,7 @@ #ifndef OS_PTHREADS_BUFFER_QUEUE_HPP #define OS_PTHREADS_BUFFER_QUEUE_HPP -#include +#include // This is a generic buffer queue interface. namespace Os { diff --git a/Os/Pthreads/MaxHeap/MaxHeap.cpp b/Os/Pthreads/MaxHeap/MaxHeap.cpp index 5a6dc4e3c6..baa18a8071 100644 --- a/Os/Pthreads/MaxHeap/MaxHeap.cpp +++ b/Os/Pthreads/MaxHeap/MaxHeap.cpp @@ -15,7 +15,7 @@ // ====================================================================== #include "Os/Pthreads/MaxHeap/MaxHeap.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Assert.hpp" #include diff --git a/Os/Pthreads/MaxHeap/MaxHeap.hpp b/Os/Pthreads/MaxHeap/MaxHeap.hpp index c897347d77..22066c6d17 100644 --- a/Os/Pthreads/MaxHeap/MaxHeap.hpp +++ b/Os/Pthreads/MaxHeap/MaxHeap.hpp @@ -13,7 +13,7 @@ #ifndef OS_PTHREADS_MAX_HEAP_HPP #define OS_PTHREADS_MAX_HEAP_HPP -#include "Fw/Types/BasicTypes.hpp" +#include namespace Os { diff --git a/Os/Queue.hpp b/Os/Queue.hpp index ab98e2436a..56c7804042 100644 --- a/Os/Queue.hpp +++ b/Os/Queue.hpp @@ -12,7 +12,7 @@ #ifndef _Queue_hpp_ #define _Queue_hpp_ -#include +#include #include #include #include diff --git a/Os/QueueString.hpp b/Os/QueueString.hpp index 16f2f0b6d4..8b590f5ced 100644 --- a/Os/QueueString.hpp +++ b/Os/QueueString.hpp @@ -1,9 +1,8 @@ #ifndef OS_QUEUE_STRING_TYPE_HPP #define OS_QUEUE_STRING_TYPE_HPP -#include -#include #include +#include namespace Os { diff --git a/Os/Stubs/Linux/FileStub.cpp b/Os/Stubs/Linux/FileStub.cpp index 90c8cd4599..8b589cded7 100644 --- a/Os/Stubs/Linux/FileStub.cpp +++ b/Os/Stubs/Linux/FileStub.cpp @@ -1,5 +1,4 @@ #include -#include #include #include #include diff --git a/Os/SystemResources.hpp b/Os/SystemResources.hpp index 36f7bc7527..a1825762c6 100644 --- a/Os/SystemResources.hpp +++ b/Os/SystemResources.hpp @@ -12,7 +12,7 @@ #ifndef _SystemResources_hpp_ #define _SystemResources_hpp_ -#include +#include namespace Os { namespace SystemResources { diff --git a/Os/Task.hpp b/Os/Task.hpp index 2b403cf251..5e9d865195 100644 --- a/Os/Task.hpp +++ b/Os/Task.hpp @@ -2,7 +2,6 @@ #define _Task_hpp_ #include -#include #include #include diff --git a/Os/TaskLock.hpp b/Os/TaskLock.hpp index 957cfa690e..c044206c97 100644 --- a/Os/TaskLock.hpp +++ b/Os/TaskLock.hpp @@ -7,7 +7,7 @@ #ifndef _TaskLock_hpp_ #define _TaskLock_hpp_ -#include +#include namespace Os { class TaskLock { diff --git a/Os/TaskString.hpp b/Os/TaskString.hpp index 9b0befdc7d..1a100ed3ce 100644 --- a/Os/TaskString.hpp +++ b/Os/TaskString.hpp @@ -1,9 +1,8 @@ #ifndef OS_TASK_STRING_TYPE_HPP #define OS_TASK_STRING_TYPE_HPP -#include -#include #include +#include namespace Os { diff --git a/Os/ValidatedFile.hpp b/Os/ValidatedFile.hpp index 0f30cd811c..69d19feed7 100644 --- a/Os/ValidatedFile.hpp +++ b/Os/ValidatedFile.hpp @@ -14,7 +14,7 @@ #define OS_ValidatedFile_HPP #include "Fw/Types/String.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Os/ValidateFile.hpp" namespace Os { diff --git a/Os/WatchdogTimer.hpp b/Os/WatchdogTimer.hpp index 7593b7f2b0..ac409ba862 100644 --- a/Os/WatchdogTimer.hpp +++ b/Os/WatchdogTimer.hpp @@ -1,7 +1,7 @@ #ifndef _WatchdogTimer_hpp_ #define _WatchdogTimer_hpp_ -#include +#include namespace Os { class WatchdogTimer { diff --git a/RPI/RpiDemo/RpiDemoComponentImpl.cpp b/RPI/RpiDemo/RpiDemoComponentImpl.cpp index 618c27dfb2..fefec210f6 100644 --- a/RPI/RpiDemo/RpiDemoComponentImpl.cpp +++ b/RPI/RpiDemo/RpiDemoComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include namespace RPI { diff --git a/Ref/PingReceiver/PingReceiverComponentImpl.cpp b/Ref/PingReceiver/PingReceiverComponentImpl.cpp index 6b5ca46d0f..a4c77f7338 100644 --- a/Ref/PingReceiver/PingReceiverComponentImpl.cpp +++ b/Ref/PingReceiver/PingReceiverComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Ref { diff --git a/Ref/RecvBuffApp/RecvBuffComponentImpl.cpp b/Ref/RecvBuffApp/RecvBuffComponentImpl.cpp index 5abe54d39e..120960814e 100644 --- a/Ref/RecvBuffApp/RecvBuffComponentImpl.cpp +++ b/Ref/RecvBuffApp/RecvBuffComponentImpl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include diff --git a/Ref/SendBuffApp/SendBuffComponentImpl.cpp b/Ref/SendBuffApp/SendBuffComponentImpl.cpp index 5e7dd37d63..8d8865a6dc 100644 --- a/Ref/SendBuffApp/SendBuffComponentImpl.cpp +++ b/Ref/SendBuffApp/SendBuffComponentImpl.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include #include diff --git a/Ref/Top/FppConstantsAc.hpp b/Ref/Top/FppConstantsAc.hpp index 8d665860da..436a4edefd 100644 --- a/Ref/Top/FppConstantsAc.hpp +++ b/Ref/Top/FppConstantsAc.hpp @@ -12,7 +12,7 @@ #ifndef Ref_Top_FppConstantsAc_HPP #define Ref_Top_FppConstantsAc_HPP -#include "Fw/Types/BasicTypes.hpp" +#include namespace Ref { diff --git a/Svc/ActiveRateGroup/ActiveRateGroup.cpp b/Svc/ActiveRateGroup/ActiveRateGroup.cpp index 42a9b82b42..772b8ecca6 100644 --- a/Svc/ActiveRateGroup/ActiveRateGroup.cpp +++ b/Svc/ActiveRateGroup/ActiveRateGroup.cpp @@ -14,7 +14,7 @@ #include #include -#include +#include #include #include diff --git a/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp b/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp index 2cbea4117b..75d9d96eb7 100644 --- a/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp +++ b/Svc/ActiveRateGroup/ActiveRateGroupImpl.cpp @@ -14,7 +14,7 @@ #include #include -#include +#include #include #include diff --git a/Svc/ActiveTextLogger/ActiveTextLoggerImpl.cpp b/Svc/ActiveTextLogger/ActiveTextLoggerImpl.cpp index dd6fbd1fdf..5daa9318e0 100644 --- a/Svc/ActiveTextLogger/ActiveTextLoggerImpl.cpp +++ b/Svc/ActiveTextLogger/ActiveTextLoggerImpl.cpp @@ -94,7 +94,7 @@ namespace Svc { (void) snprintf(textStr, FW_INTERNAL_INTERFACE_STRING_MAX_SIZE, - "EVENT: (%d) (%04d-%02d-%02dT%02d:%02d:%02d.%03u) %s: %s\n", + "EVENT: (%" PRI_FwEventIdType ") (%04d-%02d-%02dT%02d:%02d:%02d.%03" PRIu32 ") %s: %s\n", id, tm.tm_year + 1900, tm.tm_mon + 1, tm.tm_mday, tm.tm_hour, tm.tm_min,tm.tm_sec,timeTag.getUSeconds(), severityString,text.toChar()); @@ -103,8 +103,8 @@ namespace Svc { (void) snprintf(textStr, FW_INTERNAL_INTERFACE_STRING_MAX_SIZE, - "EVENT: (%d) (%d:%d,%d) %s: %s\n", - id,timeTag.getTimeBase(),timeTag.getSeconds(),timeTag.getUSeconds(),severityString,text.toChar()); + "EVENT: (%" PRI_FwEventIdType ") (%" PRI_FwTimeBaseStoreType ":%" PRId32 ",%" PRId32 ") %s: %s\n", + id, static_cast(timeTag.getTimeBase()),timeTag.getSeconds(),timeTag.getUSeconds(),severityString,text.toChar()); } // Call internal interface so that everything else is done on component thread, diff --git a/Svc/ActiveTextLogger/LogFile.cpp b/Svc/ActiveTextLogger/LogFile.cpp index 0282e378bf..38d8e12028 100644 --- a/Svc/ActiveTextLogger/LogFile.cpp +++ b/Svc/ActiveTextLogger/LogFile.cpp @@ -119,7 +119,7 @@ namespace Svc { } NATIVE_INT_TYPE stat = snprintf(fileNameFinal,Fw::String::STRING_SIZE, - "%s%d",fileName,suffix); + "%s%" PRIu32,fileName,suffix); // If there was error, then just fail: if (stat <= 0) { diff --git a/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp b/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp index ff44a64432..eecf4bf7e0 100644 --- a/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp +++ b/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include #include @@ -24,12 +24,12 @@ namespace Fw { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6, + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6, CHAR* destBuffer, NATIVE_INT_TYPE buffSize ); @@ -72,12 +72,12 @@ namespace Svc { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ) { if (m_compPtr) { @@ -108,12 +108,12 @@ namespace Svc { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ) { diff --git a/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.hpp b/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.hpp index 4de9058e1b..61b3f65541 100644 --- a/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.hpp +++ b/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.hpp @@ -48,12 +48,12 @@ namespace Svc { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ); private: @@ -68,12 +68,12 @@ namespace Svc { FILE_NAME_ARG file, NATIVE_UINT_TYPE lineNo, NATIVE_UINT_TYPE numArgs, - AssertArg arg1, - AssertArg arg2, - AssertArg arg3, - AssertArg arg4, - AssertArg arg5, - AssertArg arg6 + FwAssertArgType arg1, + FwAssertArgType arg2, + FwAssertArgType arg3, + FwAssertArgType arg4, + FwAssertArgType arg5, + FwAssertArgType arg6 ); // Prevent actual assert since FATAL handler will deal with it diff --git a/Svc/BufferAccumulator/ArrayFIFOBuffer.cpp b/Svc/BufferAccumulator/ArrayFIFOBuffer.cpp index 0ef60c8f57..6df0c1a493 100644 --- a/Svc/BufferAccumulator/ArrayFIFOBuffer.cpp +++ b/Svc/BufferAccumulator/ArrayFIFOBuffer.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include "Svc/BufferAccumulator/BufferAccumulator.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Assert.hpp" diff --git a/Svc/BufferAccumulator/BufferAccumulator.cpp b/Svc/BufferAccumulator/BufferAccumulator.cpp index 5399518370..ea997b025a 100644 --- a/Svc/BufferAccumulator/BufferAccumulator.cpp +++ b/Svc/BufferAccumulator/BufferAccumulator.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include "Svc/BufferAccumulator/BufferAccumulator.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/BufferAccumulator/test/ut/Tester.cpp b/Svc/BufferAccumulator/test/ut/Tester.cpp index 068cb3484d..da253ea686 100644 --- a/Svc/BufferAccumulator/test/ut/Tester.cpp +++ b/Svc/BufferAccumulator/test/ut/Tester.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include "Tester.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/MallocAllocator.hpp" #define INSTANCE 0 diff --git a/Svc/BufferManager/BufferManagerComponentImpl.cpp b/Svc/BufferManager/BufferManagerComponentImpl.cpp index a1904fbe3c..a256f8c301 100644 --- a/Svc/BufferManager/BufferManagerComponentImpl.cpp +++ b/Svc/BufferManager/BufferManagerComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include +#include #include #include #include diff --git a/Svc/ComLogger/ComLogger.cpp b/Svc/ComLogger/ComLogger.cpp index dcd94cd244..2d10362a0d 100644 --- a/Svc/ComLogger/ComLogger.cpp +++ b/Svc/ComLogger/ComLogger.cpp @@ -5,7 +5,7 @@ // ---------------------------------------------------------------------- #include -#include +#include #include #include #include @@ -147,16 +147,16 @@ namespace Svc { // Create filename: Fw::Time timestamp = getTime(); memset(this->fileName, 0, sizeof(this->fileName)); - bytesCopied = snprintf(this->fileName, sizeof(this->fileName), "%s_%d_%d_%06d.com", - this->filePrefix, static_cast(timestamp.getTimeBase()), timestamp.getSeconds(), timestamp.getUSeconds()); + bytesCopied = snprintf(this->fileName, sizeof(this->fileName), "%s_%" PRI_FwTimeBaseStoreType "_%" PRIu32 "_%06" PRIu32 ".com", + this->filePrefix, static_cast(timestamp.getTimeBase()), timestamp.getSeconds(), timestamp.getUSeconds()); // "A return value of size or more means that the output was truncated" // See here: http://linux.die.net/man/3/snprintf FW_ASSERT( bytesCopied < sizeof(this->fileName) ); // Create sha filename: - bytesCopied = snprintf(this->hashFileName, sizeof(this->hashFileName), "%s_%d_%d_%06d.com%s", - this->filePrefix, static_cast(timestamp.getTimeBase()), timestamp.getSeconds(), timestamp.getUSeconds(), Utils::Hash::getFileExtensionString()); + bytesCopied = snprintf(this->hashFileName, sizeof(this->hashFileName), "%s_%" PRI_FwTimeBaseStoreType "_%" PRIu32 "_%06" PRIu32 ".com%s", + this->filePrefix, static_cast(timestamp.getTimeBase()), timestamp.getSeconds(), timestamp.getUSeconds(), Utils::Hash::getFileExtensionString()); FW_ASSERT( bytesCopied < sizeof(this->hashFileName) ); Os::File::Status ret = file.open(this->fileName, Os::File::OPEN_WRITE); diff --git a/Svc/ComLogger/ComLogger.hpp b/Svc/ComLogger/ComLogger.hpp index 1f0afc99ba..248efebd47 100644 --- a/Svc/ComLogger/ComLogger.hpp +++ b/Svc/ComLogger/ComLogger.hpp @@ -24,6 +24,13 @@ #define COMLOGGER_PATH_MAX 255 #endif +// some limits.h don't have NAME_MAX +#ifdef NAME_MAX +#define COMLOGGER_NAME_MAX NAME_MAX +#else +#define COMLOGGER_NAME_MAX 255 +#endif + namespace Svc { class ComLogger : @@ -81,7 +88,7 @@ namespace Svc { // ---------------------------------------------------------------------- // The maximum size of a filename enum { - MAX_FILENAME_SIZE = NAME_MAX, // as defined in limits.h + MAX_FILENAME_SIZE = COMLOGGER_NAME_MAX, MAX_PATH_SIZE = COMLOGGER_PATH_MAX }; diff --git a/Svc/ComSplitter/ComSplitter.cpp b/Svc/ComSplitter/ComSplitter.cpp index 7a8af5c816..963eb71504 100644 --- a/Svc/ComSplitter/ComSplitter.cpp +++ b/Svc/ComSplitter/ComSplitter.cpp @@ -5,7 +5,7 @@ // ---------------------------------------------------------------------- #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/Deframer/Deframer.cpp b/Svc/Deframer/Deframer.cpp index 5d9f1686d3..00a259a8c3 100644 --- a/Svc/Deframer/Deframer.cpp +++ b/Svc/Deframer/Deframer.cpp @@ -14,7 +14,7 @@ #include "Fw/Com/ComPacket.hpp" #include "Fw/Logger/Logger.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Svc/Deframer/Deframer.hpp" namespace Svc { diff --git a/Svc/Deframer/test/ut-fprime-protocol/GenerateFrames.hpp b/Svc/Deframer/test/ut-fprime-protocol/GenerateFrames.hpp index f1e6e1a41a..1e2487388b 100644 --- a/Svc/Deframer/test/ut-fprime-protocol/GenerateFrames.hpp +++ b/Svc/Deframer/test/ut-fprime-protocol/GenerateFrames.hpp @@ -7,7 +7,7 @@ #ifndef SVC_GENERATE_FRAMES_HPP #define SVC_GENERATE_FRAMES_HPP -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/StringType.hpp" #include "STest/STest/Pick/Pick.hpp" #include "STest/STest/Rule/Rule.hpp" diff --git a/Svc/Deframer/test/ut-fprime-protocol/SendBuffer.hpp b/Svc/Deframer/test/ut-fprime-protocol/SendBuffer.hpp index d642366917..0f21758709 100644 --- a/Svc/Deframer/test/ut-fprime-protocol/SendBuffer.hpp +++ b/Svc/Deframer/test/ut-fprime-protocol/SendBuffer.hpp @@ -7,7 +7,7 @@ #ifndef SVC_SEND_BUFFER_HPP #define SVC_SEND_BUFFER_HPP -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/StringType.hpp" #include "STest/STest/Pick/Pick.hpp" #include "STest/STest/Rule/Rule.hpp" diff --git a/Svc/FatalHandler/FatalHandlerComponentBaremetalImpl.cpp b/Svc/FatalHandler/FatalHandlerComponentBaremetalImpl.cpp index de7dbbef27..e62f4535ec 100644 --- a/Svc/FatalHandler/FatalHandlerComponentBaremetalImpl.cpp +++ b/Svc/FatalHandler/FatalHandlerComponentBaremetalImpl.cpp @@ -7,7 +7,7 @@ #include #include #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/FatalHandler/FatalHandlerComponentCommonImpl.cpp b/Svc/FatalHandler/FatalHandlerComponentCommonImpl.cpp index be76416c7b..42bd6ec9e4 100644 --- a/Svc/FatalHandler/FatalHandlerComponentCommonImpl.cpp +++ b/Svc/FatalHandler/FatalHandlerComponentCommonImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/FatalHandler/FatalHandlerComponentLinuxImpl.cpp b/Svc/FatalHandler/FatalHandlerComponentLinuxImpl.cpp index 9cb3a02d63..ff566bb731 100644 --- a/Svc/FatalHandler/FatalHandlerComponentLinuxImpl.cpp +++ b/Svc/FatalHandler/FatalHandlerComponentLinuxImpl.cpp @@ -14,7 +14,7 @@ #include #include #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/FatalHandler/FatalHandlerComponentVxWorksImpl.cpp b/Svc/FatalHandler/FatalHandlerComponentVxWorksImpl.cpp index 86f4a17922..25a8e689b1 100644 --- a/Svc/FatalHandler/FatalHandlerComponentVxWorksImpl.cpp +++ b/Svc/FatalHandler/FatalHandlerComponentVxWorksImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include diff --git a/Svc/FileDownlink/File.cpp b/Svc/FileDownlink/File.cpp index bb701afaf8..34cead16b6 100644 --- a/Svc/FileDownlink/File.cpp +++ b/Svc/FileDownlink/File.cpp @@ -12,7 +12,7 @@ #include #include -#include +#include #include namespace Svc { diff --git a/Svc/FileDownlink/FileDownlink.cpp b/Svc/FileDownlink/FileDownlink.cpp index ce1fff0121..40080d320a 100644 --- a/Svc/FileDownlink/FileDownlink.cpp +++ b/Svc/FileDownlink/FileDownlink.cpp @@ -11,7 +11,7 @@ #include #include -#include +#include #include #include #include diff --git a/Svc/FileManager/FileManager.cpp b/Svc/FileManager/FileManager.cpp index 9fb0564bef..6000fce879 100644 --- a/Svc/FileManager/FileManager.cpp +++ b/Svc/FileManager/FileManager.cpp @@ -15,7 +15,7 @@ #include "Svc/FileManager/FileManager.hpp" #include "Fw/Types/Assert.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/FileUplink/FileUplink.cpp b/Svc/FileUplink/FileUplink.cpp index ca3aecc7a6..bff997fc6d 100644 --- a/Svc/FileUplink/FileUplink.cpp +++ b/Svc/FileUplink/FileUplink.cpp @@ -12,7 +12,7 @@ #include #include -#include +#include namespace Svc { diff --git a/Svc/Framer/Framer.cpp b/Svc/Framer/Framer.cpp index 71e13dfb4c..873ff0f20a 100644 --- a/Svc/Framer/Framer.cpp +++ b/Svc/Framer/Framer.cpp @@ -12,7 +12,7 @@ #include #include "Fw/Logger/Logger.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Utils/Hash/Hash.hpp" namespace Svc { diff --git a/Svc/GenericHub/GenericHubComponentImpl.cpp b/Svc/GenericHub/GenericHubComponentImpl.cpp index 3757abf20c..0b6623fd12 100644 --- a/Svc/GenericHub/GenericHubComponentImpl.cpp +++ b/Svc/GenericHub/GenericHubComponentImpl.cpp @@ -13,7 +13,7 @@ #include #include "Fw/Logger/Logger.hpp" #include "Fw/Types/Assert.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include // Required port serialization or the hub cannot work static_assert(FW_PORT_SERIALIZATION, "FW_PORT_SERIALIZATION must be enabled to use GenericHub"); diff --git a/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp b/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp index e4c4d0d39d..7c1b710faf 100644 --- a/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp +++ b/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/GroundInterface/GroundInterface.cpp b/Svc/GroundInterface/GroundInterface.cpp index 0fe5b1343e..b400fc3476 100644 --- a/Svc/GroundInterface/GroundInterface.cpp +++ b/Svc/GroundInterface/GroundInterface.cpp @@ -6,7 +6,7 @@ #include #include -#include "Fw/Types/BasicTypes.hpp" +#include #include namespace Svc { diff --git a/Svc/GroundInterface/test/ut/DeframerRules.hpp b/Svc/GroundInterface/test/ut/DeframerRules.hpp index 647e5dd7bf..09d1f72cbf 100644 --- a/Svc/GroundInterface/test/ut/DeframerRules.hpp +++ b/Svc/GroundInterface/test/ut/DeframerRules.hpp @@ -15,7 +15,7 @@ #ifndef FPRIME_SVC_GROUND_INTERFACE_HPP #define FPRIME_SVC_GROUND_INTERFACE_HPP -#include +#include #include #include #include diff --git a/Svc/GroundInterface/test/ut/GroundInterfaceRules.hpp b/Svc/GroundInterface/test/ut/GroundInterfaceRules.hpp index ed3029691e..2808d677cb 100644 --- a/Svc/GroundInterface/test/ut/GroundInterfaceRules.hpp +++ b/Svc/GroundInterface/test/ut/GroundInterfaceRules.hpp @@ -15,7 +15,7 @@ #ifndef FPRIME_SVC_GROUND_INTERFACE_HPP #define FPRIME_SVC_GROUND_INTERFACE_HPP -#include +#include #include #include #include diff --git a/Svc/Health/HealthComponentImpl.cpp b/Svc/Health/HealthComponentImpl.cpp index 22dec74b72..c2400244e5 100644 --- a/Svc/Health/HealthComponentImpl.cpp +++ b/Svc/Health/HealthComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include namespace Svc { diff --git a/Svc/Health/Stub/HealthComponentStubChecks.cpp b/Svc/Health/Stub/HealthComponentStubChecks.cpp index 6510e8141e..051ba4e591 100644 --- a/Svc/Health/Stub/HealthComponentStubChecks.cpp +++ b/Svc/Health/Stub/HealthComponentStubChecks.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include diff --git a/Svc/Health/VxWorks/HealthComponentVxWorksChecks.cpp b/Svc/Health/VxWorks/HealthComponentVxWorksChecks.cpp index 6510e8141e..051ba4e591 100644 --- a/Svc/Health/VxWorks/HealthComponentVxWorksChecks.cpp +++ b/Svc/Health/VxWorks/HealthComponentVxWorksChecks.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include diff --git a/Svc/LinuxTimer/LinuxTimerComponentImplCommon.cpp b/Svc/LinuxTimer/LinuxTimerComponentImplCommon.cpp index 2f78012335..ec9158262b 100644 --- a/Svc/LinuxTimer/LinuxTimerComponentImplCommon.cpp +++ b/Svc/LinuxTimer/LinuxTimerComponentImplCommon.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/LinuxTimer/LinuxTimerComponentImplTaskDelay.cpp b/Svc/LinuxTimer/LinuxTimerComponentImplTaskDelay.cpp index 2278b2aba3..c0cc750674 100644 --- a/Svc/LinuxTimer/LinuxTimerComponentImplTaskDelay.cpp +++ b/Svc/LinuxTimer/LinuxTimerComponentImplTaskDelay.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include #include namespace Svc { diff --git a/Svc/LinuxTimer/LinuxTimerComponentImplTimerFd.cpp b/Svc/LinuxTimer/LinuxTimerComponentImplTimerFd.cpp index f113b17135..acf3b58efa 100644 --- a/Svc/LinuxTimer/LinuxTimerComponentImplTimerFd.cpp +++ b/Svc/LinuxTimer/LinuxTimerComponentImplTimerFd.cpp @@ -12,7 +12,7 @@ #include #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include #include diff --git a/Svc/PassiveConsoleTextLogger/ConsoleTextLoggerImplCommon.cpp b/Svc/PassiveConsoleTextLogger/ConsoleTextLoggerImplCommon.cpp index ac49b26cbf..bb27536235 100644 --- a/Svc/PassiveConsoleTextLogger/ConsoleTextLoggerImplCommon.cpp +++ b/Svc/PassiveConsoleTextLogger/ConsoleTextLoggerImplCommon.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include @@ -43,8 +43,8 @@ namespace Svc { severityString = "SEVERITY ERROR"; break; } - Fw::Logger::logMsg("EVENT: (%d) (%d:%d,%d) %s: %s\n", - id, timeTag.getTimeBase(), timeTag.getSeconds(), timeTag.getUSeconds(), - reinterpret_cast(severityString), reinterpret_cast(text.toChar())); + Fw::Logger::logMsg("EVENT: (%" PRI_FwEventIdType ") (%" PRI_FwTimeBaseStoreType ":%" PRIu32 ",%" PRIu32 ") %s: %s\n", + id, static_cast(timeTag.getTimeBase()), timeTag.getSeconds(), timeTag.getUSeconds(), + reinterpret_cast(severityString), reinterpret_cast(text.toChar())); } } diff --git a/Svc/PolyDb/PolyDbImpl.cpp b/Svc/PolyDb/PolyDbImpl.cpp index 03310344a0..48e4e4c1e3 100644 --- a/Svc/PolyDb/PolyDbImpl.cpp +++ b/Svc/PolyDb/PolyDbImpl.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include namespace Svc { PolyDbImpl::PolyDbImpl(const char* name) : PolyDbComponentBase(name) { diff --git a/Svc/RateGroupDriver/RateGroupDriver.cpp b/Svc/RateGroupDriver/RateGroupDriver.cpp index f3bfe29a70..082a10f0eb 100644 --- a/Svc/RateGroupDriver/RateGroupDriver.cpp +++ b/Svc/RateGroupDriver/RateGroupDriver.cpp @@ -1,5 +1,5 @@ #include -#include +#include #include #include #include diff --git a/Svc/RateGroupDriver/RateGroupDriver.hpp b/Svc/RateGroupDriver/RateGroupDriver.hpp index 3320d99257..57a3b18062 100644 --- a/Svc/RateGroupDriver/RateGroupDriver.hpp +++ b/Svc/RateGroupDriver/RateGroupDriver.hpp @@ -19,7 +19,7 @@ #define SVC_RATEGROUPDRIVER_HPP #include -#include +#include namespace Svc { diff --git a/Svc/StaticMemory/StaticMemoryComponentImpl.cpp b/Svc/StaticMemory/StaticMemoryComponentImpl.cpp index cdf48881b3..a50b8de30b 100644 --- a/Svc/StaticMemory/StaticMemoryComponentImpl.cpp +++ b/Svc/StaticMemory/StaticMemoryComponentImpl.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Types/Assert.hpp" namespace Svc { diff --git a/Svc/SystemResources/SystemResources.cpp b/Svc/SystemResources/SystemResources.cpp index 9e34edf5d0..c187348a10 100644 --- a/Svc/SystemResources/SystemResources.cpp +++ b/Svc/SystemResources/SystemResources.cpp @@ -13,7 +13,7 @@ #include //isnan() #include #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { diff --git a/Svc/TlmChan/TlmChanImpl.cpp b/Svc/TlmChan/TlmChanImpl.cpp index 69f16727ae..874bcd41be 100644 --- a/Svc/TlmChan/TlmChanImpl.cpp +++ b/Svc/TlmChan/TlmChanImpl.cpp @@ -11,7 +11,7 @@ */ #include #include -#include +#include #include #include diff --git a/Svc/TlmChan/TlmChanImplGet.cpp b/Svc/TlmChan/TlmChanImplGet.cpp index a5f54c7bce..fa630af75a 100644 --- a/Svc/TlmChan/TlmChanImplGet.cpp +++ b/Svc/TlmChan/TlmChanImplGet.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include diff --git a/Svc/TlmChan/TlmChanImplRecv.cpp b/Svc/TlmChan/TlmChanImplRecv.cpp index 4ea477b8ef..0aa2c91110 100644 --- a/Svc/TlmChan/TlmChanImplRecv.cpp +++ b/Svc/TlmChan/TlmChanImplRecv.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include diff --git a/Svc/TlmChan/TlmChanImplTask.cpp b/Svc/TlmChan/TlmChanImplTask.cpp index d44b9a1488..9415994ee0 100644 --- a/Svc/TlmChan/TlmChanImplTask.cpp +++ b/Svc/TlmChan/TlmChanImplTask.cpp @@ -12,7 +12,7 @@ #include #include -#include +#include #include #include #include diff --git a/Svc/TlmPacketizer/TlmPacketizer.cpp b/Svc/TlmPacketizer/TlmPacketizer.cpp index 32731b2b24..9235394af8 100644 --- a/Svc/TlmPacketizer/TlmPacketizer.cpp +++ b/Svc/TlmPacketizer/TlmPacketizer.cpp @@ -9,7 +9,7 @@ // acknowledged. #include -#include +#include #include namespace Svc { diff --git a/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp b/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp index 0e7405c2cc..bae4d1e91e 100644 --- a/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp +++ b/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp @@ -14,7 +14,7 @@ #ifndef SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ #define SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ -#include +#include namespace Svc { static const NATIVE_UINT_TYPE MAX_PACKETIZER_PACKETS = 200; diff --git a/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp b/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp index 4b6181a537..8c9885b3de 100644 --- a/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp +++ b/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include #include diff --git a/Svc/UdpSender/UdpSenderComponentImpl.cpp b/Svc/UdpSender/UdpSenderComponentImpl.cpp index 0271e2a928..9daa282562 100644 --- a/Svc/UdpSender/UdpSenderComponentImpl.cpp +++ b/Svc/UdpSender/UdpSenderComponentImpl.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include #include #include #include diff --git a/Utils/CRCChecker.hpp b/Utils/CRCChecker.hpp index 8d277af931..d15c23e2e9 100644 --- a/Utils/CRCChecker.hpp +++ b/Utils/CRCChecker.hpp @@ -12,7 +12,7 @@ #ifndef CRC_CHECKER_HPP #define CRC_CHECKER_HPP -#include +#include namespace Utils { diff --git a/Utils/Hash/HashBuffer.hpp b/Utils/Hash/HashBuffer.hpp index 71712081f9..eeee42da2a 100644 --- a/Utils/Hash/HashBuffer.hpp +++ b/Utils/Hash/HashBuffer.hpp @@ -13,7 +13,7 @@ #ifndef UTILS_HASH_BUFFER_HPP #define UTILS_HASH_BUFFER_HPP -#include +#include #include #include #include diff --git a/Utils/LockGuard.hpp b/Utils/LockGuard.hpp index b7e54c72ef..5b632101e3 100644 --- a/Utils/LockGuard.hpp +++ b/Utils/LockGuard.hpp @@ -12,7 +12,7 @@ #ifndef LockGuard_HPP #define LockGuard_HPP -#include +#include #include namespace Utils { diff --git a/Utils/RateLimiter.hpp b/Utils/RateLimiter.hpp index 58979fdcbd..8705bada36 100644 --- a/Utils/RateLimiter.hpp +++ b/Utils/RateLimiter.hpp @@ -13,7 +13,7 @@ #ifndef RateLimiter_HPP #define RateLimiter_HPP -#include +#include #include namespace Utils { diff --git a/Utils/TokenBucket.hpp b/Utils/TokenBucket.hpp index c4f171106d..845e279724 100644 --- a/Utils/TokenBucket.hpp +++ b/Utils/TokenBucket.hpp @@ -14,7 +14,7 @@ #ifndef TokenBucket_HPP #define TokenBucket_HPP -#include +#include #include #define MAX_TOKEN_BUCKET_TOKENS 1000 diff --git a/Utils/Types/CircularBuffer.cpp b/Utils/Types/CircularBuffer.cpp index 31d5fb34d7..594f55ca04 100644 --- a/Utils/Types/CircularBuffer.cpp +++ b/Utils/Types/CircularBuffer.cpp @@ -12,7 +12,7 @@ * Revised March 2022 * Author: bocchino */ -#include +#include #include #include diff --git a/Utils/Types/CircularBuffer.hpp b/Utils/Types/CircularBuffer.hpp index f62b7eca14..38720e839e 100644 --- a/Utils/Types/CircularBuffer.hpp +++ b/Utils/Types/CircularBuffer.hpp @@ -18,7 +18,6 @@ #define TYPES_CIRCULAR_BUFFER_HPP #include -#include #include //#define CIRCULAR_DEBUG diff --git a/Utils/Types/test/ut/CircularBuffer/CircularRules.hpp b/Utils/Types/test/ut/CircularBuffer/CircularRules.hpp index d24966098b..0d4484057b 100644 --- a/Utils/Types/test/ut/CircularBuffer/CircularRules.hpp +++ b/Utils/Types/test/ut/CircularBuffer/CircularRules.hpp @@ -19,7 +19,7 @@ #ifndef FPRIME_GROUNDINTERFACERULES_HPP #define FPRIME_GROUNDINTERFACERULES_HPP -#include +#include #include #include #include diff --git a/Utils/Types/test/ut/CircularBuffer/CircularState.hpp b/Utils/Types/test/ut/CircularBuffer/CircularState.hpp index b2c7b48723..535c29b569 100644 --- a/Utils/Types/test/ut/CircularBuffer/CircularState.hpp +++ b/Utils/Types/test/ut/CircularBuffer/CircularState.hpp @@ -7,7 +7,7 @@ * @author mstarch */ -#include +#include #include #ifndef FPRIME_CIRCULARSTATE_HPP diff --git a/Utils/test/ut/LockGuardTester.hpp b/Utils/test/ut/LockGuardTester.hpp index 009b236352..3d647897b7 100644 --- a/Utils/test/ut/LockGuardTester.hpp +++ b/Utils/test/ut/LockGuardTester.hpp @@ -15,7 +15,7 @@ #define LOCKGUARDTESTER_HPP #include "Utils/LockGuard.hpp" -#include +#include #include "gtest/gtest.h" namespace Utils { diff --git a/Utils/test/ut/RateLimiterTester.hpp b/Utils/test/ut/RateLimiterTester.hpp index c686cbefcb..90fef081ef 100644 --- a/Utils/test/ut/RateLimiterTester.hpp +++ b/Utils/test/ut/RateLimiterTester.hpp @@ -15,7 +15,7 @@ #define RATELIMITERTESTER_HPP #include "Utils/RateLimiter.hpp" -#include +#include #include "gtest/gtest.h" namespace Utils { diff --git a/Utils/test/ut/TokenBucketTester.hpp b/Utils/test/ut/TokenBucketTester.hpp index a8dfaffacb..9b6d162083 100644 --- a/Utils/test/ut/TokenBucketTester.hpp +++ b/Utils/test/ut/TokenBucketTester.hpp @@ -15,7 +15,7 @@ #define TOKENBUCKETTESTER_HPP #include "Utils/TokenBucket.hpp" -#include +#include #include "gtest/gtest.h" namespace Utils { diff --git a/ci/tests/RPI.bash b/ci/tests/RPI.bash index e52387532d..2f9af2c9ca 100755 --- a/ci/tests/RPI.bash +++ b/ci/tests/RPI.bash @@ -43,4 +43,4 @@ done # Test Completed echo -e "${GREEN}CI test ${FPUTIL_DEPLOYS} RPI SUCCESSFUL${NOCOLOR}" -archive_logs \ No newline at end of file +archive_logs diff --git a/cmake/platform/Darwin.cmake b/cmake/platform/Darwin.cmake index b8bbf56494..35a6a8c4da 100644 --- a/cmake/platform/Darwin.cmake +++ b/cmake/platform/Darwin.cmake @@ -19,5 +19,5 @@ if (NOT DEFINED FPRIME_USE_BAREMETAL_SCHEDULER) FIND_PACKAGE ( Threads REQUIRED ) endif() -# Add linux include path which is compatible with Darwin for StandardTypes.hpp -include_directories(SYSTEM "${FPRIME_FRAMEWORK_PATH}/Fw/Types/Linux") +# Add linux include path which is compatible with Darwin for PlatformTypes.hpp +include_directories(SYSTEM "${CMAKE_CURRENT_LIST_DIR}/types") diff --git a/cmake/platform/Linux.cmake b/cmake/platform/Linux.cmake index d8e71e19ea..89beac4d55 100644 --- a/cmake/platform/Linux.cmake +++ b/cmake/platform/Linux.cmake @@ -15,4 +15,5 @@ add_definitions(-DTGT_OS_TYPE_LINUX) set(FPRIME_USE_POSIX ON) # Add Linux specific headers into the system -include_directories(SYSTEM "${FPRIME_FRAMEWORK_PATH}/Fw/Types/Linux") +include_directories(SYSTEM "${CMAKE_CURRENT_LIST_DIR}/types") + diff --git a/cmake/platform/platform.cmake.template b/cmake/platform/platform.cmake.template index d38e04898c..c3c3b5087a 100644 --- a/cmake/platform/platform.cmake.template +++ b/cmake/platform/platform.cmake.template @@ -3,7 +3,7 @@ # # This file acts as a template for the fprime platform files used by the CMake system. # These files specify build flags, compiler directives, and must specify an include -# directory for system includes like "StandardTypes.hpp". +# directory for system includes like "PlatformTypes.hpp". # # Follow all the steps in this template to create a platform file. Ensure # to remove the platform-failsafe (step 1) and fill in all tags. @@ -29,7 +29,7 @@ # F prime platform files are used to set F prime specific settings. This allows the user to control # some aspects of the F prime build at the top-level. This means setting global include directories # compiler definitions for the platform, threading libraries, etc. The bare-minimum platform file -# should specify an include directory for "StandardTypes.hpp" and a threading library if using +# should specify an include directory for "PlatformTypes.hpp" and a threading library if using # active components with OS supported threads. This can be done with the following lines: # # ``` @@ -67,7 +67,7 @@ if (NOT DEFINED FPRIME_USE_BAREMETAL_SCHEDULER) FIND_PACKAGE ( Threads REQUIRED ) endif() -# STEP 5: Specify a directory containing the "StandardTypes.hpp" headers, as well +# STEP 5: Specify a directory containing the "PlatformTypes.hpp" headers, as well # as other system headers. Other global headers can be placed here. # Note: Typically, the Linux directory is a good default, as it grabs # standard types from . diff --git a/cmake/platform/types/PlatformTypes.hpp b/cmake/platform/types/PlatformTypes.hpp new file mode 100644 index 0000000000..4c4b3a5bd9 --- /dev/null +++ b/cmake/platform/types/PlatformTypes.hpp @@ -0,0 +1,129 @@ +/** + * \brief PlatformTypes.hpp for Linux/Darwin systems + * + * PlatformTypes.hpp is typically published by platform developers to define + * the standard available arithmetic types for use in fprime. This standard + * types header is designed to support standard Linux/Darwin distributions + * running on x86, x86_64 machines and using the standard gcc/clang compilers + * shipped with the operating system. + * + * As part of these definitions, we include min and max constants for each + * type. Implementors must define these constants in a C++ struct for two + * reasons: + * + * 1. static constants in structs do not incur storage when referred to + * in a static context without the need for optimization in gcc + * + * 2. static constants in structs can be inherited via private inheritance + * allowing the definitions to be available to descendant functions + * + * In C++ fprime code, users may then refer to FpLimits::PlatformIntType_MIN + * without referring to this header directly. + */ +#ifndef PLATFORM_TYPES_HPP_ +#define PLATFORM_TYPES_HPP_ +#include + +// Section 0: C Standard Types +// fprime depends on the existence of intN_t and uintN_t C standard ints and +// the mix/max values for those types. Platform developers must either: +// 1. define these types and definitions +// 2. include headers that define these types +// +// In addition, support for various type widths can be turned on/off with the +// switches in this section to control which of the C standard types are +// available in the system. fprime consumes this information and produces the +// UN, IN, and FN types we see in fprime code. +#include +#include +#include + +#define FW_HAS_64_BIT 1 //!< Architecture supports 64 bit integers +#define FW_HAS_32_BIT 1 //!< Architecture supports 32 bit integers +#define FW_HAS_16_BIT 1 //!< Architecture supports 16 bit integers +#define FW_HAS_F64 1 //!< Architecture supports 64 bit floating point numbers + +// Section 1: Logical Types +// fprime requires platform implementors to define logical types for their +// system. The list of logical types can be found in the document: +// docs/Design/numerical-types.md with the names of the form "Platform*" + +typedef int PlatformIntType; +#define PRI_PlatformIntType "d" + +typedef unsigned int PlatformUIntType; +#define PRI_PlatformUIntType "ud" + +typedef PlatformIntType PlatformIndexType; +#define PRI_PlatformIndexType PRI_PlatformIntType + +typedef PlatformUIntType PlatformSizeType; +#define PRI_PlatformSizeType PRI_PlatformUIntType + +typedef PlatformIntType PlatformAssertArgType; +#define PRI_PlatformAssertArgType PRI_PlatformIntType + +// Linux/Darwin definitions for pointer have various sizes across platforms +// and since these definitions need to be consistent we must ask the size. +#ifndef PLATFORM_POINTER_CAST_TYPE_DEFINED + // Check for __SIZEOF_POINTER__ or cause error + #ifndef __SIZEOF_POINTER__ + #error "Compiler does not support __SIZEOF_POINTER__, cannot use Linux/Darwin types" + #endif + + // Pointer sizes are determined by size of compiler + #if __SIZEOF_POINTER__ == 8 + typedef uint64_t PlatformPointerCastType; + #define PRI_PlatformPointerCastType PRIx64 + #elif __SIZEOF_POINTER__ == 4 + typedef uint32_t PlatformPointerCastType; + #define PRI_PlatformPointerCastType PRIx32 + #elif __SIZEOF_POINTER__ == 2 + typedef uint16_t PlatformPointerCastType; + #define PRI_PlatformPointerCastType PRIx16 + #else + typedef uint8_t PlatformPointerCastType; + #define PRI_PlatformPointerCastType PRIx8 + #endif +#endif +/** + * PlatformLimits: + * + * PlatformLimits define the min and max values for the constructs defined + * within this file. These must be defined as `static const` members to + * ensure that unnecessary storage is not allocated. + */ +struct PlatformLimits { + static const PlatformIntType PlatformIntType_MIN = std::numeric_limits::min(); + static const PlatformIntType PlatformIntType_MAX = std::numeric_limits::max(); + + static const PlatformUIntType PlatformUIntType_MIN = std::numeric_limits::min(); + static const PlatformUIntType PlatformUIntType_MAX = std::numeric_limits::max(); + + static const PlatformIndexType PlatformIndexType_MIN = PlatformIntType_MIN; + static const PlatformIndexType PlatformIndexType_MAX = PlatformIntType_MAX; + + static const PlatformSizeType PlatformSizeType_MIN = PlatformUIntType_MIN; + static const PlatformSizeType PlatformSizeType_MAX = PlatformUIntType_MAX; + + static const PlatformAssertArgType PlatformAssertArgType_MIN = PlatformIntType_MIN; + static const PlatformAssertArgType PlatformAssertArgType_MAX = PlatformIntType_MAX; + + // Pointer sizes are determined by size of compiler + #if __SIZEOF_POINTER__ == 8 + static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); + static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); + #elif __SIZEOF_POINTER__ == 4 + static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); + static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); + #elif __SIZEOF_POINTER__ == 2 + static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); + static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); + #elif __SIZEOF_POINTER__ == 1 + static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); + static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); + #else + #error "Unsupported pointer size" + #endif +}; +#endif //PLATFORM_TYPES_HPP_ diff --git a/config/BufferManagerComponentImplCfg.hpp b/config/BufferManagerComponentImplCfg.hpp index 08f271e46e..c3b4277953 100644 --- a/config/BufferManagerComponentImplCfg.hpp +++ b/config/BufferManagerComponentImplCfg.hpp @@ -1,7 +1,7 @@ #ifndef __BUFFERMANAGERCOMPONENTIMPLCFG_HPP__ #define __BUFFERMANAGERCOMPONENTIMPLCFG_HPP__ -#include +#include namespace Svc { static const NATIVE_UINT_TYPE BUFFERMGR_MAX_NUM_BINS = 10; diff --git a/config/DeframerCfg.hpp b/config/DeframerCfg.hpp index 7f3badc89d..64eed47649 100644 --- a/config/DeframerCfg.hpp +++ b/config/DeframerCfg.hpp @@ -7,7 +7,7 @@ #ifndef SVC_DEFRAMER_CFG_HPP #define SVC_DEFRAMER_CFG_HPP -#include +#include namespace Svc { namespace DeframerCfg { diff --git a/config/FileDownlinkCfg.hpp b/config/FileDownlinkCfg.hpp index 8c39633395..113e6e10e1 100644 --- a/config/FileDownlinkCfg.hpp +++ b/config/FileDownlinkCfg.hpp @@ -6,7 +6,7 @@ #ifndef SVC_FILEDOWNLINK_FILEDOWNLINKCFG_HPP_ #define SVC_FILEDOWNLINK_FILEDOWNLINKCFG_HPP_ -#include +#include namespace Svc { // If this is set to true, the run handler will look to diff --git a/config/FpConfig.hpp b/config/FpConfig.hpp index 3224a25264..12b10ecb30 100644 --- a/config/FpConfig.hpp +++ b/config/FpConfig.hpp @@ -11,80 +11,114 @@ */ #ifndef _FW_CONFIG_HPP_ #define _FW_CONFIG_HPP_ +#include -// To enable various facilities, set the below to 0 or 1. If it is set in compiler flags, -// these defaults will be overridden +typedef PlatformIndexType FwIndexType; +#define PRI_FwIndexType PRI_PlatformIndexType -// Available types +typedef PlatformSizeType FwSizeType; +#define PRI_FwSizeType PRI_PlatformSizeType -#ifndef FW_HAS_64_BIT -#define FW_HAS_64_BIT 1 //!< Architecture supports 64 bit integers -#endif +typedef PlatformAssertArgType FwAssertArgType; +#define PRI_FwAssertArgType PRI_PlatformAssertArgType -#ifndef FW_HAS_32_BIT -#define FW_HAS_32_BIT 1 //!< Architecture supports 32 bit integers -#endif -#ifndef FW_HAS_16_BIT -#define FW_HAS_16_BIT 1 //!< Architecture supports 16 bit integers -#endif +typedef PlatformIntType FwNativeIntType; +#define PRI_FwNativeIntType PRI_PlatformIntType -#ifndef FW_HAS_F64 -#define FW_HAS_F64 1 //!< Architecture supports 64 bit floating point numbers -#endif +typedef PlatformUIntType FwNativeUIntType; +#define PRI_FwNativeUIntType PRI_PlatformUIntType -// Boolean values for serialization +typedef U16 FwBuffSizeType; +#define PRI_FwBuffSizeType PRIu16 -#ifndef FW_SERIALIZE_TRUE_VALUE -#define FW_SERIALIZE_TRUE_VALUE (0xFF) //!< Value encoded during serialization for boolean true -#endif +typedef I32 FwEnumStoreType; +#define PRI_FwEnumStoreType PRId32 -#ifndef FW_SERIALIZE_FALSE_VALUE -#define FW_SERIALIZE_FALSE_VALUE (0x00) //!< Value encoded during serialization for boolean false -#endif +// Define enumeration for Time base types +enum TimeBase { + TB_NONE, //!< No time base has been established + TB_PROC_TIME, //!< Indicates time is processor cycle time. Not tied to external time + TB_WORKSTATION_TIME, //!< Time as reported on workstation where software is running. For testing. + TB_DONT_CARE = 0xFFFF //!< Don't care value for sequences. If FwTimeBaseStoreType is changed, value should be changed +}; +#define FW_CONTEXT_DONT_CARE 0xFF //!< Don't care value for time contexts in sequences -#ifndef AssertArg -#define AssertArg U32 -#endif +typedef U16 FwTimeBaseStoreType; +#define PRI_FwTimeBaseStoreType PRIu16 -// typedefs for various serialization items -// *** NOTE *** Changes here MUST match GSE in order to decode the values correctly +typedef U8 FwTimeContextStoreType; +#define PRI_FwTimeContextStoreType PRIu8 -#ifndef FwPacketDescriptorType -#define FwPacketDescriptorType U32 //!< Type representation for a packet descriptor -#endif +typedef U32 FwPacketDescriptorType; +#define PRI_FwPacketDescriptorType PRIu32 -#ifndef FwOpcodeType -#define FwOpcodeType U32 //!< Type representation for a command opcode -#endif +typedef U32 FwOpcodeType; +#define PRI_FwOpcodeType PRIu32 -#ifndef FwChanIdType -#define FwChanIdType U32 //!< Type representation for a channel id -#endif +typedef U32 FwChanIdType; +#define PRI_FwChanIdType PRIu32 -#ifndef FwEventIdType -#define FwEventIdType U32 //!< Type representation for an event id -#endif +typedef U32 FwEventIdType; +#define PRI_FwEventIdType PRIu32 -#ifndef FwPrmIdType -#define FwPrmIdType U32 //!< Type representation for a parameter id -#endif +typedef U32 FwPrmIdType; +#define PRI_FwPrmIdType PRIu32 -#ifndef FwTlmPacketizeIdType -#define FwTlmPacketizeIdType U16 //!< Packetized telemetry packet id -#endif +typedef U16 FwTlmPacketizeIdType; +#define PRI_FwTlmPacketizeIdType PRIu16 + +/** + * FpLimits: + * + * Sets the limit constants for the types defined int this file. Constants are + * defined as `static const` to ensure that storage is not allocated. This class + * inherits from BasicLimits and transitively from PlatformLimits such that it + * includes the limits included within those files. + * + **/ +struct FpLimits : BasicLimits { + static const FwIndexType FwIndexType_MIN = PlatformIndexType_MIN; + static const FwIndexType FwIndexType_MAX = PlatformIndexType_MAX; + static const FwSizeType FwSizeType_MIN = PlatformSizeType_MIN; + static const FwSizeType FwSizeType_MAX = PlatformSizeType_MAX; + static const FwAssertArgType FwAssertArgType_MIN = PlatformAssertArgType_MIN; + static const FwAssertArgType FwAssertArgType_MAX = PlatformAssertArgType_MAX; + static const FwNativeIntType FwNativeIntType_MIN = PlatformIntType_MIN; + static const FwNativeIntType FwNativeIntType_MAX = PlatformIntType_MAX; + static const FwNativeUIntType FwNativeUIntType_MIN = PlatformUIntType_MIN; + static const FwNativeUIntType FwNativeUIntType_MAX = PlatformUIntType_MAX; + static const FwBuffSizeType FwBuffSizeType_MIN = U16_MIN; + static const FwBuffSizeType FwBuffSizeType_MAX = U16_MAX; + static const FwEnumStoreType FwEnumStoreType_MIN = I32_MIN; + static const FwEnumStoreType FwEnumStoreType_MAX = I32_MAX; + static const FwTimeBaseStoreType FwTimeBaseStoreType_MIN = U16_MIN; + static const FwTimeBaseStoreType FwTimeBaseStoreType_MAX = U16_MAX; + static const FwTimeContextStoreType FwTimeContextStoreType_MIN = U8_MIN; + static const FwTimeContextStoreType FwTimeContextStoreType_MAX = U8_MAX; + static const FwPacketDescriptorType FwPacketDescriptorType_MIN = U32_MIN; + static const FwPacketDescriptorType FwPacketDescriptorType_MAX = U32_MAX; + static const FwOpcodeType FwOpcodeType_MIN = U32_MIN; + static const FwOpcodeType FwOpcodeType_MAX = U32_MAX; + static const FwChanIdType FwChanIdType_MIN = U32_MIN; + static const FwChanIdType FwChanIdType_MAX = U32_MAX; + static const FwEventIdType FwEventIdType_MIN = U32_MIN; + static const FwEventIdType FwEventIdType_MAX = U32_MAX; + static const FwPrmIdType FwPrmIdType_MIN = U32_MIN; + static const FwPrmIdType FwPrmIdType_MAX = U32_MAX; + static const FwTlmPacketizeIdType FwTlmPacketizeIdType_MIN = U16_MIN; + static const FwTlmPacketizeIdType FwTlmPacketizeIdType_MAX = U16_MAX; +}; -// How big the size of a buffer (or string) representation is -#ifndef FwBuffSizeType -#define FwBuffSizeType U16 //!< Type representation for storing a buffer or string size +// Boolean values for serialization +#ifndef FW_SERIALIZE_TRUE_VALUE +#define FW_SERIALIZE_TRUE_VALUE (0xFF) //!< Value encoded during serialization for boolean true #endif -// How many bits are used to store an enumeration defined in XML during serialization. -#ifndef FwEnumStoreType -#define FwEnumStoreType I32 //!< Type representation for an enumeration value +#ifndef FW_SERIALIZE_FALSE_VALUE +#define FW_SERIALIZE_FALSE_VALUE (0x00) //!< Value encoded during serialization for boolean false #endif -// Object facilities // Allow objects to have names. Allocates storage for each instance #ifndef FW_OBJECT_NAMES @@ -320,24 +354,6 @@ #define FW_AMPCS_COMPATIBLE 0 //!< Whether or not JPL AMPCS ground system support is enabled. #endif -// Define enumeration for Time base types -enum TimeBase { - TB_NONE, //!< No time base has been established - TB_PROC_TIME, //!< Indicates time is processor cycle time. Not tied to external time - TB_WORKSTATION_TIME, //!< Time as reported on workstation where software is running. For testing. - TB_DONT_CARE = 0xFFFF //!< Don't care value for sequences. If FwTimeBaseStoreType is changed, value should be changed -}; - -// How many bits are used to store the time base -#ifndef FwTimeBaseStoreType -#define FwTimeBaseStoreType U16 //!< Storage conversion for time base in scripts/ground interface -#endif - -#ifndef FwTimeContextStoreType -#define FwTimeContextStoreType U8 //!< Storage conversion for time context in scripts/ground interface -#define FW_CONTEXT_DONT_CARE 0xFF //!< Don't care value for time contexts in sequences -#endif - // These settings configure whether or not the timebase and context values for the Fw::Time // class are used. Some systems may not use or need those fields diff --git a/config/UdpReceiverComponentImplCfg.hpp b/config/UdpReceiverComponentImplCfg.hpp index c32d8e8e78..f09ee10e07 100644 --- a/config/UdpReceiverComponentImplCfg.hpp +++ b/config/UdpReceiverComponentImplCfg.hpp @@ -8,7 +8,7 @@ #ifndef SVC_UDPRECEIVER_UDPRECEIVERCOMPONENTIMPLCFG_HPP_ #define SVC_UDPRECEIVER_UDPRECEIVERCOMPONENTIMPLCFG_HPP_ -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { const static NATIVE_UINT_TYPE UDP_RECEIVER_MSG_SIZE = 256; diff --git a/config/UdpSenderComponentImplCfg.hpp b/config/UdpSenderComponentImplCfg.hpp index a39be283dc..3ed3660e06 100644 --- a/config/UdpSenderComponentImplCfg.hpp +++ b/config/UdpSenderComponentImplCfg.hpp @@ -8,7 +8,7 @@ #ifndef SVC_UDPSENDER_UDPSENDERCOMPONENTIMPLCFG_HPP_ #define SVC_UDPSENDER_UDPSENDERCOMPONENTIMPLCFG_HPP_ -#include "Fw/Types/BasicTypes.hpp" +#include namespace Svc { static const NATIVE_UINT_TYPE UDP_SENDER_MSG_SIZE = 256; diff --git a/docs/Design/numerical-types.md b/docs/Design/numerical-types.md index 3ff26d721e..f486b05b40 100644 --- a/docs/Design/numerical-types.md +++ b/docs/Design/numerical-types.md @@ -29,7 +29,7 @@ their compiler does not support. | F32 | float | n/a | | F64 | double | FW_HAS_F64 | -Platform developers should include `stdint.h` or equivalent in their `StandardTypes.hpp` file provided alongside their +Platform developers should include `stdint.h` or equivalent in their `PlatformTypes.hpp` file provided alongside their platform. If for some reason that header does not exist or does not define all types, then developers must define all "Equivalent" definitions above. @@ -41,6 +41,8 @@ U32 value = 10; printf("My value: %" PRId32, value); // Uses string constant concatenation ``` +Minimum and maximum limits are provided by `FpLimits` of the form `FpLimits::_MIN` and `FpLimits::_MAX`. + ## F´ Logical Integer Type Design @@ -57,37 +59,45 @@ projects need to be able to control these sizes when operating across multiple p ### Platform Configured Types -Platform developers should define the following logical types in the `StandardTypes.hpp` header provided alongside -their CMake platform and toolchain files. Each must also define a compiler directive to indicate the type was defined. -If the type is not specified as seen through the compiler directive the `DefaultTypes.hpp` header will fill in a default -definition. Each also defines a format specifier for use with the `printf` family of functions. Additionally, each -defines a pair of constants of the form `_MIN` and `_MAX` to define the minimum and maximum values. - -| Platform Logical Type | Compiler Directive | Default | Format Specifier | Notes | -|-------------------------|------------------------------------|------------------|-----------------------|-----------------------------| -| PlatformIndexType | PLATFORM_INDEX_TYPE_DEFINED | PlatformIntType | PRI_PlatformIndexType | Ports indices | -| PlatformSizeType | PLATFORM_SIZE_TYPE_DEFINED | PlatformUIntType | PRI_PlatformSizeType | Sizes | -| PlatformPointerCastType | PLATFORM_POINTER_CAST_TYPE_DEFINED | PlatformIntType | PRI_PointerCastType | Pointers stored as integers | -| PlatformAssertArgType | PLATFORM_ASSERT_ARG_TYPE_DEFINED | PlatformIntType | PRI_AssertArgType | Argument to FW_ASSERT | -| PlatformIntType | PLATFORM_INT_TYPE_DEFINED | int | PRI_PlatformIntType | Deprecated (see note) | -| PlatformUIntType | PLATFORM_UINT_TYPE_DEFINED | unsigned int | PRI_PlatformUIntType | Deprecated (see note) | - -A complete definition of a type as a platform should supply within `StandardTypes.hpp` is shown below. Notice the type -is defined along with a compiler directive announcing it is defined, and a format specifier. +Platform developers must define the following logical types in the `PlatformTypes.hpp` header provided alongside +their CMake platform and toolchain files. Each type also defines a format specifier for use with the `printf` family of +functions. Additionally, each defines a pair of static constants of the form `_MIN` and `_MAX` as limits to +the range of these values. All limits must be defined as public static constants or public static constant expressions +within a struct called `PlatformLimits`. For simplicity, structs are used to ensure all definitions are public. + +| Platform Logical Type | Format Specifier | Notes | +|-------------------------|-----------------------------|-----------------------------| +| PlatformIndexType | PRI_PlatformIndexType | Ports indices | +| PlatformSizeType | PRI_PlatformSizeType | Sizes | +| PlatformPointerCastType | PRI_PlatformPointerCastType | Pointers stored as integers | +| PlatformAssertArgType | PRI_PlatformAssertArgType | Argument to FW_ASSERT | +| PlatformIntType | PRI_PlatformIntType | Deprecated (see note) | +| PlatformUIntType | PRI_PlatformUIntType | Deprecated (see note) | + +A complete definition of each type for a given platform must be supplied within `PlatformTypes.hpp` as shown in the +example below. Notice the type is defined along with a format specifier and static constants are set in the +`PlatformLimits` struct. ```c++ typedef int32_t PlatformIndexType; -const PlatformIndexType PlatformIndexType_MIN = 0; -const PlatformIndexType PlatformIndexType_MAX = INT32_MAX; -#define PLATFORM_INDEX_TYPE_DEFINED #define PRI_PlatformIndexType PRId32 +... + +struct PlatformLimits { + ... + static const PlatformIndexType PlatformIndexType_MIN = 0; + static const PlatformIndexType PlatformIndexType_MAX = INT32_MAX; + ... +}; ``` -In order to print these types, developers can use the following example as a basis: +In order to print these types, developers can use the following example as a basis for using the PRI_* macros. This +example also shows the use of the type's minimum limit. ```c++ PlatformIndexType index = 3; -printf("Index: %" PRI_PlatformIndexType " is the index", index); // Uses string constant concatenation +// Print the above index type, and the minimum value supported by the same type +printf("Index %" PRI_PlatformIndexType " is bound by %" PRI_PlatformIndexType, index, FpLimits::PlatformIndexType_MIN); ``` **Note:** in order for F´ to compile without warnings it is necessary that each of the platform types are elements in @@ -95,23 +105,27 @@ the set of integers supplied by the C standard int header. i.e. each type is an `int64_t` or unsigned equivalents. On some compilers `int` and `unsigned int` are not members of that set and on those platforms it is imperative that both `PlatformIntType` and `PlatformUIntType` be set to some fixed size type instead. +Additionally, types are defined as public static const expressions within a struct for two reasons. First, it allows the +use of strongly typed constants without allocating storage for the constant nor requiring compiler optimization to +remove storage. Second, it allows inheritance such that all constants from `PlatformLimits`, `BasicLimits`, and +`FpLimits` (described below) are available through `FpLimits`. This implementation implies that one should never take +the address of one of these constants. + ### Configurable Integer Types Project may configure the framework types that the framework and components use for implementation through -`FpConfig.hpp`. The default configuration uses the above platform types where applicable. `_MIN` and `_MAX` -to define the minimum and maximum values. +`FpConfig.hpp`. The default configuration as supplied with F´uses the above platform types where applicable. +`_MIN` and `_MAX` limit constants are to be defined publicly within the `FpLimits` struct. The `FpLimits` +struct inherit from `BasicLimits` using private inheritance as shown in the example at the bottom of this section. -| Framework Type | Logical Usage | Default | Format Specifier | Notes | -|------------------------|----------------------------|-----------------------|----------------------|------------| -| FwIndexType | Port indices | PlatformIndexType | PRI_FwIndexType | | -| FwSizeType | Sizes | PlatformSizeType | PRI_FwSizeType | | -| FwAssertArg | Arguments to asserts | PlatformAssertArgType | PRI_FwAssertArgType | | -| FwNativeIntType | `int` | PlatformIntType | PRI_FwNativeIntType | Deprecated | -| FwNativeUIntType | `unsigned int` | PlatformUIntType | PRI_FwNativeUIntType | Deprecated | +| Framework Type | Logical Usage | Default | Format Specifier | Notes | +|-----------------|----------------------|-----------------------|---------------------|-------| +| FwIndexType | Port indices | PlatformIndexType | PRI_FwIndexType | | +| FwSizeType | Sizes | PlatformSizeType | PRI_FwSizeType | | +| FwAssertArgType | Arguments to asserts | PlatformAssertArgType | PRI_FwAssertArgType | | There is also a set of framework types that are used across F´ deployments and specifically interact with ground data -systems. `_MIN` and `_MAX` to define the minimum and maximum values. These GDS types are based on -configurable platform independent fixed-widths as shown below: +systems. These GDS types have defaults based on configurable platform independent fixed-widths as shown below: | GDS Type | Logical Usage | Default | Format Specifier | |------------------------|----------------------------|-----------------------|----------------------------| @@ -126,11 +140,18 @@ configurable platform independent fixed-widths as shown below: | FwPrmIdType | F´ parameter ids | U32 | PRI_FwPrmIdType | | FwTlmPacketizeIdType | F´ telemetry packet ids | U16 | PRI_FwTlmPacketizeIdType | -A complete definition of a framework/GDS type in `FpConfig.hpp` would look like: +All defaults can be overridden via project specific configuration supplying a custom `FpConfig.hpp`. A complete +definition of a framework/GDS type in `FpConfig.hpp` would look like: ```c++ +#include +... typedef uint32_t FwSizeType; -const FwSizeType PlatformIndexType_MIN = 0; -const FwSizeType PlatformIndexType_MAX = UINT32_MAX; #define PRI_FwSizeType PRIu32 +... + +struct FpLimits : BasicLimits { + const FwSizeType PlatformIndexType_MIN = 0; + const FwSizeType PlatformIndexType_MAX = UINT32_MAX; +}; ``` diff --git a/docs/Tutorials/GpsTutorial/Tutorial.md b/docs/Tutorials/GpsTutorial/Tutorial.md index bb63a1c940..210746a3a9 100644 --- a/docs/Tutorials/GpsTutorial/Tutorial.md +++ b/docs/Tutorials/GpsTutorial/Tutorial.md @@ -460,7 +460,7 @@ is not to demonstrate how to write each line of code, the steps above are called // ====================================================================== #include -#include "Fw/Types/BasicTypes.hpp" +#include #include "Fw/Logger/Logger.hpp" #include diff --git a/docs/Tutorials/MathComponent/MathReceiver/MathReceiver.cpp b/docs/Tutorials/MathComponent/MathReceiver/MathReceiver.cpp index 3e312eb09e..50340b3b5e 100644 --- a/docs/Tutorials/MathComponent/MathReceiver/MathReceiver.cpp +++ b/docs/Tutorials/MathComponent/MathReceiver/MathReceiver.cpp @@ -11,7 +11,7 @@ // ====================================================================== #include "Fw/Types/Assert.hpp" -#include "Fw/Types/BasicTypes.hpp" +#include #include "Ref/MathReceiver/MathReceiver.hpp" namespace Ref { diff --git a/docs/Tutorials/MathComponent/MathSender/MathSender.cpp b/docs/Tutorials/MathComponent/MathSender/MathSender.cpp index e74f498309..ad839ed6d2 100644 --- a/docs/Tutorials/MathComponent/MathSender/MathSender.cpp +++ b/docs/Tutorials/MathComponent/MathSender/MathSender.cpp @@ -12,7 +12,7 @@ #include -#include "Fw/Types/BasicTypes.hpp" +#include namespace Ref { diff --git a/docs/UsersGuide/cmake/cmake-platforms.md b/docs/UsersGuide/cmake/cmake-platforms.md index 6d8247f7ca..39622c08d5 100644 --- a/docs/UsersGuide/cmake/cmake-platforms.md +++ b/docs/UsersGuide/cmake/cmake-platforms.md @@ -4,7 +4,7 @@ Users can create platform-specific build files for the purposes of tailoring fpr for given platform targets. Any CMake toolchain file should work, but it will require a platform file created here to add target specific configuration using the name "${CMAKE_SYSTEM_NAME}.cmake". -At minimum this file can be blank, but more commonly included paths for "StandardTypes.hpp" to support. +At minimum this file can be blank, but more commonly included paths for "PlatformTypes.hpp" to support. Build flags, and other includes can be added in to support different compile time options. In addition, these files can define CMake option flags specific to the build. From 9a47389fd8064e53529bea9acdba63c4521f924d Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 6 Sep 2022 11:03:52 -0700 Subject: [PATCH 053/169] lestarch: adding join for the UART driver thread (#1651) --- Drv/LinuxUartDriver/LinuxUartDriver.cpp | 4 ++++ Drv/LinuxUartDriver/LinuxUartDriver.hpp | 3 +++ 2 files changed, 7 insertions(+) diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.cpp b/Drv/LinuxUartDriver/LinuxUartDriver.cpp index 6a6aeffddb..c2193762b2 100644 --- a/Drv/LinuxUartDriver/LinuxUartDriver.cpp +++ b/Drv/LinuxUartDriver/LinuxUartDriver.cpp @@ -368,4 +368,8 @@ void LinuxUartDriver ::quitReadThread() { this->m_quitReadThread = true; } +Os::Task::TaskStatus LinuxUartDriver ::join(void** value_ptr) { + return m_readTask.join(value_ptr); +} + } // end namespace Drv diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.hpp b/Drv/LinuxUartDriver/LinuxUartDriver.hpp index 5786c3c1a5..282ea5f106 100644 --- a/Drv/LinuxUartDriver/LinuxUartDriver.hpp +++ b/Drv/LinuxUartDriver/LinuxUartDriver.hpp @@ -55,6 +55,9 @@ class LinuxUartDriver : public LinuxUartDriverComponentBase { //! Quit thread void quitReadThread(); + //! Join thread + Os::Task::TaskStatus join(void** value_ptr); + //! Destroy object LinuxUartDriver //! ~LinuxUartDriver(); From 51ed8a3b0eeeb89736b443ba921a2ed3bf58709d Mon Sep 17 00:00:00 2001 From: kevin-f-ortega Date: Fri, 16 Sep 2022 05:20:59 -0700 Subject: [PATCH 054/169] fixed typos (#1656) --- Drv/ByteStreamDriverModel/docs/sdd.md | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/Drv/ByteStreamDriverModel/docs/sdd.md b/Drv/ByteStreamDriverModel/docs/sdd.md index a4db565059..28353014c2 100644 --- a/Drv/ByteStreamDriverModel/docs/sdd.md +++ b/Drv/ByteStreamDriverModel/docs/sdd.md @@ -41,7 +41,7 @@ The following components implement the byte stream model using a callback format ![Poll](./img/canvas-poll.png) -In the callback formation, The manager component (typically the ground interface) initiates the transfer of received +In the polling formation, the manager component (typically the ground interface) initiates the transfer of received data by calling the "poll" input port. This port fills in the provided `Fw::Buffer` along with a status for the poll. This status is an enumeration whose values are described in the following table: @@ -64,10 +64,3 @@ implementations running on baremetal machines. | BYTEDRV-001 | The ByteStreamDriverModel shall provide the capability to send bytes | inspection | | BYTEDRV-002 | The ByteStreamDriverModel shall provide the capability to poll for bytes | inspection | | BYTEDRV-003 | The ByteStreamDriverModel shall provide the capability to produce bytes | inspection | - -## Change Log - -| Date | Description | -|---|---| -| 2020-12-17 | Initial Draft | -| 2021-01-28 | Updated | From f8d9e307102466b93b366b8c2b36d251ef746c8b Mon Sep 17 00:00:00 2001 From: kevin-f-ortega Date: Fri, 16 Sep 2022 05:22:54 -0700 Subject: [PATCH 055/169] adding space after line number otherwise it combines with arg1. (#1655) --- Fw/Types/Assert.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Fw/Types/Assert.cpp b/Fw/Types/Assert.cpp index fe7ac60dba..06354e89dd 100644 --- a/Fw/Types/Assert.cpp +++ b/Fw/Types/Assert.cpp @@ -10,9 +10,9 @@ #else #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define fileIdFs "Assert file ID 0x%08X: Line: %" PRI_FwAssertArgType +#define fileIdFs "Assert file ID 0x%08X: Line: %" PRI_FwAssertArgType " " #else -#define fileIdFs "Assert file \"%s\": Line: %" PRI_FwAssertArgType +#define fileIdFs "Assert file \"%s\": Line: %" PRI_FwAssertArgType " " #endif namespace Fw { From 473cd5e0898225b5a15d41f981d9c12ce25232cd Mon Sep 17 00:00:00 2001 From: kevin-f-ortega Date: Mon, 19 Sep 2022 09:49:57 -0700 Subject: [PATCH 056/169] enhanced watchdogtimer capabilities (#1649) * enhanced watchdogtimer capabilities * replace getters with expire. The purose of the getters was to fulfill what expire does; so, no need for getters. --- Os/Linux/WatchdogTimer.cpp | 6 ++++++ Os/WatchdogTimer.hpp | 1 + 2 files changed, 7 insertions(+) diff --git a/Os/Linux/WatchdogTimer.cpp b/Os/Linux/WatchdogTimer.cpp index 79f7e0f6b7..e1b686ca87 100644 --- a/Os/Linux/WatchdogTimer.cpp +++ b/Os/Linux/WatchdogTimer.cpp @@ -1,4 +1,5 @@ #include +#include namespace Os { @@ -26,6 +27,11 @@ namespace Os { return WATCHDOG_CANCEL_ERROR; } + void WatchdogTimer::expire() { + FW_ASSERT(m_cb != nullptr); + m_cb(m_parameter); + } + } diff --git a/Os/WatchdogTimer.hpp b/Os/WatchdogTimer.hpp index ac409ba862..d25c4b7d0f 100644 --- a/Os/WatchdogTimer.hpp +++ b/Os/WatchdogTimer.hpp @@ -31,6 +31,7 @@ namespace Os { WatchdogStatus cancel(); //!< cancel timer + void expire(); //!< Invoke the callback function with m_parameter private: From e3216ff09ee0ddeb4d271f408353750ca31d2fa8 Mon Sep 17 00:00:00 2001 From: Sean Marquez Date: Mon, 19 Sep 2022 13:28:41 -0700 Subject: [PATCH 057/169] Update cross compile toolchain for raspberrypi in cmake & RPI CI (#1578) * install cross-compile tools using apt for RPI CI * apt install `gcc-arm-linux-gnueabihf` & `g++-arm-linux-gnueabihf` * check `/usr/arm-linux-gnueabihf` directory for RPI tools * use @astroesteban cmake toolchain for raspberrypi see https://github.com/nasa/fprime/issues/1163#issuecomment-1007810914 * check for arm toolchain by env var then PATH Check environment variable, RPI_TOOLCHAIN_DIR, first. If RPI_TOOLCHAIN_DIR not set, then check PATH See https://github.com/nasa/fprime/issues/1163#issuecomment-1133375177 * update expect.txt in .github/actions/spelling add to expect.txt: db multiarch objcopy objdump * fix typo for Raspberry in raspberrypi.cmake * set ARM toolchain variables using find_program() * add gdb to .github/actions/spelling/expect.txt * lestarch: removing GDB since it isn't used The build is failing to find gdb-multiarch, but GDB itself is not used in the CMake system. Thus, I am removing it here and leaving it up to the user to install/run their tooling. * lestarch: updateing installation in RPI readme Co-authored-by: M Starch --- .github/actions/spelling/expect.txt | 5 +++ .github/workflows/build-test-rpi.yml | 2 +- RPI/README.md | 9 ++++- ci/tests/RPI.bash | 2 +- cmake/toolchain/raspberrypi.cmake | 57 +++++++++++----------------- 5 files changed, 38 insertions(+), 37 deletions(-) diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 62c5b9d029..784802b695 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -264,6 +264,7 @@ DASSERT databinding datastore dawbarton +db DBUILD DCMAKE DDDTHH @@ -512,6 +513,7 @@ gcc gcda gcgandhi gcov +gdb gdiplus gencode genfile @@ -829,6 +831,7 @@ mstat mstring mtype mul +multiarch multioptionals multirequired multline @@ -891,7 +894,9 @@ numargs nums nxt objclass +objcopy objdoc +objdump objmodule objs oclc diff --git a/.github/workflows/build-test-rpi.yml b/.github/workflows/build-test-rpi.yml index 8f02c2e604..f1763f9c08 100644 --- a/.github/workflows/build-test-rpi.yml +++ b/.github/workflows/build-test-rpi.yml @@ -21,7 +21,7 @@ jobs: fetch-depth: 0 - uses: ./.github/actions/setup - name: Install RPI Toolchain - run: sudo git clone https://github.com/raspberrypi/tools.git /opt/rpi/tools + run: sudo apt update && sudo apt install -y gcc-arm-linux-gnueabihf g++-arm-linux-gnueabihf - name: F prime CI step run: ./ci/tests/RPI.bash - name: Copy Tests diff --git a/RPI/README.md b/RPI/README.md index 85593ded52..69053f62f4 100644 --- a/RPI/README.md +++ b/RPI/README.md @@ -39,7 +39,14 @@ If the UART port is not set up correctly, there will be a file open error. **Install the packages necessary to run the demo.** -Please see [INSTALL.md](../docs/INSTALL.md) to ensure that the F´ application has been installed and tested with the basic Ref. For cross-compiling, clone the cross-compile tools from [here](https://github.com/raspberrypi/tools). This demo has configuration files that assume that the tools have been installed in `/opt/rpi`. If they are installed elsewhere, the user can set the environment variable `RPI_TOOLCHAIN_DIR` to the full tools directory. e.g. in bash the user may run `export RPI_TOOLCHAIN_DIR=/opt/rpi/tools/arm-bcm2708/arm-rpi-4.9.3-linux-gnueabihf/`. +Please see [INSTALL.md](../docs/INSTALL.md) to ensure that the F´ application has been installed and tested with the basic Ref. Additionally, the +cross-compilers need to be installed. This is done by installing the `gcc-arm-linux-gnueabihf` and `g++-arm-linux-gnueabihf` packages on the host +system. This is shown on Ubuntu below. + +**Example: Installing Cross-Compilers for Raspberry PI on Ubuntu** +``` +sudo apt update && sudo apt install -y gcc-arm-linux-gnueabihf g++-arm-linux-gnueabihf +``` ### Build the software diff --git a/ci/tests/RPI.bash b/ci/tests/RPI.bash index 2f9af2c9ca..7072f5df08 100755 --- a/ci/tests/RPI.bash +++ b/ci/tests/RPI.bash @@ -21,7 +21,7 @@ export FPUTIL_DEPLOYS="${FPRIME_DIR}/RPI" echo -e "${BLUE}Starting CI test ${FPUTIL_DEPLOYS} RPI${NOCOLOR}" export CMAKE_EXTRA_SETTINGS="" -if [ ! -d "/opt/rpi/tools/arm-bcm2708/arm-rpi-4.9.3-linux-gnueabihf" ] +if [ ! -d "/usr/arm-linux-gnueabihf" ] then warn_and_cont "RPI tools not installed, refusing to test." continue diff --git a/cmake/toolchain/raspberrypi.cmake b/cmake/toolchain/raspberrypi.cmake index 4ae1b7f846..500c23acc2 100644 --- a/cmake/toolchain/raspberrypi.cmake +++ b/cmake/toolchain/raspberrypi.cmake @@ -1,41 +1,30 @@ #### # Raspberry PI Toolchain # -# A toolchain file for the raspberrypi. This toolchain can be used to build against the raspberry pi embedded Linux -# target. In order to use this toolchain, the raspberry pi build tools should be cloned onto a Linux build host. These -# tools are available at: [https://github.com/raspberrypi/tools](https://github.com/raspberrypi/tools) -# -# Typically these tools are cloned to `/opt/rpi/`. If they are cloned elsewhere, the user must set the environment -# variable `RPI_TOOLCHAIN_DIR` to the full path to the `arm-bcm2708/arm-rpi-4.9.3-linux-gnueabihf` directory before -# running CMake or `fprime-util generate`. -# -# e.g. should the user install the tools in ``/home/user1` then the environment variable might be set using -# `export RPI_TOOLCHAIN_DIR=/home/user/tools/arm-bcm2708/arm-rpi-4.9.3-linux-gnueabihf/` +# This is a toolchain for the Raspberry Pi. This toolchain can be used ot build +# against the Raspberry Pi embedded Linux target. In order to use this toolchain, +# the Raspberry Pi cross-compiler should be installed on a Linux host. These +# tools are installable as follows: +# sudo apt install gcc-arm-linux-gnueabihf g++-arm-linux-gnueabihf gdb-multiarch #### -# Set system name -set(CMAKE_SYSTEM_NAME "Linux") -set(CMAKE_SYSTEM_PROCESSOR "arm") -# Location of pi toolchain -set(RPI_TOOLCHAIN "$ENV{RPI_TOOLCHAIN_DIR}") -if ("${RPI_TOOLCHAIN}" STREQUAL "") - set(RPI_TOOLCHAIN "/opt/rpi/tools/arm-bcm2708/arm-rpi-4.9.3-linux-gnueabihf") -endif() -# Check toolchain directory exists -IF(NOT EXISTS "${RPI_TOOLCHAIN}") - message(FATAL_ERROR "RPI toolchain not found at ${RPI_TOOLCHAIN}. Install it, set RPI_TOOLCHAIN_DIR environment variable, or choose another toolchain") -endif() -message(STATUS "Using RPI toolchain at: ${RPI_TOOLCHAIN}") -# specify the cross compiler -set(CMAKE_C_COMPILER "${RPI_TOOLCHAIN}/bin/arm-linux-gnueabihf-gcc") -set(CMAKE_CXX_COMPILER "${RPI_TOOLCHAIN}/bin/arm-linux-gnueabihf-g++") +# Set the system information +set(CMAKE_SYSTEM_NAME Linux) +set(CMAKE_SYSTEM_PROCESSOR arm) +set(CMAKE_SYSTEM_VERSION 1) -# where is the target environment -set(CMAKE_FIND_ROOT_PATH "${RPI_TOOLCHAIN}") +# Set the GNU ARM toolchain +find_program(CMAKE_AR NAMES arm-linux-gnueabihf-ar PATHS ENV RPI_TOOLCHAIN_DIR PATH_SUFFIXES bin REQUIRED) +find_program(CMAKE_C_COMPILER NAMES arm-linux-gnueabihf-gcc PATHS ENV RPI_TOOLCHAIN_DIR PATH_SUFFIXES bin REQUIRED) +find_program(CMAKE_CXX_COMPILER NAMES arm-linux-gnueabihf-g++ PATHS ENV RPI_TOOLCHAIN_DIR PATH_SUFFIXES bin REQUIRED) +message(STATUS "[arm-linux] C Compiler: ${CMAKE_C_COMPILER}") +message(STATUS "[arm-linux] CXX Compiler: ${CMAKE_CXX_COMPILER}") +find_program(CMAKE_ASM_COMPILER NAMES arm-linux-gnueabihf-as PATHS ENV RPI_TOOLCHAIN_DIR PATH_SUFFIXES bin REQUIRED) +find_program(CMAKE_OBJCOPY NAMES arm-linux-gnueabihf-objcopy PATHS ENV RPI_TOOLCHAIN_DIR PATH_SUFFIXES bin REQUIRED) +find_program(CMAKE_OBJDUMP NAMES arm-linux-gnueabihf-objdump PATHS ENV RPI_TOOLCHAIN_DIR PATH_SUFFIXES bin REQUIRED) -# search for programs in the build host directories -set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) -# for libraries and headers in the target directories -set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) -set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) -set(CMAKE_FIND_ROOT_PATH_MODE_PACKAGE ONLY) +# Configure the find commands for finding the toolchain +set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) +set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY NEVER) +set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE NEVER) +set(CMAKE_FIND_ROOT_PATH_MODE_PACKAGE NEVER) From 3c23396adbbacc0f935927b41f919f6d0be81fe7 Mon Sep 17 00:00:00 2001 From: Tiffany Chieu Date: Mon, 19 Sep 2022 13:29:43 -0700 Subject: [PATCH 058/169] FPP CMake integration (#1629) * Filter ai_xml sources against generated sources * Remove quotes from GENERATED_SOURCES * lestarch: reworking generated files as list Co-authored-by: M Starch --- cmake/autocoder/ai_xml.cmake | 18 +++++++++++++++++- cmake/autocoder/autocoder.cmake | 7 ++++--- 2 files changed, 21 insertions(+), 4 deletions(-) diff --git a/cmake/autocoder/ai_xml.cmake b/cmake/autocoder/ai_xml.cmake index 007ddf344b..318e856cca 100644 --- a/cmake/autocoder/ai_xml.cmake +++ b/cmake/autocoder/ai_xml.cmake @@ -15,9 +15,25 @@ autocoder_setup_for_individual_sources() # # Required function, processes ComponentAi.xml files. # `AC_INPUT_FILE` potential input to the autocoder +# ...: any number of arguments representing a list of previously generated files #### function(ai_xml_is_supported AC_INPUT_FILE) - autocoder_support_by_suffix("Ai.xml" "${AC_INPUT_FILE}") + ends_with(IS_SUPPORTED "${AC_INPUT_FILE}" "Ai.xml") + set(PREVIOUSLY_GENERATED) + if (ARGC GREATER_EQUAL 2) + set(PREVIOUSLY_GENERATED ${ARGV2}) + endif() + + # Don't generate cpp/hpp files that have already been generated + if (IS_SUPPORTED) + string(REPLACE "Ai.xml" "Ac.cpp" CPP_FILE "${AC_INPUT_FILE}") + string(REPLACE "Ai.xml" "Ac.hpp" HPP_FILE "${AC_INPUT_FILE}") + if(("${CPP_FILE}" IN_LIST PREVIOUSLY_GENERATED) AND ("${HPP_FILE}" IN_LIST PREVIOUSLY_GENERATED)) + set(IS_SUPPORTED FALSE) + endif() + endif() + # Note: set in PARENT_SCOPE in macro is intended. Caller **wants** to set IS_SUPPORTED in their parent's scope. + set(IS_SUPPORTED "${IS_SUPPORTED}" PARENT_SCOPE) endfunction (ai_xml_is_supported) #### diff --git a/cmake/autocoder/autocoder.cmake b/cmake/autocoder/autocoder.cmake index 317d860f7f..db3e6b47b3 100644 --- a/cmake/autocoder/autocoder.cmake +++ b/cmake/autocoder/autocoder.cmake @@ -55,7 +55,7 @@ function(run_ac AUTOCODER_CMAKE SOURCES GENERATED_SOURCES) plugin_include_helper(AUTOCODER_NAME "${AUTOCODER_CMAKE}" is_supported setup_autocode get_generated_files get_dependencies) # Normalize and filter source paths so that what we intend to run is in a standard form normalize_paths(AC_INPUT_SOURCES "${SOURCES}" "${GENERATED_SOURCES}") - _filter_sources(AC_INPUT_SOURCES "${AC_INPUT_SOURCES}") + _filter_sources(AC_INPUT_SOURCES "${GENERATED_SOURCES}" "${AC_INPUT_SOURCES}") # Break early if there are no sources, no need to autocode nothing if (NOT AC_INPUT_SOURCES) @@ -184,14 +184,15 @@ endfunction() # including an autocoder's CMake file and thus setting the active autocoder. Helper function. # # OUTPUT_NAME: name of output variable to set in parent scope +# GENERATED_SOURCES: sources created by other autocoders # ...: any number of arguments containing lists of sources #### -function(_filter_sources OUTPUT_NAME) +function(_filter_sources OUTPUT_NAME GENERATED_SOURCES) set(OUTPUT_LIST) # Loop over the list and check foreach (SOURCE_LIST IN LISTS ARGN) foreach(SOURCE IN LISTS SOURCE_LIST) - cmake_language(CALL "${AUTOCODER_NAME}_is_supported" "${SOURCE}") + cmake_language(CALL "${AUTOCODER_NAME}_is_supported" "${SOURCE}" "${GENERATED_SOURCES}") if (IS_SUPPORTED) list(APPEND OUTPUT_LIST "${SOURCE}") endif() From 604fcfca87fc5eff0cb74c3cab1ea9a03ee8b07b Mon Sep 17 00:00:00 2001 From: redixin Date: Mon, 26 Sep 2022 19:12:11 +0300 Subject: [PATCH 059/169] Raise proper exceptions in python generators (#1660) --- .../fprime_ac/generators/AbstractGenerator.py | 6 ++--- .../src/fprime_ac/generators/ChannelBody.py | 4 ++-- .../src/fprime_ac/generators/ChannelHeader.py | 4 ++-- .../src/fprime_ac/generators/CommandBody.py | 4 ++-- .../src/fprime_ac/generators/CommandHeader.py | 4 ++-- .../src/fprime_ac/generators/DictBody.py | 4 ++-- .../src/fprime_ac/generators/DictHeader.py | 4 ++-- .../src/fprime_ac/generators/DictStart.py | 4 ++-- .../src/fprime_ac/generators/EventBody.py | 4 ++-- .../src/fprime_ac/generators/EventHeader.py | 4 ++-- .../src/fprime_ac/generators/FinishSource.py | 4 ++-- .../src/fprime_ac/generators/HtmlDocPage.py | 4 ++-- .../src/fprime_ac/generators/HtmlStartPage.py | 4 ++-- .../src/fprime_ac/generators/Includes1.py | 4 ++-- .../src/fprime_ac/generators/Includes2.py | 4 ++-- .../src/fprime_ac/generators/InitFiles.py | 4 ++-- .../fprime_ac/generators/InstanceDictBody.py | 4 ++-- .../generators/InstanceDictHeader.py | 4 ++-- .../fprime_ac/generators/InstanceDictStart.py | 4 ++-- .../src/fprime_ac/generators/MdDocPage.py | 4 ++-- .../src/fprime_ac/generators/MdStartPage.py | 4 ++-- .../src/fprime_ac/generators/Namespace.py | 4 ++-- .../src/fprime_ac/generators/Private.py | 4 ++-- .../src/fprime_ac/generators/Protected.py | 4 ++-- .../Python/src/fprime_ac/generators/Public.py | 4 ++-- .../src/fprime_ac/generators/StartChannel.py | 4 ++-- .../src/fprime_ac/generators/StartCommand.py | 4 ++-- .../src/fprime_ac/generators/StartEvent.py | 4 ++-- .../src/fprime_ac/generators/StartSource.py | 4 ++-- .../src/fprime_ac/generators/formatters.py | 8 +++---- .../generators/visitors/AbstractVisitor.py | 24 +++++++++---------- .../generators/visitors/CommandVisitor.py | 2 +- .../visitors/InstanceChannelVisitor.py | 2 +- .../visitors/InstanceEventVisitor.py | 2 +- 34 files changed, 78 insertions(+), 78 deletions(-) diff --git a/Autocoders/Python/src/fprime_ac/generators/AbstractGenerator.py b/Autocoders/Python/src/fprime_ac/generators/AbstractGenerator.py index dc4e0560ea..de18671938 100644 --- a/Autocoders/Python/src/fprime_ac/generators/AbstractGenerator.py +++ b/Autocoders/Python/src/fprime_ac/generators/AbstractGenerator.py @@ -57,7 +57,7 @@ def __call__(self, args): Main execution point. Calls the accept method on each visitor to generate the code. """ - raise Exception( + raise NotImplementedError( "AbstractGenerator.__call__() - Implementation Error: you must supply your own concrete implementation." ) @@ -65,7 +65,7 @@ def accept(self, visitor): """ Execute the visit call on this object. """ - raise Exception( + raise NotImplementedError( "AbstractFace.accept.accept(v) - Implementation Error: you must supply your own concrete implementation." ) @@ -73,6 +73,6 @@ def addVisitor(self, visitor): """ Method to add the visitor to a list of visitors. """ - raise Exception( + raise NotImplementedError( "AbstractFace.accept.addVisitor(v) - Implementation Error: you must supply your own concrete implementation." ) diff --git a/Autocoders/Python/src/fprime_ac/generators/ChannelBody.py b/Autocoders/Python/src/fprime_ac/generators/ChannelBody.py index c84a65f632..4471c0e78b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/ChannelBody.py +++ b/Autocoders/Python/src/fprime_ac/generators/ChannelBody.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "ChannelBody.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "ChannelBody.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "ChannelBody.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "ChannelBody.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/ChannelHeader.py b/Autocoders/Python/src/fprime_ac/generators/ChannelHeader.py index 73c8b33eac..c2fe6a60e5 100644 --- a/Autocoders/Python/src/fprime_ac/generators/ChannelHeader.py +++ b/Autocoders/Python/src/fprime_ac/generators/ChannelHeader.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "ChannelHeader.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "ChannelHeader.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "ChannelHeader.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "ChannelHeader.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/CommandBody.py b/Autocoders/Python/src/fprime_ac/generators/CommandBody.py index f37b5c57f1..35c81bf8ac 100644 --- a/Autocoders/Python/src/fprime_ac/generators/CommandBody.py +++ b/Autocoders/Python/src/fprime_ac/generators/CommandBody.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "startCommandVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "startCommandVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "startCommandVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "startCommandVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/CommandHeader.py b/Autocoders/Python/src/fprime_ac/generators/CommandHeader.py index cadd440263..66bc1f29c7 100644 --- a/Autocoders/Python/src/fprime_ac/generators/CommandHeader.py +++ b/Autocoders/Python/src/fprime_ac/generators/CommandHeader.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "CommandHeader.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "CommandHeader.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "CommandHeader.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "CommandHeader.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/DictBody.py b/Autocoders/Python/src/fprime_ac/generators/DictBody.py index bc81dc69f4..a9410f7231 100644 --- a/Autocoders/Python/src/fprime_ac/generators/DictBody.py +++ b/Autocoders/Python/src/fprime_ac/generators/DictBody.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "DictBodyVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "DictBodyVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "DictBodyVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "DictBodyVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/DictHeader.py b/Autocoders/Python/src/fprime_ac/generators/DictHeader.py index 1727cb3d74..658a23d3dd 100644 --- a/Autocoders/Python/src/fprime_ac/generators/DictHeader.py +++ b/Autocoders/Python/src/fprime_ac/generators/DictHeader.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "DictHeaderVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "DictHeaderVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "DictHeaderVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "DictHeaderVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/DictStart.py b/Autocoders/Python/src/fprime_ac/generators/DictStart.py index 6cb18a921b..5df92a6bb0 100644 --- a/Autocoders/Python/src/fprime_ac/generators/DictStart.py +++ b/Autocoders/Python/src/fprime_ac/generators/DictStart.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "DictStartVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "DictStartVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "DictStartVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "DictStartVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/EventBody.py b/Autocoders/Python/src/fprime_ac/generators/EventBody.py index 847ffa4547..99eca93ac5 100644 --- a/Autocoders/Python/src/fprime_ac/generators/EventBody.py +++ b/Autocoders/Python/src/fprime_ac/generators/EventBody.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "EventBody.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "EventBody.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "EventBody.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "EventBody.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/EventHeader.py b/Autocoders/Python/src/fprime_ac/generators/EventHeader.py index b431c9ed7d..e54088c2e9 100644 --- a/Autocoders/Python/src/fprime_ac/generators/EventHeader.py +++ b/Autocoders/Python/src/fprime_ac/generators/EventHeader.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "EventHeader.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "EventHeader.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "EventHeader.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "EventHeader.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/FinishSource.py b/Autocoders/Python/src/fprime_ac/generators/FinishSource.py index 352fbe402f..9615967ca7 100644 --- a/Autocoders/Python/src/fprime_ac/generators/FinishSource.py +++ b/Autocoders/Python/src/fprime_ac/generators/FinishSource.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "FinishSource.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "FinishSource.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "FinishSource.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "FinishSource.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/HtmlDocPage.py b/Autocoders/Python/src/fprime_ac/generators/HtmlDocPage.py index 943ef39021..a204bc14cf 100644 --- a/Autocoders/Python/src/fprime_ac/generators/HtmlDocPage.py +++ b/Autocoders/Python/src/fprime_ac/generators/HtmlDocPage.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "HtmlDoc.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "HtmlDoc.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "HtmlDoc.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "HtmlDoc.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/HtmlStartPage.py b/Autocoders/Python/src/fprime_ac/generators/HtmlStartPage.py index 081ff24abc..126ec695b3 100644 --- a/Autocoders/Python/src/fprime_ac/generators/HtmlStartPage.py +++ b/Autocoders/Python/src/fprime_ac/generators/HtmlStartPage.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "HtmlStartPage.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "HtmlStartPage.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "HtmlStartPage.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "HtmlStartPage.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/Includes1.py b/Autocoders/Python/src/fprime_ac/generators/Includes1.py index c246ecc4e5..b80ebb040e 100644 --- a/Autocoders/Python/src/fprime_ac/generators/Includes1.py +++ b/Autocoders/Python/src/fprime_ac/generators/Includes1.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "Includes1.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Includes1.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "Includes1.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Includes1.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/Includes2.py b/Autocoders/Python/src/fprime_ac/generators/Includes2.py index 7cfda5f929..b22d32c5bb 100644 --- a/Autocoders/Python/src/fprime_ac/generators/Includes2.py +++ b/Autocoders/Python/src/fprime_ac/generators/Includes2.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "Includes2.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Includes2.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "Includes2.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Includes2.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/InitFiles.py b/Autocoders/Python/src/fprime_ac/generators/InitFiles.py index 4cc1eadc69..930e72605e 100644 --- a/Autocoders/Python/src/fprime_ac/generators/InitFiles.py +++ b/Autocoders/Python/src/fprime_ac/generators/InitFiles.py @@ -80,7 +80,7 @@ def accept(self, visitor): DEBUG.error( "InitFiles.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InitFiles.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -95,7 +95,7 @@ def addVisitor(self, visitor): DEBUG.error( "InitFiles.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InitFiles.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/InstanceDictBody.py b/Autocoders/Python/src/fprime_ac/generators/InstanceDictBody.py index dc12163270..c1a83c250a 100644 --- a/Autocoders/Python/src/fprime_ac/generators/InstanceDictBody.py +++ b/Autocoders/Python/src/fprime_ac/generators/InstanceDictBody.py @@ -79,7 +79,7 @@ def accept(self, visitor, topology_model): DEBUG.error( "InstanceDictBodyVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InstanceDictBodyVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "InstanceDictBodyVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InstanceDictBodyVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/InstanceDictHeader.py b/Autocoders/Python/src/fprime_ac/generators/InstanceDictHeader.py index b1098e42c7..91dbe32ba9 100644 --- a/Autocoders/Python/src/fprime_ac/generators/InstanceDictHeader.py +++ b/Autocoders/Python/src/fprime_ac/generators/InstanceDictHeader.py @@ -79,7 +79,7 @@ def accept(self, visitor, topology_model): DEBUG.error( "InstanceDictHeaderVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InstanceDictHeaderVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "InstanceDictHeaderVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InstanceDictHeaderVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/InstanceDictStart.py b/Autocoders/Python/src/fprime_ac/generators/InstanceDictStart.py index 1430de5c39..9478f3e198 100644 --- a/Autocoders/Python/src/fprime_ac/generators/InstanceDictStart.py +++ b/Autocoders/Python/src/fprime_ac/generators/InstanceDictStart.py @@ -79,7 +79,7 @@ def accept(self, visitor, topology_model): DEBUG.error( "InstanceDictStartVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InstanceDictStartVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "InstanceDictStartVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "InstanceDictStartVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/MdDocPage.py b/Autocoders/Python/src/fprime_ac/generators/MdDocPage.py index 3f35ab27db..d24d9c42d8 100644 --- a/Autocoders/Python/src/fprime_ac/generators/MdDocPage.py +++ b/Autocoders/Python/src/fprime_ac/generators/MdDocPage.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "MdDoc.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "MdDoc.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "MdDoc.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "MdDoc.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/MdStartPage.py b/Autocoders/Python/src/fprime_ac/generators/MdStartPage.py index 09a91fd1b2..55502b2806 100644 --- a/Autocoders/Python/src/fprime_ac/generators/MdStartPage.py +++ b/Autocoders/Python/src/fprime_ac/generators/MdStartPage.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "MDStartPage.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "MdStartPage.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "MdStartPage.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "MdStartPage.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/Namespace.py b/Autocoders/Python/src/fprime_ac/generators/Namespace.py index da5c08ded2..6267ddc5c3 100644 --- a/Autocoders/Python/src/fprime_ac/generators/Namespace.py +++ b/Autocoders/Python/src/fprime_ac/generators/Namespace.py @@ -80,7 +80,7 @@ def accept(self, visitor): DEBUG.error( "Namespace.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Namespace.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -95,7 +95,7 @@ def addVisitor(self, visitor): DEBUG.error( "Namespace.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Namespace.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/Private.py b/Autocoders/Python/src/fprime_ac/generators/Private.py index 1708128d1f..e4a42ccf2b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/Private.py +++ b/Autocoders/Python/src/fprime_ac/generators/Private.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "Private.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Private.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "Private.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Private.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/Protected.py b/Autocoders/Python/src/fprime_ac/generators/Protected.py index d553a52090..af6a1a4112 100644 --- a/Autocoders/Python/src/fprime_ac/generators/Protected.py +++ b/Autocoders/Python/src/fprime_ac/generators/Protected.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "Protected.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Protected.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "Protected.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Protected.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/Public.py b/Autocoders/Python/src/fprime_ac/generators/Public.py index 7a03cb02d4..77a7fa51e1 100644 --- a/Autocoders/Python/src/fprime_ac/generators/Public.py +++ b/Autocoders/Python/src/fprime_ac/generators/Public.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "Public.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Public.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "Public.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "Public.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/StartChannel.py b/Autocoders/Python/src/fprime_ac/generators/StartChannel.py index 5c6939ac79..e2c7dc9249 100644 --- a/Autocoders/Python/src/fprime_ac/generators/StartChannel.py +++ b/Autocoders/Python/src/fprime_ac/generators/StartChannel.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "startChannelVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "startChannelVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "startChannelVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "startChannelVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/StartCommand.py b/Autocoders/Python/src/fprime_ac/generators/StartCommand.py index 53a3a5496c..803d6202d0 100644 --- a/Autocoders/Python/src/fprime_ac/generators/StartCommand.py +++ b/Autocoders/Python/src/fprime_ac/generators/StartCommand.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "startCommandVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "startCommandVisit.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "startCommandVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "startCommandVisit.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/StartEvent.py b/Autocoders/Python/src/fprime_ac/generators/StartEvent.py index fa4c3e3f12..2f9913dd3c 100644 --- a/Autocoders/Python/src/fprime_ac/generators/StartEvent.py +++ b/Autocoders/Python/src/fprime_ac/generators/StartEvent.py @@ -79,7 +79,7 @@ def accept(self, visitor): DEBUG.error( "StartEvent.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "StartEvent.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -94,7 +94,7 @@ def addVisitor(self, visitor): DEBUG.error( "StartEvent.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "StartEvent.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/StartSource.py b/Autocoders/Python/src/fprime_ac/generators/StartSource.py index 88d511a2f0..e1832f7462 100644 --- a/Autocoders/Python/src/fprime_ac/generators/StartSource.py +++ b/Autocoders/Python/src/fprime_ac/generators/StartSource.py @@ -80,7 +80,7 @@ def accept(self, visitor): DEBUG.error( "StartSource.accept() - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "StartSource.accept() - the given visitor is not a subclass of AbstractVisitor!" ) @@ -95,7 +95,7 @@ def addVisitor(self, visitor): DEBUG.error( "StartSource.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) - raise Exception( + raise TypeError( "StartSource.addVisitor(v) - the given visitor is not a subclass of AbstractVisitor!" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/formatters.py b/Autocoders/Python/src/fprime_ac/generators/formatters.py index 200696af4b..8c0790b2d9 100644 --- a/Autocoders/Python/src/fprime_ac/generators/formatters.py +++ b/Autocoders/Python/src/fprime_ac/generators/formatters.py @@ -701,7 +701,7 @@ def opcodeStemName(self, id, name): "ERROR: DETECTED AN INVALID CHARACTER IN COMMAND STEM NAME (%s)." % name_string ) - raise Exception( + raise ValueError( "Fatal error, detected an invalid character in command stem name." ) # All is ok @@ -724,7 +724,7 @@ def opcodeStemNameValidate(self, id, cmd_name_list): for c in cmds: if sum([int(x == c) for x in cmds]) > 1: PRINT.info("ERROR: DETECTED %s COMMAND STEM NAME REPEATED." % c) - raise Exception("Error detected repeated command stem name.") + raise ValueError("Error detected repeated command stem name.") return True def evrNamePrefix(self, name): @@ -1113,14 +1113,14 @@ def formatFun(self, indent, one_line): "ERROR: No left paren in function name passed to formatFun: %s." % one_line ) - raise Exception("No left paren in function name passed to formatFun.") + raise ValueError("No left paren in function name passed to formatFun.") two_chunks = one_line.split("(") if len(two_chunks) != 2: PRINT.info( "ERROR: Too many left parens in name passed to formatFun: %s" % one_line ) - raise Exception("Too many left parens in name passed to formatFun.") + raise ValueError("Too many left parens in name passed to formatFun.") type_and_name = two_chunks[0] args = two_chunks[1] diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/AbstractVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/AbstractVisitor.py index 320528d6af..4c8b81a625 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/AbstractVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/AbstractVisitor.py @@ -67,7 +67,7 @@ def initFilesVisit(self, obj): Defined to generate files for generated code products. @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.initFilesVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -75,7 +75,7 @@ def startSourceFilesVisit(self, obj): """ Defined to generate starting static code within files. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.startSourceFilesVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -85,7 +85,7 @@ def includes1Visit(self, obj): Usually used for the base classes but also for Port types @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.includesVisit1() - Implementation Error: you must supply your own concrete implementation." ) @@ -95,7 +95,7 @@ def includes2Visit(self, obj): Usually used for data type includes and system includes. @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.includesVisit2() - Implementation Error: you must supply your own concrete implementation." ) @@ -105,7 +105,7 @@ def namespaceVisit(self, obj): Also any pre-condition code is generated. @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.namespaceVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -114,7 +114,7 @@ def publicVisit(self, obj): Defined to generate public stuff within a class. @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.publicVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -123,7 +123,7 @@ def protectedVisit(self, obj): Defined to generate protected stuff within a class. @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.protectedVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -132,7 +132,7 @@ def privateVisit(self, obj): Defined to generate private stuff within a class. @param args: the instance of the concrete element to operation on. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.privateVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -140,7 +140,7 @@ def finishSourceFilesVisit(self, obj): """ Defined to generate ending static code within files. """ - raise Exception( + raise NotImplementedError( "# AbstractVisitor.endSourceFilesVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -148,7 +148,7 @@ def DictStartVisit(self, obj): """ Defined to generate start of command Python class. """ - raise Exception( + raise NotImplementedError( "# DictStartVisit.startCommandVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -156,7 +156,7 @@ def DictHeaderVisit(self, obj): """ Defined to generate header for Python command class. """ - raise Exception( + raise NotImplementedError( "# DictStartVisit.commandHeaderVisit() - Implementation Error: you must supply your own concrete implementation." ) @@ -164,7 +164,7 @@ def DictBodyVisit(self, obj): """ Defined to generate body for Python command class. """ - raise Exception( + raise NotImplementedError( "# DictStartVisit.commandBodyVisit() - Implementation Error: you must supply your own concrete implementation." ) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py index 70f769c610..d23feb916b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py @@ -129,7 +129,7 @@ def DictStartVisit(self, obj): if len(obj.get_set_opcodes()) == 1: # set/save opcode numbers had better match if len(obj.get_set_opcodes()) != len(obj.get_save_opcodes()): - raise Exception("set/save opcode quantities do not match!") + raise ValueError("set/save opcode quantities do not match!") pyfile = "{}/{}_PRM_SET.py".format(output_dir, self.__stem) fd = open(pyfile, "w") if fd is None: diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py index 958a91fd61..dd9b9856cb 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py @@ -176,7 +176,7 @@ def DictBodyVisit(self, obj, topology_model): c.name = fname if len(obj.get_ids()) > 1: - raise Exception( + raise ValueError( "There is more than one event id when creating dictionaries. Check xml of {} or see if multiple explicit IDs exist in the AcConstants.ini file".format( fname ) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py index 3e78bb438b..e13cc07d04 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py @@ -179,7 +179,7 @@ def DictBodyVisit(self, obj, topology_model): c.name = fname if len(obj.get_ids()) > 1: - raise Exception( + raise ValueError( "There is more than one event id when creating dictionaries. Check xml of {} or see if multiple explicit IDs exist in the AcConstants.ini file".format( fname ) From 669d1f62c57640c74442e9d83de1d53b9a70bbc7 Mon Sep 17 00:00:00 2001 From: redixin Date: Mon, 26 Sep 2022 19:14:05 +0300 Subject: [PATCH 060/169] Remove unnecessary checks in python generators (#1661) There is no need to check returned value of built in function `open'. Documentation says: > If the file cannot be opened, IOError is raised. https://docs.python.org/2/library/functions.html#open --- .../fprime_ac/generators/visitors/ChannelVisitor.py | 4 ---- .../fprime_ac/generators/visitors/CommandVisitor.py | 12 ------------ .../generators/visitors/ComponentVisitorBase.py | 2 -- .../fprime_ac/generators/visitors/EventVisitor.py | 4 ---- .../generators/visitors/InstanceChannelVisitor.py | 2 -- .../generators/visitors/InstanceCommandVisitor.py | 6 ------ .../generators/visitors/InstanceEventVisitor.py | 2 -- .../visitors/InstanceSerializableVisitor.py | 2 -- .../visitors/InstanceTopologyCppVisitor.py | 2 -- .../generators/visitors/InstanceTopologyHVisitor.py | 2 -- .../fprime_ac/generators/visitors/PortCppVisitor.py | 2 -- .../fprime_ac/generators/visitors/PortHVisitor.py | 2 -- .../generators/visitors/SerialCppVisitor.py | 2 -- .../fprime_ac/generators/visitors/SerialHVisitor.py | 2 -- .../generators/visitors/SerializableVisitor.py | 2 -- .../generators/visitors/TopologyCppVisitor.py | 2 -- .../generators/visitors/TopologyHVisitor.py | 2 -- .../generators/visitors/TopologyIDVisitor.py | 2 -- 18 files changed, 54 deletions(-) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py index 85b5b049c5..4ac4574705 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/ChannelVisitor.py @@ -99,16 +99,12 @@ def DictStartVisit(self, obj): if len(obj.get_ids()) == 1: pyfile = "{}/{}.py".format(output_dir, obj.get_name()) fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp.append(fd) else: for inst, id in enumerate(obj.get_ids()): pyfile = "%s/%s_%d.py" % (output_dir, obj.get_name(), inst) DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") DEBUG.info(f"Completed {pyfile} open") self.__fp.append(fd) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py index d23feb916b..3d7bffdcd1 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/CommandVisitor.py @@ -108,16 +108,12 @@ def DictStartVisit(self, obj): if len(obj.get_opcodes()) == 1: pyfile = "{}/{}.py".format(output_dir, obj.get_mnemonic()) fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp1.append(fd) else: for inst, opcode in enumerate(obj.get_opcodes()): pyfile = "%s/%s_%d.py" % (output_dir, obj.get_mnemonic(), inst) DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") DEBUG.info(f"Completed {pyfile} open") self.__fp1.append(fd) elif type(obj) is Parameter.Parameter: @@ -132,30 +128,22 @@ def DictStartVisit(self, obj): raise ValueError("set/save opcode quantities do not match!") pyfile = "{}/{}_PRM_SET.py".format(output_dir, self.__stem) fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp1.append(fd) pyfile = "{}/{}_PRM_SAVE.py".format(output_dir, self.__stem) fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp2.append(fd) else: for inst, opcode in enumerate(obj.get_set_opcodes()): pyfile = "%s/%s_%d_PRM_SET.py" % (output_dir, self.__stem, inst) DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp1.append(fd) DEBUG.info(f"Completed {pyfile} open") pyfile = "%s/%s_%d_PRM_SAVE.py" % (output_dir, self.__stem, inst) DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp2.append(fd) DEBUG.info(f"Completed {pyfile} open") diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py b/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py index fc9db5ac11..cf9efe3f95 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/ComponentVisitorBase.py @@ -863,8 +863,6 @@ def openFile(self, filename): """ DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open file %s") % filename DEBUG.info("Completed") def initFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py index ee4c5c802b..27ee38b47f 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/EventVisitor.py @@ -101,8 +101,6 @@ def DictStartVisit(self, obj): if len(obj.get_ids()) == 1: pyfile = "{}/{}.py".format(output_dir, obj.get_name()) fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") self.__fp.append(fd) else: inst = 0 @@ -111,8 +109,6 @@ def DictStartVisit(self, obj): inst += 1 DEBUG.info(f"Open file: {pyfile}") fd = open(pyfile, "w") - if fd is None: - raise Exception(f"Could not open {pyfile} file.") DEBUG.info(f"Completed {pyfile} open") self.__fp.append(fd) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py index dd9b9856cb..ed066dcf1b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceChannelVisitor.py @@ -125,8 +125,6 @@ def DictStartVisit(self, obj, topology_model): pyfile = "{}/{}.py".format(output_dir, fname) DEBUG.info("Open file: {}".format(pyfile)) fd = open(pyfile, "w") - if fd is None: - raise Exception("Could not open {} file.".format(pyfile)) DEBUG.info("Completed {} open".format(pyfile)) self.__fp[fname] = fd diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceCommandVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceCommandVisitor.py index 9e36eaf9ec..55a70fb6b5 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceCommandVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceCommandVisitor.py @@ -138,8 +138,6 @@ def DictStartVisit(self, obj, topology_model): pyfile = "{}/{}.py".format(output_dir, fname) DEBUG.info("Open file: {}".format(pyfile)) fd = open(pyfile, "w") - if fd is None: - raise Exception("Could not open {} file.".format(pyfile)) DEBUG.info("Completed {} open".format(pyfile)) self.__fp1[fname] = fd @@ -164,16 +162,12 @@ def DictStartVisit(self, obj, topology_model): pyfile = "{}/{}_PRM_SET.py".format(output_dir, fname) DEBUG.info("Open file: {}".format(pyfile)) fd = open(pyfile, "w") - if fd is None: - raise Exception("Could not open {} file.".format(pyfile)) self.__fp1[fname] = fd DEBUG.info("Completed {} open".format(pyfile)) pyfile = "{}/{}_PRM_SAVE.py".format(output_dir, fname) DEBUG.info("Open file: {}".format(pyfile)) fd = open(pyfile, "w") - if fd is None: - raise Exception("Could not open {} file.".format(pyfile)) self.__fp2[fname] = fd DEBUG.info("Completed {} open".format(pyfile)) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py index e13cc07d04..8c77c2a38e 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceEventVisitor.py @@ -127,8 +127,6 @@ def DictStartVisit(self, obj, topology_model): pyfile = "{}/{}.py".format(output_dir, fname) DEBUG.info("Open file: {}".format(pyfile)) fd = open(pyfile, "w") - if fd is None: - raise Exception("Could not open {} file.".format(pyfile)) DEBUG.info("Completed {} open".format(pyfile)) self.__fp[fname] = fd diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceSerializableVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceSerializableVisitor.py index 71ee865989..cd9a5ac663 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceSerializableVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceSerializableVisitor.py @@ -189,8 +189,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info(f"Open file: {pyfile}") self.__fp = open(pyfile, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % pyfile DEBUG.info("Completed") def startSourceFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyCppVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyCppVisitor.py index 56fead0266..060f53c35b 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyCppVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyCppVisitor.py @@ -128,8 +128,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") else: PRINT.info("ERROR: NO COMPONENTS FOUND IN TOPOLOGY XML FILE...") diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyHVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyHVisitor.py index e600788a35..97e5a923a2 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyHVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/InstanceTopologyHVisitor.py @@ -128,8 +128,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") else: PRINT.info("ERROR: NO COMPONENTS FOUND IN TOPOLOGY XML FILE...") diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/PortCppVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/PortCppVisitor.py index 8344accbaa..dedd5ff0b8 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/PortCppVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/PortCppVisitor.py @@ -195,8 +195,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") def startSourceFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py index 7ec1f26d56..8506e2f816 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py @@ -255,8 +255,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") def startSourceFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/SerialCppVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/SerialCppVisitor.py index d96d1ea0b1..ba45be60e4 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/SerialCppVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/SerialCppVisitor.py @@ -250,8 +250,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") def startSourceFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/SerialHVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/SerialHVisitor.py index 7cb9fcecc2..586d4fef5d 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/SerialHVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/SerialHVisitor.py @@ -256,8 +256,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") def startSourceFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/SerializableVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/SerializableVisitor.py index bdedd2a9e8..2880d1773e 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/SerializableVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/SerializableVisitor.py @@ -189,8 +189,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info(f"Open file: {pyfile}") self.__fp = open(pyfile, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % pyfile DEBUG.info("Completed") def startSourceFilesVisit(self, obj): diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyCppVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyCppVisitor.py index 08040a761c..448523d819 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyCppVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyCppVisitor.py @@ -128,8 +128,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") else: PRINT.info("ERROR: NO COMPONENTS FOUND IN TOPOLOGY XML FILE...") diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyHVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyHVisitor.py index ba1f5f9335..2ea6369d80 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyHVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyHVisitor.py @@ -128,8 +128,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") else: PRINT.info("ERROR: NO COMPONENTS FOUND IN TOPOLOGY XML FILE...") diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyIDVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyIDVisitor.py index 31e4d4420a..e0f9178fd1 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyIDVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/TopologyIDVisitor.py @@ -115,8 +115,6 @@ def initFilesVisit(self, obj): # Open file for writing here... DEBUG.info("Open file: %s" % filename) self.__fp = open(filename, "w") - if self.__fp is None: - raise Exception("Could not open %s file.") % filename DEBUG.info("Completed") else: PRINT.info("ERROR: NO COMPONENTS FOUND IN TOPOLOGY XML FILE...") From 378e546c5e13a976c9c84ddc2491eabd4908a568 Mon Sep 17 00:00:00 2001 From: Yang Hau Date: Tue, 27 Sep 2022 01:48:27 +0800 Subject: [PATCH 061/169] Initialize Array before used (#1668) --- Autocoders/Python/test/partition/Top.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Autocoders/Python/test/partition/Top.cpp b/Autocoders/Python/test/partition/Top.cpp index f95d9d1c86..9f5a8d002f 100644 --- a/Autocoders/Python/test/partition/Top.cpp +++ b/Autocoders/Python/test/partition/Top.cpp @@ -83,7 +83,7 @@ int main(int argc, char* argv[]) { // Construct the topology here. constructArchitecture(); // Ask for input to huey or duey here. - char in[80]; + char in[80] = {}; U32 cmd; Fw::String *str; char str2[80]; From d76db5373404b4f599826c76d31d362e15b4a3ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Fr=C3=A9d=C3=A9ric=20Chapoton?= Date: Mon, 26 Sep 2022 20:07:48 +0200 Subject: [PATCH 062/169] Patch 1 (#1644) * Update test_schematron.py trying to use Path from pathlib * Update test_schematron.py fix detail --- .../Python/test/schematron/test_schematron.py | 32 ++++++++----------- 1 file changed, 13 insertions(+), 19 deletions(-) diff --git a/Autocoders/Python/test/schematron/test_schematron.py b/Autocoders/Python/test/schematron/test_schematron.py index b2ad1f5a94..af8b586ee3 100644 --- a/Autocoders/Python/test/schematron/test_schematron.py +++ b/Autocoders/Python/test/schematron/test_schematron.py @@ -5,7 +5,7 @@ @author jishii """ - +from pathlib import Path import os import shutil import sys @@ -13,8 +13,9 @@ import pexpect from pexpect import EOF, TIMEOUT -sys.path.append(os.path.join(os.environ["BUILD_ROOT"], "Fw", "Python", "src")) -sys.path.append(os.path.join(os.environ["BUILD_ROOT"], "Gds", "src")) # Add GDS modules +build_root = Path(os.environ["BUILD_ROOT"]) +sys.path.append(build_root / "Fw" / "Python" / "src") +sys.path.append(build_root / "Gds" / "src") # Add GDS modules def test_schematron(): @@ -24,21 +25,14 @@ def test_schematron(): try: # cd into test directory to find test files (code/test/schematron can only find files this way) - testdir = os.path.join( - os.environ["BUILD_ROOT"], - "Autocoders", - "Python", - "test", - "schematron", - "xml", - ) + testdir = build_root / "Autocoders" / "Python" / "test" / "schematron" / "xml" os.chdir(testdir) - bindir = os.path.join(os.environ["BUILD_ROOT"], "Autocoders", "Python", "bin") + bindir = build_root / "Autocoders" / "Python" / "bin" # Autocode enum XML p_enum = pexpect.spawn( - "python " + os.path.join(bindir, "codegen.py") + " -v Enum1EnumAi.xml" + "python " + str(bindir / "codegen.py") + " -v Enum1EnumAi.xml" ) p_enum.expect("(?=.*Enum1 Schematron).*") print("Enum autocoded for test cases") @@ -52,7 +46,7 @@ def test_schematron(): # Successful test case p_test1 = pexpect.spawn( - "python " + os.path.join(bindir, "codegen.py") + " -v TestTopologyAppAi.xml" + "python " + str(bindir / "codegen.py") + " -v TestTopologyAppAi.xml" ) p_test1.expect( "(?=.*Found component XML file)(?=.*Parsing Component TestComponent)(?!.*ERROR)(?!.*is not valid according to schematron).*", @@ -63,7 +57,7 @@ def test_schematron(): # Active component without an async port p_test2 = pexpect.spawn( "python " - + os.path.join(bindir, "codegen.py") + + str(bindir / "codegen.py") + " -v Test2TopologyAppAi.xml" ) p_test2.expect( @@ -77,7 +71,7 @@ def test_schematron(): # Topology with 2 instances of the same ID p_test3 = pexpect.spawn( "python " - + os.path.join(bindir, "codegen.py") + + str(bindir / "codegen.py") + " -v BrokenTopologyAppAi.xml" ) p_test3.expect("(?=.*top_uniqueness_schematron.rng)(?!.*ERROR).*", timeout=5) @@ -91,12 +85,12 @@ def test_schematron(): # Broken imported dict print( "python " - + os.path.join(bindir, "codegen.py") + + str(bindir / "codegen.py") + " -v Test{}DictComponentAi.xml".format(type) ) p_test_dict = pexpect.spawn( "python " - + os.path.join(bindir, "codegen.py") + + str(bindir / "codegen.py") + " -v Test{}DictComponentAi.xml".format(type) ) if type == "Cmd": @@ -129,7 +123,7 @@ def test_schematron(): # Broken component xml p_test_dict = pexpect.spawn( "python " - + os.path.join(bindir, "codegen.py") + + str(bindir / "codegen.py") + " -v Test{}ComponentAi.xml".format(type) ) p_test_dict.expect( From 8849abca87d0ef1311014df999c754d6d375fdbe Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Mon, 26 Sep 2022 20:54:27 +0200 Subject: [PATCH 063/169] Improve `getMemUtil()` of the OSAL Linux port (#1667) * Use `sysinfo()` syscall to get meminfo * Remove unused includes * lestarch: sp Co-authored-by: M Starch --- .github/actions/spelling/expect.txt | 2 ++ Os/Linux/SystemResources.cpp | 36 ++++++++--------------------- 2 files changed, 12 insertions(+), 26 deletions(-) diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index b28dca4106..84ddc620b7 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -504,6 +504,7 @@ fprofile fptr fputil fpv +freeram Fregoso frontend frox @@ -1444,6 +1445,7 @@ TOTALFF TOTALISFLOGEVENTMSG TOTALISFTELMMSG TOTALQUEUEFULL +totalram TOUPPER transcoding treeview diff --git a/Os/Linux/SystemResources.cpp b/Os/Linux/SystemResources.cpp index bb7a23661c..e4f4c51dfa 100644 --- a/Os/Linux/SystemResources.cpp +++ b/Os/Linux/SystemResources.cpp @@ -9,10 +9,8 @@ // acknowledged. // // ====================================================================== -#include /* fopen() */ -#include /* scanf */ -#include /* statfs() */ -#include /* get_nprocs() */ +#include +#include #include #include #include @@ -82,31 +80,17 @@ namespace Os { } SystemResources::SystemResourcesStatus SystemResources::getMemUtil(MemUtil &memory_util) { - FILE *fp = nullptr; - NATIVE_INT_TYPE total = 0; - NATIVE_INT_TYPE free = 0; - // Fallbacks - memory_util.total = 1; - memory_util.used = 1; - - fp = fopen("/proc/meminfo", "r"); - if (fp == nullptr) { - return SYSTEM_RESOURCES_ERROR; - } - // No string concerns as strings discarded - if (fscanf(fp, "%*s %d %*s", &total) != 1 || /* 1st line is MemTotal */ - fscanf(fp, "%*s %d", &free) != 1) { /* 2nd line is MemFree */ - fclose(fp); - return SYSTEM_RESOURCES_ERROR; - } - fclose(fp); - // Check results - if (total < 0 or free < 0 or total < free) { + struct sysinfo memory_info; + sysinfo(&memory_info); + + if (memory_info.totalram < memory_info.freeram) { return SYSTEM_RESOURCES_ERROR; } - memory_util.total = static_cast(total) * 1024; // KB to Bytes - memory_util.used = static_cast(total - free) * 1024; + + memory_util.total = static_cast(memory_info.totalram * memory_info.mem_unit); + memory_util.used = static_cast((memory_info.totalram - memory_info.freeram) * memory_info.mem_unit); + return SYSTEM_RESOURCES_OK; } } From 8ff0d6fd49124c82cc39b2638b4969c9e0899e99 Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 26 Sep 2022 13:08:22 -0700 Subject: [PATCH 064/169] lestarch: fixing formatting of failing python file (#1672) --- Autocoders/Python/test/schematron/test_schematron.py | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/Autocoders/Python/test/schematron/test_schematron.py b/Autocoders/Python/test/schematron/test_schematron.py index af8b586ee3..f9b5a62132 100644 --- a/Autocoders/Python/test/schematron/test_schematron.py +++ b/Autocoders/Python/test/schematron/test_schematron.py @@ -56,9 +56,7 @@ def test_schematron(): # Active component without an async port p_test2 = pexpect.spawn( - "python " - + str(bindir / "codegen.py") - + " -v Test2TopologyAppAi.xml" + "python " + str(bindir / "codegen.py") + " -v Test2TopologyAppAi.xml" ) p_test2.expect( "(?=.*Found component XML file)(?=.*active_comp_schematron.rng)(?!.*ERROR).*", @@ -70,9 +68,7 @@ def test_schematron(): # Topology with 2 instances of the same ID p_test3 = pexpect.spawn( - "python " - + str(bindir / "codegen.py") - + " -v BrokenTopologyAppAi.xml" + "python " + str(bindir / "codegen.py") + " -v BrokenTopologyAppAi.xml" ) p_test3.expect("(?=.*top_uniqueness_schematron.rng)(?!.*ERROR).*", timeout=5) print( From 3442b8d472d645ae9ed6f7135ae04eef1590623e Mon Sep 17 00:00:00 2001 From: kevin-f-ortega Date: Thu, 29 Sep 2022 18:34:33 -0700 Subject: [PATCH 065/169] added missing cpp file for baremetal (#1678) * added missing cpp file for baremetal * added missing cpp files for Os/Baremetal --- Os/CMakeLists.txt | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Os/CMakeLists.txt b/Os/CMakeLists.txt index 3d244349d4..12bde1fcf1 100644 --- a/Os/CMakeLists.txt +++ b/Os/CMakeLists.txt @@ -81,9 +81,13 @@ if (FPRIME_USE_BAREMETAL_SCHEDULER) list(REMOVE_ITEM SOURCE_FILES "${ITER_ITEM}") endif() endforeach() - list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/Task.cpp") + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/File.cpp") + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/FileSystem.cpp") + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/IntervalTimer.cpp") list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/Mutex.cpp") + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/Queue.cpp") list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/SystemResources.cpp") + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Baremetal/Task.cpp") endif() register_fprime_module() From 092d9c8a8dfda74a0b6056106508bcd774ab0905 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Mon, 3 Oct 2022 09:21:16 -0700 Subject: [PATCH 066/169] Fix type specifications in framework (#1697) * Revise file ID type for FSW assertions * Fix type specifications in framework * Back out change to Sched port We can make this change later, when we have updated FPP code gen --- Fw/Test/UnitTestAssert.cpp | 4 +-- Fw/Types/Assert.cpp | 71 ++++++++++++++++++++++++++++++-------- Fw/Types/Assert.hpp | 2 +- 3 files changed, 59 insertions(+), 18 deletions(-) diff --git a/Fw/Test/UnitTestAssert.cpp b/Fw/Test/UnitTestAssert.cpp index 95c343e3fb..77a0da89f4 100644 --- a/Fw/Test/UnitTestAssert.cpp +++ b/Fw/Test/UnitTestAssert.cpp @@ -43,9 +43,9 @@ namespace Test { void UnitTestAssert::doAssert() { this->m_assertFailed = true; #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT - (void)fprintf(stderr,"Assert File: 0x%x, Line: %" PRI_FwAssertArgType "\n", this->m_file, this->m_lineNo); + (void)fprintf(stderr,"Assert File: 0x%" PRIx32 ", Line: %" PRI_PlatformUIntType "\n", this->m_file, this->m_lineNo); #else - (void)fprintf(stderr,"Assert File: %s, Line: %" PRI_FwAssertArgType "\n", this->m_file.toChar(), this->m_lineNo); + (void)fprintf(stderr,"Assert File: %s, Line: %" PRI_PlatformUIntType "\n", this->m_file.toChar(), this->m_lineNo); #endif } diff --git a/Fw/Types/Assert.cpp b/Fw/Types/Assert.cpp index 06354e89dd..046ccd8782 100644 --- a/Fw/Types/Assert.cpp +++ b/Fw/Types/Assert.cpp @@ -10,9 +10,9 @@ #else #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define fileIdFs "Assert file ID 0x%08X: Line: %" PRI_FwAssertArgType " " +#define fileIdFs "Assert file ID 0x%08" PRIx32 ": Line: %" PRI_PlatformUIntType #else -#define fileIdFs "Assert file \"%s\": Line: %" PRI_FwAssertArgType " " +#define fileIdFs "Assert file \"%s\": Line: %" PRI_PlatformUIntType #endif namespace Fw { @@ -38,31 +38,72 @@ namespace Fw { switch (numArgs) { case 0: - (void)snprintf(destBuffer,buffSize,fileIdFs,file,lineNo); + (void) snprintf(destBuffer, buffSize, fileIdFs, file, lineNo); break; case 1: - (void)snprintf(destBuffer,buffSize,fileIdFs "%d",file,lineNo, - arg1); + (void) snprintf( + destBuffer, + buffSize, + fileIdFs "%" PRI_FwAssertArgType, + file, + lineNo, + arg1 + ); break; case 2: - (void)snprintf(destBuffer,buffSize,fileIdFs "%d %d",file,lineNo, - arg1,arg2); + (void) snprintf( + destBuffer, + buffSize, + fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType, + file, + lineNo, + arg1, arg2 + ); break; case 3: - (void)snprintf(destBuffer,buffSize,fileIdFs "%d %d %d",file,lineNo, - arg1,arg2,arg3); + (void) snprintf( + destBuffer, + buffSize, + fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + " %" PRI_FwAssertArgType, + file, + lineNo, + arg1, arg2, arg3 + ); break; case 4: - (void)snprintf(destBuffer,buffSize,fileIdFs "%d %d %d %d",file,lineNo, - arg1,arg2,arg3,arg4); + (void) snprintf( + destBuffer, + buffSize, + fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, + file, + lineNo, + arg1, arg2, arg3, arg4); break; case 5: - (void)snprintf(destBuffer,buffSize,fileIdFs "%d %d %d %d %d",file,lineNo, - arg1,arg2,arg3,arg4,arg5); + (void) snprintf( + destBuffer, + buffSize, + fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType + " %" PRI_FwAssertArgType, + file, + lineNo, + arg1, arg2, arg3, arg4, arg5 + ); break; case 6: - (void)snprintf(destBuffer,buffSize,fileIdFs "%d %d %d %d %d %d",file,lineNo, - arg1,arg2,arg3,arg4,arg5,arg6); + (void) snprintf( + destBuffer, + buffSize, + fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType + " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, + file, + lineNo, + arg1, arg2, arg3, arg4, arg5, arg6 + ); break; default: // in an assert already, what can we do? break; diff --git a/Fw/Types/Assert.hpp b/Fw/Types/Assert.hpp index 5d3780aacd..bee5710995 100644 --- a/Fw/Types/Assert.hpp +++ b/Fw/Types/Assert.hpp @@ -8,7 +8,7 @@ #else // ASSERT is defined #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define FILE_NAME_ARG NATIVE_UINT_TYPE +#define FILE_NAME_ARG U32 #define FW_ASSERT(cond, ...) \ ((void) ((cond) ? (0) : \ (Fw::SwAssert(ASSERT_FILE_ID, __LINE__, ##__VA_ARGS__)))) From 4758c6315d875e2454b44a6464d0a23480854bda Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 3 Oct 2022 09:21:30 -0700 Subject: [PATCH 067/169] lestarch: cleaned-up cmake autocoder handling. Fixes: #1431, #1680, and #1681 (#1682) * lestarch: cleaned-up cmake autocoder handling. Fixes: #1431, #1680, and #1681 * lestarch: removing tab to fix spacing * lestarch: removing debug code * lestarch: typo in improved docs --- cmake/autocoder/ai_xml.cmake | 8 ++++-- cmake/autocoder/autocoder.cmake | 14 +++------- cmake/autocoder/fpp.cmake | 8 +++--- cmake/autocoder/helpers.cmake | 29 ++++++++++++++++++++ cmake/target/build.cmake | 22 ++++++++------- cmake/utilities.cmake | 2 +- docs/UsersGuide/dev/autocoder-integration.md | 21 ++++++++++++++ 7 files changed, 77 insertions(+), 27 deletions(-) diff --git a/cmake/autocoder/ai_xml.cmake b/cmake/autocoder/ai_xml.cmake index 318e856cca..f64b6c941f 100644 --- a/cmake/autocoder/ai_xml.cmake +++ b/cmake/autocoder/ai_xml.cmake @@ -28,9 +28,14 @@ function(ai_xml_is_supported AC_INPUT_FILE) if (IS_SUPPORTED) string(REPLACE "Ai.xml" "Ac.cpp" CPP_FILE "${AC_INPUT_FILE}") string(REPLACE "Ai.xml" "Ac.hpp" HPP_FILE "${AC_INPUT_FILE}") - if(("${CPP_FILE}" IN_LIST PREVIOUSLY_GENERATED) AND ("${HPP_FILE}" IN_LIST PREVIOUSLY_GENERATED)) + if(("${CPP_FILE}" IN_LIST PREVIOUSLY_GENERATED) AND ("${HPP_FILE}" IN_LIST PREVIOUSLY_GENERATED)) set(IS_SUPPORTED FALSE) endif() + + # If this Ai.xml file was not a generated product, then mark it as requiring a rebuild + if (NOT "${AC_INPUT_FILE}" IN_LIST PREVIOUSLY_GENERATED) + requires_regeneration("${AC_INPUT_FILE}") + endif() endif() # Note: set in PARENT_SCOPE in macro is intended. Caller **wants** to set IS_SUPPORTED in their parent's scope. set(IS_SUPPORTED "${IS_SUPPORTED}" PARENT_SCOPE) @@ -60,7 +65,6 @@ macro(__ai_info XML_PATH MODULE_NAME) # Run the parser and capture the output. If an error occurs, that fatals CMake as we cannot continue set(MODULE_NAME_NO_SUFFIX "${MODULE_NAME}") set(PARSER_PATH "${FPRIME_FRAMEWORK_PATH}/cmake/autocoder/ai-parser/ai_parser.py") - set_property(DIRECTORY APPEND PROPERTY CMAKE_CONFIGURE_DEPENDS "${PARSER_PATH}") execute_process( COMMAND "${PYTHON}" "${PARSER_PATH}" "${XML_PATH}" "${MODULE_NAME_NO_SUFFIX}" "${FPRIME_CLOSEST_BUILD_ROOT}" RESULT_VARIABLE ERR_RETURN diff --git a/cmake/autocoder/autocoder.cmake b/cmake/autocoder/autocoder.cmake index db3e6b47b3..c54bf4bac9 100644 --- a/cmake/autocoder/autocoder.cmake +++ b/cmake/autocoder/autocoder.cmake @@ -98,19 +98,13 @@ function(run_ac AUTOCODER_CMAKE SOURCES GENERATED_SOURCES) set(GENERATED_FILES "${GENERATED_FILES_LIST}") else() __ac_process_sources("${AC_INPUT_SOURCES}") - if (GENERATED_FILES) - set(CONSUMED_SOURCES "${AC_INPUT_SOURCES}") - endif() + set(CONSUMED_SOURCES "${AC_INPUT_SOURCES}") endif() set_property(DIRECTORY PROPERTY "${SRCS_HASH}_DEPENDENCIES" "${MODULE_DEPENDENCIES}") set_property(DIRECTORY PROPERTY "${SRCS_HASH}_GENERATED" "${GENERATED_FILES}") set_property(DIRECTORY PROPERTY "${SRCS_HASH}_CONSUMED" "${CONSUMED_SOURCES}") set_property(DIRECTORY PROPERTY "${SRCS_HASH}_FILE_DEPENDENCIES" "${FILE_DEPENDENCIES}") _describe_autocoder_run("${AUTOCODER_NAME}") - # Configure depends on this source file if it causes a change to module dependencies - if (MODULE_DEPENDENCIES) - set_property(DIRECTORY APPEND PROPERTY CMAKE_CONFIGURE_DEPENDS ${CONSUMED_SOURCES}) - endif() endif() get_property(DEPS DIRECTORY PROPERTY "${SRCS_HASH}_DEPENDENCIES") get_property(GENS DIRECTORY PROPERTY "${SRCS_HASH}_GENERATED") @@ -231,8 +225,8 @@ function(__ac_process_sources SOURCES) add_custom_command(OUTPUT ${AUTOCODER_GENERATED} COMMAND ${AUTOCODER_SCRIPT} ${AUTOCODER_INPUTS} DEPENDS ${AUTOCODER_INPUTS} ${AUTOCODER_DEPENDENCIES}) endif() - set(MODULE_DEPENDENCIES ${AUTOCODER_DEPENDENCIES} PARENT_SCOPE) - set(GENERATED_FILES ${AUTOCODER_GENERATED} PARENT_SCOPE) - set(FILE_DEPENDENCIES ${AUTOCODER_INPUTS} PARENT_SCOPE) + set(MODULE_DEPENDENCIES "${AUTOCODER_DEPENDENCIES}" PARENT_SCOPE) + set(GENERATED_FILES "${AUTOCODER_GENERATED}" PARENT_SCOPE) + set(FILE_DEPENDENCIES "${AUTOCODER_INPUTS}" PARENT_SCOPE) endfunction() diff --git a/cmake/autocoder/fpp.cmake b/cmake/autocoder/fpp.cmake index b17f79f925..6e64de32ea 100644 --- a/cmake/autocoder/fpp.cmake +++ b/cmake/autocoder/fpp.cmake @@ -54,7 +54,7 @@ endfunction(locate_fpp_tools) # `AC_INPUT_FILE` potential input to the autocoder #### function(fpp_is_supported AC_INPUT_FILE) - autocoder_support_by_suffix(".fpp" "${AC_INPUT_FILE}") + autocoder_support_by_suffix(".fpp" "${AC_INPUT_FILE}" TRUE) endfunction(fpp_is_supported) #### @@ -151,7 +151,6 @@ function(fpp_info AC_INPUT_FILES) set(FPP_IMPORTS "${STDOUT}" PARENT_SCOPE) endfunction(fpp_info) - #### # Function `fpp_setup_autocode`: # @@ -194,13 +193,14 @@ function(fpp_setup_autocode AC_INPUT_FILES) # Add in steps for CPP generation if (GENERATED_CPP) add_custom_command( - OUTPUT ${GENERATED_CPP} + OUTPUT ${GENERATED_CPP} COMMAND ${FPP_TO_CPP} "-d" "${CMAKE_CURRENT_BINARY_DIR}" ${IMPORTS} ${AC_INPUT_FILES} "-p" "${FPRIME_BUILD_LOCATIONS_COMMA_SEP},${CMAKE_BINARY_DIR}" DEPENDS ${FILE_DEPENDENCIES} ${MODULE_DEPENDENCIES} ) endif() - set(AUTOCODER_GENERATED ${GENERATED_AI} ${GENERATED_CPP} PARENT_SCOPE) + set(AUTOCODER_GENERATED ${GENERATED_AI} ${GENERATED_CPP}) + set(AUTOCODER_GENERATED "${AUTOCODER_GENERATED}" PARENT_SCOPE) set(AUTOCODER_DEPENDENCIES "${MODULE_DEPENDENCIES}" PARENT_SCOPE) endfunction(fpp_setup_autocode) diff --git a/cmake/autocoder/helpers.cmake b/cmake/autocoder/helpers.cmake index f93a1402ce..23e8e129b6 100644 --- a/cmake/autocoder/helpers.cmake +++ b/cmake/autocoder/helpers.cmake @@ -6,6 +6,7 @@ #### include_guard() include("utilities") +set_property(GLOBAL PROPERTY AUTO_RECONFIGURE_LIST) #### # Macro `autocoder_support_by_suffix`: # @@ -19,13 +20,41 @@ include("utilities") # # **SUFFIX**: suffix to support # **AC_INPUT_FILE**: file to check with suffix +# **REQUIRE_CMAKE_RESCAN:** (optional) this file should trigger a cmake rescan. Default: false #### macro(autocoder_support_by_suffix SUFFIX AC_INPUT_FILE) ends_with(IS_SUPPORTED "${AC_INPUT_FILE}" "${SUFFIX}") # Note: set in PARENT_SCOPE in macro is intended. Caller **wants** to set IS_SUPPORTED in their parent's scope. set(IS_SUPPORTED "${IS_SUPPORTED}" PARENT_SCOPE) + + # Files that are supported may also be marked as requiring a rescan. This is done through an optional third argument + if (IS_SUPPORTED AND ${ARGC} GREATER 2) + # CMake weirdness, if ${ARGC} is <= 2 then ${ARGV2} is inherited not from this macro call, but rather from the + # calling function. Thus we need a 2-tier if statement to prevent an explosion. + # See: https://cmake.org/cmake/help/latest/command/macro.html#argument-caveats + if (${ARGV2}) + requires_regeneration("${AC_INPUT_FILE}") + endif() + endif() endmacro() +#### +# Function `requires_regeneration`: +# +# Called by the autocoder when a source file needs to setup CMake to reconfigure when the source file changes. +# +# `AC_INPUT_FILE`: file to mark as tracked +#### +function(requires_regeneration AC_INPUT_FILE) + get_property(RECONFIGURE_LIST GLOBAL PROPERTY AUTO_RECONFIGURE_LIST) + get_filename_component(REAL_FILE "${AC_INPUT_FILE}" REALPATH) + if (NOT "${REAL_FILE}" IN_LIST RECONFIGURE_LIST) + set_property(DIRECTORY APPEND PROPERTY CMAKE_CONFIGURE_DEPENDS "${AC_INPUT_FILE}") + list(APPEND RECONFIGURE_LIST "${REAL_FILE}") + set_property(GLOBAL PROPERTY AUTO_RECONFIGURE_LIST "${RECONFIGURE_LIST}") + endif() +endfunction() + #### # Function `_set_autocoder_name`: # diff --git a/cmake/target/build.cmake b/cmake/target/build.cmake index 366ba8f68f..6e9459c200 100644 --- a/cmake/target/build.cmake +++ b/cmake/target/build.cmake @@ -54,16 +54,18 @@ function(build_setup_build_module MODULE SOURCES GENERATED EXCLUDED_SOURCES DEPE get_target_property(MODULE_SOURCES "${MODULE}" SOURCES) list(REMOVE_ITEM MODULE_SOURCES "${EMPTY}") - set_target_properties( - ${MODULE} - PROPERTIES - SOURCES "${MODULE_SOURCES}" - ) - # Setup the hash file for our sources - foreach(SRC_FILE IN LISTS MODULE_SOURCES) - set_hash_flag("${SRC_FILE}") - endforeach() - + # Only update module sources if the list is not empty. Otherwise we keep empty.c as the only source. + if (NOT "${MODULE_SOURCES}" STREQUAL "") + set_target_properties( + ${MODULE} + PROPERTIES + SOURCES "${MODULE_SOURCES}" + ) + # Setup the hash file for our sources + foreach(SRC_FILE IN LISTS MODULE_SOURCES) + set_hash_flag("${SRC_FILE}") + endforeach() + endif() # Includes the source, so that the Ac files can include source headers target_include_directories("${MODULE}" PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/cmake/utilities.cmake b/cmake/utilities.cmake index 0435934d66..f2d590392c 100644 --- a/cmake/utilities.cmake +++ b/cmake/utilities.cmake @@ -186,7 +186,7 @@ endfunction(ends_with) #### function(init_variables) foreach (VARIABLE IN LISTS ARGN) - set(${VARIABLE} PARENT_SCOPE) + set(${VARIABLE} "" PARENT_SCOPE) endforeach() endfunction(init_variables) diff --git a/docs/UsersGuide/dev/autocoder-integration.md b/docs/UsersGuide/dev/autocoder-integration.md index b85e4f3c54..65ba0f7d03 100644 --- a/docs/UsersGuide/dev/autocoder-integration.md +++ b/docs/UsersGuide/dev/autocoder-integration.md @@ -89,6 +89,27 @@ function(_is_supported AC_INPUT_FILE) endfunction(_is_supported ) ``` +Should an autocoder need to indicate that a given input file will cause inter-target dependency changes (i.e. CMake +re-generation must be performed) then the function `requires_regeneration()` must be called. This can be +done directly or by providing `TRUE` as an optional third argument to `autocoder_support_by_suffix`. Both ways are shown below. + +```cmake +... +include(autocoder/helpers) +... +function(_is_supported AC_INPUT_FILE) + requires_regeneration("${AC_INPUT_FILE}") +endfunction(_is_supported ) +``` +```cmake +... +include(autocoder/helpers) +... +function(_is_supported AC_INPUT_FILE) + autocoder_support_by_suffix(".fpp" "${AC_INPUT_FILE}" TRUE) +endfunction(_is_supported ) +``` + ## Implement `_setup_autocode AC_INPUT_FILES)` Implementing `_setup_autocode AC_INPUT_FILES)` should setup the autocoder for generating files. It will From 3b41a9cb2c6b731f133653426347e5fa5aa41bd7 Mon Sep 17 00:00:00 2001 From: codeflight1 Date: Mon, 3 Oct 2022 14:08:20 -0700 Subject: [PATCH 068/169] remove locs.fpp, subdirs.txt, update-locs, and update-subdirs (#1699) --- Drv/locs.fpp | 11 ---------- Drv/subdirs.txt | 3 --- Drv/update-locs | 3 --- Drv/update-subdirs | 3 --- Fpp/locs.fpp | 1 - Fpp/update-locs | 3 --- Fw/locs.fpp | 29 --------------------------- Fw/subdirs.txt | 8 -------- Fw/update-locs | 3 --- Fw/update-subdirs | 3 --- Ref/locs.fpp | 48 -------------------------------------------- Ref/subdirs.txt | 5 ----- Ref/update-locs | 3 --- Ref/update-subdirs | 3 --- Svc/locs.fpp | 50 ---------------------------------------------- Svc/subdirs.txt | 35 -------------------------------- Svc/update-locs | 3 --- Svc/update-subdirs | 3 --- config/locs.fpp | 19 ------------------ config/update-locs | 3 --- 20 files changed, 239 deletions(-) delete mode 100644 Drv/locs.fpp delete mode 100644 Drv/subdirs.txt delete mode 100755 Drv/update-locs delete mode 100755 Drv/update-subdirs delete mode 100644 Fpp/locs.fpp delete mode 100755 Fpp/update-locs delete mode 100644 Fw/locs.fpp delete mode 100644 Fw/subdirs.txt delete mode 100755 Fw/update-locs delete mode 100755 Fw/update-subdirs delete mode 100644 Ref/locs.fpp delete mode 100644 Ref/subdirs.txt delete mode 100755 Ref/update-locs delete mode 100755 Ref/update-subdirs delete mode 100644 Svc/locs.fpp delete mode 100644 Svc/subdirs.txt delete mode 100755 Svc/update-locs delete mode 100755 Svc/update-subdirs delete mode 100644 config/locs.fpp delete mode 100755 config/update-locs diff --git a/Drv/locs.fpp b/Drv/locs.fpp deleted file mode 100644 index 1149e2c5a7..0000000000 --- a/Drv/locs.fpp +++ /dev/null @@ -1,11 +0,0 @@ -locate component Drv.BlockDriver at "BlockDriver/BlockDriver.fpp" -locate component Drv.ByteStreamDriverModel at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate port Drv.ByteStreamPoll at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate port Drv.ByteStreamReady at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate port Drv.ByteStreamRecv at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate port Drv.ByteStreamSend at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate port Drv.DataBuffer at "DataTypes/DataTypes.fpp" -locate type Drv.DataBuffer at "DataTypes/DataTypes.fpp" -locate type Drv.PollStatus at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate type Drv.RecvStatus at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" -locate type Drv.SendStatus at "ByteStreamDriverModel/ByteStreamDriverModel.fpp" diff --git a/Drv/subdirs.txt b/Drv/subdirs.txt deleted file mode 100644 index afab5e0325..0000000000 --- a/Drv/subdirs.txt +++ /dev/null @@ -1,3 +0,0 @@ -BlockDriver -ByteStreamDriverModel -DataTypes diff --git a/Drv/update-locs b/Drv/update-locs deleted file mode 100755 index 76583058af..0000000000 --- a/Drv/update-locs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -fpp-locate-defs `find . -name '*.fpp'` > locs.fpp diff --git a/Drv/update-subdirs b/Drv/update-subdirs deleted file mode 100755 index f86970a7cb..0000000000 --- a/Drv/update-subdirs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -find . -mindepth 2 -name '*.fpp' | cut -d '/' -f 2 | sort | uniq > subdirs.txt diff --git a/Fpp/locs.fpp b/Fpp/locs.fpp deleted file mode 100644 index 2844f84f24..0000000000 --- a/Fpp/locs.fpp +++ /dev/null @@ -1 +0,0 @@ -locate type Fpp.ToCpp.Phases at "ToCpp.fpp" diff --git a/Fpp/update-locs b/Fpp/update-locs deleted file mode 100755 index 76583058af..0000000000 --- a/Fpp/update-locs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -fpp-locate-defs `find . -name '*.fpp'` > locs.fpp diff --git a/Fw/locs.fpp b/Fw/locs.fpp deleted file mode 100644 index 6c2da0e730..0000000000 --- a/Fw/locs.fpp +++ /dev/null @@ -1,29 +0,0 @@ -locate port Fw.BufferGet at "Buffer/Buffer.fpp" -locate port Fw.BufferSend at "Buffer/Buffer.fpp" -locate port Fw.Cmd at "Cmd/Cmd.fpp" -locate port Fw.CmdReg at "Cmd/Cmd.fpp" -locate port Fw.CmdResponse at "Cmd/Cmd.fpp" -locate port Fw.Com at "Com/Com.fpp" -locate port Fw.Log at "Log/Log.fpp" -locate port Fw.LogText at "Log/Log.fpp" -locate port Fw.PrmGet at "Prm/Prm.fpp" -locate port Fw.PrmSet at "Prm/Prm.fpp" -locate port Fw.Time at "Time/Time.fpp" -locate port Fw.Tlm at "Tlm/Tlm.fpp" -locate port Fw.TlmGet at "Tlm/Tlm.fpp" -locate type Fw.Buffer at "Buffer/Buffer.fpp" -locate type Fw.CmdArgBuffer at "Cmd/Cmd.fpp" -locate type Fw.CmdResponse at "Cmd/Cmd.fpp" -locate type Fw.ComBuffer at "Com/Com.fpp" -locate type Fw.DeserialStatus at "Types/Types.fpp" -locate type Fw.Enabled at "Types/Types.fpp" -locate type Fw.LogBuffer at "Log/Log.fpp" -locate type Fw.LogSeverity at "Log/Log.fpp" -locate type Fw.ParamBuffer at "Prm/Prm.fpp" -locate type Fw.ParamValid at "Prm/Prm.fpp" -locate type Fw.PolyType at "Types/Types.fpp" -locate type Fw.SerialStatus at "Types/Types.fpp" -locate type Fw.String at "Types/Types.fpp" -locate type Fw.TextLogString at "Log/Log.fpp" -locate type Fw.Time at "Time/Time.fpp" -locate type Fw.TlmBuffer at "Tlm/Tlm.fpp" diff --git a/Fw/subdirs.txt b/Fw/subdirs.txt deleted file mode 100644 index 86c3a94524..0000000000 --- a/Fw/subdirs.txt +++ /dev/null @@ -1,8 +0,0 @@ -Buffer -Cmd -Com -Log -Prm -Time -Tlm -Types diff --git a/Fw/update-locs b/Fw/update-locs deleted file mode 100755 index 76583058af..0000000000 --- a/Fw/update-locs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -fpp-locate-defs `find . -name '*.fpp'` > locs.fpp diff --git a/Fw/update-subdirs b/Fw/update-subdirs deleted file mode 100755 index f86970a7cb..0000000000 --- a/Fw/update-subdirs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -find . -mindepth 2 -name '*.fpp' | cut -d '/' -f 2 | sort | uniq > subdirs.txt diff --git a/Ref/locs.fpp b/Ref/locs.fpp deleted file mode 100644 index 8de60b43b4..0000000000 --- a/Ref/locs.fpp +++ /dev/null @@ -1,48 +0,0 @@ -locate component Ref.PingReceiver at "PingReceiver/PingReceiver.fpp" -locate component Ref.RecvBuff at "RecvBuffApp/RecvBuffApp.fpp" -locate component Ref.SendBuff at "SendBuffApp/SendBuffApp.fpp" -locate component Ref.SignalGen at "SignalGen/SignalGen.fpp" -locate constant Ref.Default.queueSize at "Top/instances.fpp" -locate constant Ref.Default.stackSize at "Top/instances.fpp" -locate instance Ref.$health at "Top/instances.fpp" -locate instance Ref.SG1 at "Top/instances.fpp" -locate instance Ref.SG2 at "Top/instances.fpp" -locate instance Ref.SG3 at "Top/instances.fpp" -locate instance Ref.SG4 at "Top/instances.fpp" -locate instance Ref.SG5 at "Top/instances.fpp" -locate instance Ref.blockDrv at "Top/instances.fpp" -locate instance Ref.chanTlm at "Top/instances.fpp" -locate instance Ref.cmdDisp at "Top/instances.fpp" -locate instance Ref.cmdSeq at "Top/instances.fpp" -locate instance Ref.comm at "Top/instances.fpp" -locate instance Ref.downlink at "Top/instances.fpp" -locate instance Ref.eventLogger at "Top/instances.fpp" -locate instance Ref.fatalAdapter at "Top/instances.fpp" -locate instance Ref.fatalHandler at "Top/instances.fpp" -locate instance Ref.fileDownlink at "Top/instances.fpp" -locate instance Ref.fileManager at "Top/instances.fpp" -locate instance Ref.fileUplink at "Top/instances.fpp" -locate instance Ref.fileUplinkBufferManager at "Top/instances.fpp" -locate instance Ref.linuxTime at "Top/instances.fpp" -locate instance Ref.pingRcvr at "Top/instances.fpp" -locate instance Ref.prmDb at "Top/instances.fpp" -locate instance Ref.rateGroup1Comp at "Top/instances.fpp" -locate instance Ref.rateGroup2Comp at "Top/instances.fpp" -locate instance Ref.rateGroup3Comp at "Top/instances.fpp" -locate instance Ref.rateGroupDriverComp at "Top/instances.fpp" -locate instance Ref.recvBuffComp at "Top/instances.fpp" -locate instance Ref.sendBuffComp at "Top/instances.fpp" -locate instance Ref.staticMemory at "Top/instances.fpp" -locate instance Ref.textLogger at "Top/instances.fpp" -locate instance Ref.uplink at "Top/instances.fpp" -locate topology Ref.Ref at "Top/topology.fpp" -locate type Ref.PacketRecvStatus at "RecvBuffApp/RecvBuffApp.fpp" -locate type Ref.PacketStat at "RecvBuffApp/RecvBuffApp.fpp" -locate type Ref.Ports_RateGroups at "Top/topology.fpp" -locate type Ref.Ports_StaticMemory at "Top/topology.fpp" -locate type Ref.SendBuff.ActiveState at "SendBuffApp/SendBuffApp.fpp" -locate type Ref.SignalInfo at "SignalGen/SignalGen.fpp" -locate type Ref.SignalPair at "SignalGen/SignalGen.fpp" -locate type Ref.SignalPairSet at "SignalGen/SignalGen.fpp" -locate type Ref.SignalSet at "SignalGen/SignalGen.fpp" -locate type Ref.SignalType at "SignalGen/SignalGen.fpp" diff --git a/Ref/subdirs.txt b/Ref/subdirs.txt deleted file mode 100644 index 0bc5265b21..0000000000 --- a/Ref/subdirs.txt +++ /dev/null @@ -1,5 +0,0 @@ -PingReceiver -RecvBuffApp -SendBuffApp -SignalGen -Top diff --git a/Ref/update-locs b/Ref/update-locs deleted file mode 100755 index 76583058af..0000000000 --- a/Ref/update-locs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -fpp-locate-defs `find . -name '*.fpp'` > locs.fpp diff --git a/Ref/update-subdirs b/Ref/update-subdirs deleted file mode 100755 index f86970a7cb..0000000000 --- a/Ref/update-subdirs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -find . -mindepth 2 -name '*.fpp' | cut -d '/' -f 2 | sort | uniq > subdirs.txt diff --git a/Svc/locs.fpp b/Svc/locs.fpp deleted file mode 100644 index 7c79bd583d..0000000000 --- a/Svc/locs.fpp +++ /dev/null @@ -1,50 +0,0 @@ -locate component Svc.ActiveLogger at "ActiveLogger/ActiveLogger.fpp" -locate component Svc.ActiveRateGroup at "ActiveRateGroup/ActiveRateGroup.fpp" -locate component Svc.ActiveTextLogger at "ActiveTextLogger/ActiveTextLogger.fpp" -locate component Svc.AssertFatalAdapter at "AssertFatalAdapter/AssertFatalAdapter.fpp" -locate component Svc.BufferLogger at "BufferLogger/BufferLogger.fpp" -locate component Svc.BufferManager at "BufferManager/BufferManager.fpp" -locate component Svc.CmdSequencer at "CmdSequencer/CmdSequencer.fpp" -locate component Svc.ComLogger at "ComLogger/ComLogger.fpp" -locate component Svc.ComSplitter at "ComSplitter/ComSplitter.fpp" -locate component Svc.CommandDispatcher at "CmdDispatcher/CmdDispatcher.fpp" -locate component Svc.Deframer at "Deframer/Deframer.fpp" -locate component Svc.FatalHandler at "FatalHandler/FatalHandler.fpp" -locate component Svc.FileDownlink at "FileDownlink/FileDownlink.fpp" -locate component Svc.FileManager at "FileManager/FileManager.fpp" -locate component Svc.FileUplink at "FileUplink/FileUplink.fpp" -locate component Svc.Framer at "Framer/Framer.fpp" -locate component Svc.GenericHub at "GenericHub/GenericHub.fpp" -locate component Svc.GenericRepeater at "GenericRepeater/GenericRepeater.fpp" -locate component Svc.GroundInterface at "GroundInterface/GroundInterface.fpp" -locate component Svc.Health at "Health/Health.fpp" -locate component Svc.LinuxTimer at "LinuxTimer/LinuxTimer.fpp" -locate component Svc.PassiveTextLogger at "PassiveConsoleTextLogger/PassiveConsoleTextLogger.fpp" -locate component Svc.PolyDb at "PolyDb/PolyDb.fpp" -locate component Svc.PrmDb at "PrmDb/PrmDb.fpp" -locate component Svc.RateGroupDriver at "RateGroupDriver/RateGroupDriver.fpp" -locate component Svc.StaticMemory at "StaticMemory/StaticMemory.fpp" -locate component Svc.Time at "Time/Time.fpp" -locate component Svc.TlmChan at "TlmChan/TlmChan.fpp" -locate port Svc.CmdSeqCancel at "Seq/Seq.fpp" -locate port Svc.CmdSeqIn at "Seq/Seq.fpp" -locate port Svc.Cycle at "Cycle/Cycle.fpp" -locate port Svc.FatalEvent at "Fatal/Fatal.fpp" -locate port Svc.Ping at "Ping/Ping.fpp" -locate port Svc.Poly at "PolyIf/PolyIf.fpp" -locate port Svc.Sched at "Sched/Sched.fpp" -locate port Svc.SendFileComplete at "FileDownlink/FileDownlink.fpp" -locate port Svc.SendFileRequest at "FileDownlink/FileDownlink.fpp" -locate port Svc.WatchDog at "WatchDog/WatchDog.fpp" -locate type Svc.ActiveLogger.Enabled at "ActiveLogger/ActiveLogger.fpp" -locate type Svc.ActiveLogger.FilterSeverity at "ActiveLogger/ActiveLogger.fpp" -locate type Svc.BufferLogger.LogState at "BufferLogger/BufferLogger.fpp" -locate type Svc.CmdSequencer.BlockState at "CmdSequencer/CmdSequencer.fpp" -locate type Svc.CmdSequencer.FileReadStage at "CmdSequencer/CmdSequencer.fpp" -locate type Svc.CmdSequencer.SeqMode at "CmdSequencer/CmdSequencer.fpp" -locate type Svc.MeasurementStatus at "PolyIf/PolyIf.fpp" -locate type Svc.PrmDb.PrmReadError at "PrmDb/PrmDb.fpp" -locate type Svc.PrmDb.PrmWriteError at "PrmDb/PrmDb.fpp" -locate type Svc.SendFileResponse at "FileDownlink/FileDownlink.fpp" -locate type Svc.SendFileStatus at "FileDownlink/FileDownlink.fpp" -locate type Svc.TimerVal at "Cycle/Cycle.fpp" diff --git a/Svc/subdirs.txt b/Svc/subdirs.txt deleted file mode 100644 index 782fc8c0da..0000000000 --- a/Svc/subdirs.txt +++ /dev/null @@ -1,35 +0,0 @@ -ActiveLogger -ActiveRateGroup -ActiveTextLogger -AssertFatalAdapter -BufferLogger -BufferManager -CmdDispatcher -CmdSequencer -ComLogger -ComSplitter -Cycle -Deframer -Fatal -FatalHandler -FileDownlink -FileManager -FileUplink -Framer -GenericHub -GenericRepeater -GroundInterface -Health -LinuxTimer -PassiveConsoleTextLogger -Ping -PolyDb -PolyIf -PrmDb -RateGroupDriver -Sched -Seq -StaticMemory -Time -TlmChan -WatchDog diff --git a/Svc/update-locs b/Svc/update-locs deleted file mode 100755 index 76583058af..0000000000 --- a/Svc/update-locs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -fpp-locate-defs `find . -name '*.fpp'` > locs.fpp diff --git a/Svc/update-subdirs b/Svc/update-subdirs deleted file mode 100755 index f86970a7cb..0000000000 --- a/Svc/update-subdirs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -find . -mindepth 2 -name '*.fpp' | cut -d '/' -f 2 | sort | uniq > subdirs.txt diff --git a/config/locs.fpp b/config/locs.fpp deleted file mode 100644 index 602254c6dc..0000000000 --- a/config/locs.fpp +++ /dev/null @@ -1,19 +0,0 @@ -locate constant ActiveRateGroupOutputPorts at "AcConstants.fpp" -locate constant CmdDispatcherComponentCommandPorts at "AcConstants.fpp" -locate constant CmdDispatcherSequencePorts at "AcConstants.fpp" -locate constant FileDownCompletePorts at "AcConstants.fpp" -locate constant GenericHubInputBuffers at "AcConstants.fpp" -locate constant GenericHubInputPorts at "AcConstants.fpp" -locate constant GenericHubOutputBuffers at "AcConstants.fpp" -locate constant GenericHubOutputPorts at "AcConstants.fpp" -locate constant GenericRepeaterOutputPorts at "AcConstants.fpp" -locate constant HealthPingPorts at "AcConstants.fpp" -locate constant RateGroupDriverRateGroupPorts at "AcConstants.fpp" -locate constant StaticMemoryAllocations at "AcConstants.fpp" -locate type FwChanIdType at "FpConfig.fpp" -locate type FwEventIdType at "FpConfig.fpp" -locate type FwOpcodeType at "FpConfig.fpp" -locate type FwPrmIdType at "FpConfig.fpp" -locate type NATIVE_INT_TYPE at "FpConfig.fpp" -locate type NATIVE_UINT_TYPE at "FpConfig.fpp" -locate type POINTER_CAST at "FpConfig.fpp" diff --git a/config/update-locs b/config/update-locs deleted file mode 100755 index 76583058af..0000000000 --- a/config/update-locs +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/sh - -fpp-locate-defs `find . -name '*.fpp'` > locs.fpp From fdc382cc83ee1dd854356f862399a441dc9ec99b Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Tue, 4 Oct 2022 13:12:17 -0700 Subject: [PATCH 069/169] Make UTs work with FW_ASSERT_LEVEL == FW_FILEID_ASSERT (#1703) * Fix UTs with FILEID_ASSERT * Replace %X with %PRIX32 --- Fw/Types/test/ut/TypesTest.cpp | 4 ++++ .../AssertFatalAdapterComponentImpl.cpp | 2 +- Svc/AssertFatalAdapter/test/ut/Tester.cpp | 23 +++++++++++++++---- 3 files changed, 24 insertions(+), 5 deletions(-) diff --git a/Fw/Types/test/ut/TypesTest.cpp b/Fw/Types/test/ut/TypesTest.cpp index f0d96211ea..d3af331a47 100644 --- a/Fw/Types/test/ut/TypesTest.cpp +++ b/Fw/Types/test/ut/TypesTest.cpp @@ -795,7 +795,11 @@ void AssertTest() { private: +#if FW_ASSERT_LEVEL == FW_FILEID_ASSERT + FILE_NAME_ARG m_file = 0; +#else FILE_NAME_ARG m_file = nullptr; +#endif NATIVE_UINT_TYPE m_lineNo = 0; NATIVE_UINT_TYPE m_numArgs = 0; FwAssertArgType m_arg1 = 0; diff --git a/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp b/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp index eecf4bf7e0..69d2f8d40a 100644 --- a/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp +++ b/Svc/AssertFatalAdapter/AssertFatalAdapterComponentImpl.cpp @@ -119,7 +119,7 @@ namespace Svc { #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT Fw::LogStringArg fileArg; - fileArg.format("0x%08X",file); + fileArg.format("0x%08" PRIX32,file); #else Fw::LogStringArg fileArg(file); #endif diff --git a/Svc/AssertFatalAdapter/test/ut/Tester.cpp b/Svc/AssertFatalAdapter/test/ut/Tester.cpp index 1991f96652..24eb86b63b 100644 --- a/Svc/AssertFatalAdapter/test/ut/Tester.cpp +++ b/Svc/AssertFatalAdapter/test/ut/Tester.cpp @@ -10,8 +10,9 @@ // // ====================================================================== -#include "Tester.hpp" +#include "Fw/Types/String.hpp" #include "Fw/Types/StringUtils.hpp" +#include "Tester.hpp" #define INSTANCE 0 #define MAX_HISTORY_SIZE 10 @@ -40,7 +41,13 @@ namespace Svc { U32 lineNo; char file[80 + 1]; // Limit to 80 characters in the port call - (void) Fw::StringUtils::string_copy(file, __FILE__, sizeof(file)); + Fw::String fileString; +#if FW_ASSERT_LEVEL == FW_FILEID_ASSERT + fileString.format("0x%08" PRIX32, ASSERT_FILE_ID); +#else + fileString = __FILE__; +#endif + (void) Fw::StringUtils::string_copy(file, fileString.toChar(), sizeof(file)); // FW_ASSERT_0 @@ -85,9 +92,17 @@ namespace Svc { ASSERT_EVENTS_AF_ASSERT_6(0,file,lineNo,1,2,3,4,5,6); // Test unexpected assert - this->component.reportAssert("foo",1000,10,1,2,3,4,5,6); +#if FW_ASSERT_LEVEL == FW_FILEID_ASSERT + U32 unexpectedFile = 0xF00; + const char *const unexpectedFileArg = "0x00000F00"; +#else + const char *const unexpectedFile = "foo"; + const char *const unexpectedFileArg = unexpectedFile; +#endif + + this->component.reportAssert(unexpectedFile,1000,10,1,2,3,4,5,6); ASSERT_EVENTS_AF_UNEXPECTED_ASSERT_SIZE(1); - ASSERT_EVENTS_AF_UNEXPECTED_ASSERT(0,"foo",1000,10); + ASSERT_EVENTS_AF_UNEXPECTED_ASSERT(0,unexpectedFileArg,1000,10); } From c5767dff0a18db3956d2632a456465c8119c5790 Mon Sep 17 00:00:00 2001 From: codeflight1 Date: Tue, 4 Oct 2022 15:54:30 -0700 Subject: [PATCH 070/169] Add standard FPP types (#1698) * Add standard FPP types * Update LinuxGpioDriver to use new Fw::Logic type * sp * RPI deployment fixes --- .github/actions/spelling/expect.txt | 1 + Drv/GpioDriverPorts/GpioDriverPorts.fpp | 4 +- .../LinuxGpioDriverComponentImpl.cpp | 8 ++-- .../LinuxGpioDriverComponentImpl.hpp | 4 +- .../LinuxGpioDriverComponentImplStub.cpp | 4 +- Fw/Types/Types.fpp | 38 +++++++++++++++++++ RPI/RpiDemo/RpiDemo.fpp | 11 ++---- RPI/RpiDemo/RpiDemoComponentImpl.cpp | 19 ++++------ RPI/RpiDemo/RpiDemoComponentImpl.hpp | 4 +- 9 files changed, 62 insertions(+), 31 deletions(-) diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 84ddc620b7..18048eb49d 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -655,6 +655,7 @@ inits initstate inkscape inode +INOUT INPCK Inputline installable diff --git a/Drv/GpioDriverPorts/GpioDriverPorts.fpp b/Drv/GpioDriverPorts/GpioDriverPorts.fpp index ae37e09a77..9bb6a2297a 100644 --- a/Drv/GpioDriverPorts/GpioDriverPorts.fpp +++ b/Drv/GpioDriverPorts/GpioDriverPorts.fpp @@ -1,7 +1,7 @@ module Drv { port GpioWrite( - state: bool + state: Fw.Logic ) } @@ -9,7 +9,7 @@ module Drv { module Drv { port GpioRead( - ref state: bool + ref state: Fw.Logic ) } diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp index 3b4eec017f..4c3d62beed 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp @@ -251,7 +251,7 @@ namespace Drv { void LinuxGpioDriverComponentImpl :: gpioRead_handler( const NATIVE_INT_TYPE portNum, - bool &state + Fw::Logic &state ) { FW_ASSERT(this->m_fd != -1); @@ -262,7 +262,7 @@ namespace Drv { this->log_WARNING_HI_GP_ReadError(this->m_gpio,stat); return; } else { - state = val?true:false; + state = val ? Fw::Logic::HIGH : Fw::Logic::LOW; } } @@ -270,14 +270,14 @@ namespace Drv { void LinuxGpioDriverComponentImpl :: gpioWrite_handler( const NATIVE_INT_TYPE portNum, - bool state + const Fw::Logic& state ) { FW_ASSERT(this->m_fd != -1); NATIVE_INT_TYPE stat; - stat = gpio_set_value(this->m_fd,state?1:0); + stat = gpio_set_value(this->m_fd,(state == Fw::Logic::HIGH) ? 1 : 0); if (0 != stat) { this->log_WARNING_HI_GP_WriteError(this->m_gpio,stat); diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.hpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.hpp index 2fbb2a916a..559dfccf2b 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.hpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.hpp @@ -70,14 +70,14 @@ namespace Drv { //! void gpioRead_handler( const NATIVE_INT_TYPE portNum, /*!< The port number*/ - bool &state + Fw::Logic &state ); //! Handler implementation for gpioWrite //! void gpioWrite_handler( const NATIVE_INT_TYPE portNum, /*!< The port number*/ - bool state + const Fw::Logic& state ); //! keep GPIO ID diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp index 761b36dab7..41663e8d67 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImplStub.cpp @@ -23,7 +23,7 @@ namespace Drv { void LinuxGpioDriverComponentImpl :: gpioRead_handler( const NATIVE_INT_TYPE portNum, - bool &state + Fw::Logic &state ) { // TODO @@ -32,7 +32,7 @@ namespace Drv { void LinuxGpioDriverComponentImpl :: gpioWrite_handler( const NATIVE_INT_TYPE portNum, - bool state + const Fw::Logic& state ) { // TODO diff --git a/Fw/Types/Types.fpp b/Fw/Types/Types.fpp index bdfcf32a83..a109da5fcd 100644 --- a/Fw/Types/Types.fpp +++ b/Fw/Types/Types.fpp @@ -28,4 +28,42 @@ module Fw { ENABLED @< Enabled state } + @ On and off states + enum On { + OFF @< Off state + ON @< On state + } + + @ Logic states + enum Logic { + LOW @< Logic low state + HIGH @< Logic high state + } + + @ Open and closed states + enum Open { + CLOSED @< Closed state + OPEN @< Open state + } + + @ Direction states + enum Direction { + IN @< In direction + OUT @< Out direction + INOUT @< In/Out direction + } + + @ Active and inactive states + enum Active { + INACTIVE @< Inactive state + ACTIVE @< Active state + } + + @ Health states + enum Health { + HEALTHY @< Healthy state + SICK @< Sick state + FAILED @< Failed state + } + } diff --git a/RPI/RpiDemo/RpiDemo.fpp b/RPI/RpiDemo/RpiDemo.fpp index 5bbcd2d206..01bee01e73 100644 --- a/RPI/RpiDemo/RpiDemo.fpp +++ b/RPI/RpiDemo/RpiDemo.fpp @@ -17,11 +17,6 @@ module RPI { PIN_24 = 1 } - enum GpioVal { - CLEAR = 0 - SET = 1 - } - enum LedState { BLINKING = 0 OFF = 1 @@ -108,7 +103,7 @@ module RPI { @ Sets a GPIO port value async command RD_SetGpio( $output: GpioOutNum @< Output GPIO - value: GpioVal @< GPIO value + value: Fw.Logic @< GPIO value ) \ opcode 3 @@ -147,7 +142,7 @@ module RPI { @ GPIO set event RD_GpioSetVal( $output: U32 @< The output number - value: GpioVal @< GPIO value + value: Fw.Logic @< GPIO value ) \ severity activity high \ id 2 \ @@ -156,7 +151,7 @@ module RPI { @ GPIO get event RD_GpioGetVal( $output: U32 @< The output number - value: GpioVal @< GPIO value + value: Fw.Logic @< GPIO value ) \ severity activity high \ id 3 \ diff --git a/RPI/RpiDemo/RpiDemoComponentImpl.cpp b/RPI/RpiDemo/RpiDemoComponentImpl.cpp index fefec210f6..aa285559b6 100644 --- a/RPI/RpiDemo/RpiDemoComponentImpl.cpp +++ b/RPI/RpiDemo/RpiDemoComponentImpl.cpp @@ -28,7 +28,7 @@ namespace RPI { ,m_uartWriteBytes(0) ,m_uartReadBytes(0) ,m_spiBytes(0) - ,m_currLedVal(RpiDemo_GpioVal::CLEAR) + ,m_currLedVal(Fw::Logic::LOW) ,m_ledOn(true) ,m_ledDivider(10) // start at 1Hz ,m_1HzTicks(0) @@ -99,9 +99,9 @@ namespace RPI { case RG_CONTEXT_10Hz: // Toggle LED value if ( (this->m_10HzTicks++%this->m_ledDivider == 0) and this->m_ledOn) { - this->GpioWrite_out(2, (this->m_currLedVal == RpiDemo_GpioVal::SET)); - this->m_currLedVal = (this->m_currLedVal == RpiDemo_GpioVal::SET) ? - RpiDemo_GpioVal::CLEAR : RpiDemo_GpioVal::SET; + this->GpioWrite_out(2, this->m_currLedVal); + this->m_currLedVal = (this->m_currLedVal == Fw::Logic::HIGH) ? + Fw::Logic::LOW : Fw::Logic::HIGH; } break; default: @@ -166,7 +166,7 @@ namespace RPI { const FwOpcodeType opCode, const U32 cmdSeq, RpiDemo_GpioOutNum output, /*!< Output GPIO*/ - RpiDemo_GpioVal value + Fw::Logic value ) { NATIVE_INT_TYPE port; @@ -188,7 +188,7 @@ namespace RPI { return; } // set value of GPIO - this->GpioWrite_out(port, (RpiDemo_GpioVal::SET == value.e)); + this->GpioWrite_out(port, value); this->log_ACTIVITY_HI_RD_GpioSetVal(output.e, value); this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); } @@ -215,12 +215,9 @@ namespace RPI { return; } // get value of GPIO input - bool val; + Fw::Logic val; this->GpioRead_out(port, val); - this->log_ACTIVITY_HI_RD_GpioGetVal( - input.e, - val ? RpiDemo_GpioVal::SET : RpiDemo_GpioVal::CLEAR - ); + this->log_ACTIVITY_HI_RD_GpioGetVal(input.e, val); this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); } diff --git a/RPI/RpiDemo/RpiDemoComponentImpl.hpp b/RPI/RpiDemo/RpiDemoComponentImpl.hpp index 7c02977b27..3b42dda276 100644 --- a/RPI/RpiDemo/RpiDemoComponentImpl.hpp +++ b/RPI/RpiDemo/RpiDemoComponentImpl.hpp @@ -98,7 +98,7 @@ namespace RPI { const FwOpcodeType opCode, /*!< The opcode*/ const U32 cmdSeq, /*!< The command sequence number*/ RpiDemo_GpioOutNum output, /*!< Output GPIO*/ - RpiDemo_GpioVal value /*!< GPIO value*/ + Fw::Logic value /*!< GPIO value*/ ) override; //! Implementation for RD_GetGpio command handler @@ -142,7 +142,7 @@ namespace RPI { U32 m_uartReadBytes; U32 m_spiBytes; Fw::TlmString m_lastUartMsg; - RpiDemo_GpioVal m_currLedVal; + Fw::Logic m_currLedVal; // serial buffers Fw::Buffer m_recvBuffers[NUM_RPI_UART_BUFFERS]; BYTE m_uartBuffers[NUM_RPI_UART_BUFFERS][RPI_UART_READ_BUFF_SIZE]; From 0cef78e7f686e303eaf93e6fb6d93885ef9e693a Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 7 Oct 2022 12:59:34 -0700 Subject: [PATCH 071/169] lestarch: com stub component (#1711) * lestarch: adding success type and success port * lestarch: com stub and ut * lestarch: improved com stub documentation * lestarch: fix header guards * lestarch: sp --- .github/actions/spelling/expect.txt | 1 + Fw/CMakeLists.txt | 1 + Fw/Ports/SuccessCondition/CMakeLists.txt | 9 + .../SuccessCondition/SuccessCondition.fpp | 12 ++ Fw/Types/Types.fpp | 5 + Svc/CMakeLists.txt | 1 + Svc/ComStub/CMakeLists.txt | 23 +++ Svc/ComStub/ComStub.cpp | 58 ++++++ Svc/ComStub/ComStub.fpp | 31 ++++ Svc/ComStub/ComStub.hpp | 60 ++++++ Svc/ComStub/docs/img/byte-stream.png | Bin 0 -> 52177 bytes Svc/ComStub/docs/img/com-adapter.png | Bin 0 -> 90892 bytes Svc/ComStub/docs/sdd.md | 96 ++++++++++ Svc/ComStub/test/ut/TestMain.cpp | 31 ++++ Svc/ComStub/test/ut/Tester.cpp | 172 ++++++++++++++++++ Svc/ComStub/test/ut/Tester.hpp | 104 +++++++++++ .../communications-adapter-interface.md | 63 +++++++ docs/Design/img/com-adapter.png | Bin 0 -> 92476 bytes docs/Design/memory.md | 3 + 19 files changed, 670 insertions(+) create mode 100644 Fw/Ports/SuccessCondition/CMakeLists.txt create mode 100644 Fw/Ports/SuccessCondition/SuccessCondition.fpp create mode 100644 Svc/ComStub/CMakeLists.txt create mode 100644 Svc/ComStub/ComStub.cpp create mode 100644 Svc/ComStub/ComStub.fpp create mode 100644 Svc/ComStub/ComStub.hpp create mode 100644 Svc/ComStub/docs/img/byte-stream.png create mode 100644 Svc/ComStub/docs/img/com-adapter.png create mode 100644 Svc/ComStub/docs/sdd.md create mode 100644 Svc/ComStub/test/ut/TestMain.cpp create mode 100644 Svc/ComStub/test/ut/Tester.cpp create mode 100644 Svc/ComStub/test/ut/Tester.hpp create mode 100644 docs/Design/communications-adapter-interface.md create mode 100644 docs/Design/img/com-adapter.png create mode 100644 docs/Design/memory.md diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 18048eb49d..7e1a503a8e 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -204,6 +204,7 @@ commonpath COMPACKET COMPONENTTESTERIMPL COMSPLITTER +COMSTUB Concat config configparser diff --git a/Fw/CMakeLists.txt b/Fw/CMakeLists.txt index b7be5aa001..8d34393ace 100644 --- a/Fw/CMakeLists.txt +++ b/Fw/CMakeLists.txt @@ -15,6 +15,7 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Cfg/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Comp/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Obj/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Port/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Ports/SuccessCondition") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Types/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FilePacket/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/SerializableFile/") diff --git a/Fw/Ports/SuccessCondition/CMakeLists.txt b/Fw/Ports/SuccessCondition/CMakeLists.txt new file mode 100644 index 0000000000..dff861112c --- /dev/null +++ b/Fw/Ports/SuccessCondition/CMakeLists.txt @@ -0,0 +1,9 @@ +#### +# CMakeLists.txt: +# +# Sets up the fprime module build within CMake. +#### +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/SuccessCondition.fpp" +) +register_fprime_module() \ No newline at end of file diff --git a/Fw/Ports/SuccessCondition/SuccessCondition.fpp b/Fw/Ports/SuccessCondition/SuccessCondition.fpp new file mode 100644 index 0000000000..598c4e8250 --- /dev/null +++ b/Fw/Ports/SuccessCondition/SuccessCondition.fpp @@ -0,0 +1,12 @@ +##### +# SuccessCondition: +# +# A port communicating a success or failure condition. +##### + +module Fw { + @ Port communicating success or failure condition + port SuccessCondition( + ref condition: Fw.Success @< Condition success/failure + ) +} \ No newline at end of file diff --git a/Fw/Types/Types.fpp b/Fw/Types/Types.fpp index a109da5fcd..560f0e8e30 100644 --- a/Fw/Types/Types.fpp +++ b/Fw/Types/Types.fpp @@ -66,4 +66,9 @@ module Fw { FAILED @< Failed state } + @ Success/Failure + enum Success { + FAILURE @< Representing failure + SUCCESS @< Representing success + } } diff --git a/Svc/CMakeLists.txt b/Svc/CMakeLists.txt index f3edc204d9..bf6131e82d 100644 --- a/Svc/CMakeLists.txt +++ b/Svc/CMakeLists.txt @@ -17,6 +17,7 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferManager/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferLogger/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComLogger/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComSplitter/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComStub/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/CmdDispatcher/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/CmdSequencer/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Deframer/") diff --git a/Svc/ComStub/CMakeLists.txt b/Svc/ComStub/CMakeLists.txt new file mode 100644 index 0000000000..a22cc74a44 --- /dev/null +++ b/Svc/ComStub/CMakeLists.txt @@ -0,0 +1,23 @@ +#### +# F prime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoding diles +# MOD_DEPS: (optional) module dependencies +# +# Note: using PROJECT_NAME as EXECUTABLE_NAME +#### +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/ComStub.fpp" + "${CMAKE_CURRENT_LIST_DIR}/ComStub.cpp" +) +register_fprime_module() + +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/ComStub.fpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/TestMain.cpp" +) +set(UT_MOD_DEPS + STest +) +register_fprime_ut() diff --git a/Svc/ComStub/ComStub.cpp b/Svc/ComStub/ComStub.cpp new file mode 100644 index 0000000000..2ba5d670e4 --- /dev/null +++ b/Svc/ComStub/ComStub.cpp @@ -0,0 +1,58 @@ +// ====================================================================== +// \title ComStub.cpp +// \author mstarch +// \brief cpp file for ComStub component implementation class +// ====================================================================== + +#include +#include "Fw/Types/Assert.hpp" +#include "Fw/Types/BasicTypes.hpp" + +namespace Svc { + +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +ComStub::ComStub(const char* const compName) : ComStubComponentBase(compName), m_reinitialize(true) {} + +void ComStub::init(const NATIVE_INT_TYPE instance) { + ComStubComponentBase::init(instance); +} + +ComStub::~ComStub() {} + +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- + +Drv::SendStatus ComStub::comDataIn_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& sendBuffer) { + FW_ASSERT(!this->m_reinitialize); // A message should never get here if we need to reinitialize is needed + Drv::SendStatus driverStatus = Drv::SendStatus::SEND_RETRY; + for (NATIVE_UINT_TYPE i = 0; driverStatus == Drv::SendStatus::SEND_RETRY && i < RETRY_LIMIT; i++) { + driverStatus = this->drvDataOut_out(0, sendBuffer); + } + FW_ASSERT(driverStatus != Drv::SendStatus::SEND_RETRY); // If it is still in retry state, there is no good answer + Fw::Success comSuccess = (driverStatus.e == Drv::SendStatus::SEND_OK) ? Fw::Success::SUCCESS : Fw::Success::FAILURE; + this->m_reinitialize = driverStatus.e != Drv::SendStatus::SEND_OK; + if (this->isConnected_comStatus_OutputPort(0)) { + this->comStatus_out(0, comSuccess); + } + return Drv::SendStatus::SEND_OK; // Always send ok to deframer as it does not handle this anyway +} + +void ComStub::drvConnected_handler(const NATIVE_INT_TYPE portNum) { + Fw::Success radioSuccess = Fw::Success::SUCCESS; + if (this->isConnected_comStatus_OutputPort(0) && m_reinitialize) { + this->m_reinitialize = false; + this->comStatus_out(0, radioSuccess); + } +} + +void ComStub::drvDataIn_handler(const NATIVE_INT_TYPE portNum, + Fw::Buffer& recvBuffer, + const Drv::RecvStatus& recvStatus) { + this->comDataOut_out(0, recvBuffer, recvStatus); +} + +} // end namespace Svc diff --git a/Svc/ComStub/ComStub.fpp b/Svc/ComStub/ComStub.fpp new file mode 100644 index 0000000000..65576cc854 --- /dev/null +++ b/Svc/ComStub/ComStub.fpp @@ -0,0 +1,31 @@ +module Svc { + @ Communication adapter interface implementing communication adapter interface via a Drv.ByteStreamDriverModel. + passive component ComStub { + + # ---------------------------------------------------------------------- + # Framer, deframer, and queue ports + # ---------------------------------------------------------------------- + + @ Data coming in from the framing component + sync input port comDataIn: Drv.ByteStreamSend + + @ Status of the last radio transmission + output port comStatus: Fw.SuccessCondition + + @ Com data passing back out + output port comDataOut: Drv.ByteStreamRecv + + # ---------------------------------------------------------------------- + # Byte stream model + # ---------------------------------------------------------------------- + + @ Ready signal when driver is connected + sync input port drvConnected: Drv.ByteStreamReady + + @ Data received from driver + sync input port drvDataIn: Drv.ByteStreamRecv + + @ Data going to the underlying driver + output port drvDataOut: Drv.ByteStreamSend + } +} \ No newline at end of file diff --git a/Svc/ComStub/ComStub.hpp b/Svc/ComStub/ComStub.hpp new file mode 100644 index 0000000000..f75b634660 --- /dev/null +++ b/Svc/ComStub/ComStub.hpp @@ -0,0 +1,60 @@ +// ====================================================================== +// \title ComStub.hpp +// \author mstarch +// \brief hpp file for ComStub component implementation class +// ====================================================================== + +#ifndef Svc_ComStub_HPP +#define Svc_ComStub_HPP + +#include "Svc/ComStub/ComStubComponentAc.hpp" + +namespace Svc { + +class ComStub : public ComStubComponentBase { + public: + const NATIVE_UINT_TYPE RETRY_LIMIT = 10; + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object ComStub + //! + ComStub(const char* const compName /*!< The component name*/ + ); + + //! Initialize object ComStub + //! + void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ + ); + + //! Destroy object ComStub + //! + ~ComStub() override; + + private: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for comDataIn + //! + Drv::SendStatus comDataIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& sendBuffer) override; + + //! Handler implementation for drvConnected + //! + void drvConnected_handler(const NATIVE_INT_TYPE portNum) override; + + //! Handler implementation for drvDataIn + //! + void drvDataIn_handler(const NATIVE_INT_TYPE portNum, + /*!< The port number*/ Fw::Buffer& recvBuffer, + const Drv::RecvStatus& recvStatus) override; + + bool m_reinitialize; //!< Stores if a ready signal is needed on connection +}; + +} // end namespace Svc + +#endif diff --git a/Svc/ComStub/docs/img/byte-stream.png b/Svc/ComStub/docs/img/byte-stream.png new file mode 100644 index 0000000000000000000000000000000000000000..73e31a320db38a46fa19b7f659efee309d04fd81 GIT binary patch literal 52177 zcmeFZcTg1Fwl_=?P@@d+)W^UVDY#T20t0Cy-!e5+=5{lycs;pRzr`ei9}?{&dS)yS+BzhQoT%2aAH~+maFHI}tZ-Sex?v zOcdk#yxF?fa@yLsj|dpLSQ}^*I$pq*yL@24GxSUZtB2yAvV{W9eam>=`?&>yIO~D< zJ#wM_{Z!RCUs$ntLePkQ7%f&@tpUB2@%7eq`LlTbo;B>irwZvq!)vSZzJyrKA32il zV#y`!B6V+d3KDaVBz?nTHskC_x%HB(19hue%ZY-q|9!&^tg45}+`V{mrSyA|Pt4fI zpKpfzROzG&$9irnx0RMG7Do1lrc-o8k+@PlE9ELg6NwNW3l(mh8(=Q^6ww@u`|fo4 z<@Wfs5dAf5WmT2H&#=8HmF;F!;vh8=tv{6OOs)T}!61Qw`bH&XC*xb+M(IvY5jC3B z&lO4}UZ)P9ggz5hQe@HIC#_`eY|okNA!N(SWF|(+5gQO1Kj2yHR45_XeIoDwJRNRR zZKYEJr!r1vepQ`t;Z^o@+W@&4B+L<%Hy)6|w#a!XP`g}m^58=uxyjvI6s*kpAwLCV zIrv_Jg_<5m(2Lu##{KA9t`B^y&vfhN^L5L2)E^fO^ZdYOSBt)tgGNs@bMG*6_JotY zSRt@qdb7IQ(P)mwxy}9Rxl*jGsD(41ue^Dz#kOI+TmpH)_$d<~;fEKIU4_eYc6riH z>^&rLyEf!7B-IbD?&Yu>&hifrc8TA}yEe0EHa||Ir7ZnG0K#X%qQ%3(kNuuX${ysv zmMg~p0K^XA5izO!p-*&cse!`QIrf^hj5 z;zM~g3vz+j`>Mq3Gt2l5{M%7V--=~Rh8|NK)1`NN_O_R=wzgSUlx4rh%YNe zl1JYa7OeAL`+`eUHb$>n7fP!Ww|drn!D*qv*eB-mbF1LzCU;WF zcc$N>Ee->NGQQDN=x==@CMzxD*qabp=hbJ>A|1bd)qz-yPqY?96#gjeMn&Y5%RPVK zqlA0(U{^2fkx+49doTzOJA`#vJlg!Rq_`w5(|IeW83@$SRNFWs5H)xVXP1D}1n{|T4&F{AAwX>*V) zA=%O`zBaHQ$mpTO}~O-3!6Yr`tdEzpz6gtb_7%H zrVZXr--t#C7J`NegJa2Qo+usMrs%v=sg!=3eK`V;`L;68$H-jfln;b)EMswA%G6aj zMllZZMRAwPtS+}216`Tw<3g3m_GnJuT6}$26h)J*zpk7RRyE=*%s?MwlM_E`;VRRF zXBwfO4I7m>xa)nhCE7iQf5e~I{NX1)n{aV+^~k7auec2H+1qU_@(jiG-%VI({1yjw zNmQC`v1)dr9^-lhazDPS_08+V%9p+MJ}73VbMrUl#ltJ|osPEKc6bWG((Mu7m?PP& z?&OoJ60W{QzwLM{L3SWGkC^XgfDb&=i*Rw6udd{!UZy@{C->AhPB;~3Qa`ShXu{q_Cz*>&4>)0wA^ z_Kwl+b?zxg3}{ib3_UNsLB`VzmW*2&mJ%6FpUM*Xl*9}?3b(Q6X`8a%Q!cq@wPH|i#lx%vrwYe<1@zoj)z-r;zS%EF+ec5%Nsj1Q30b9-J}Bx%HK0Ckd~@M+{rbjp z{p;rarN>j13%jez5pi6s$uUx5duj1$x@BXc1+XtQitnOQC5yo0_O_C?nb3FpB2=kr z75zNP_{j!kM`buuQDyaW>rR$)lno*o$Kmwy7^?rb#{T@)EXsDH z`>=S=X9co7e2mz>jqquAD63?kg(hFgu!% z=$o|FE(0yf{mR-_es@1CKP`=HVsxaJ7C%!a7GRgiXF-CuzWzj2t}U;>q4?$A)e=GW z0YnoZ*3K@UI+Ff1^HZu}#)%BqBk(hwwV!d8wvjCf4zWDyPRh)A5Aq$fP>fWQVXLN3++yVo#oGy@giC|J$W&tEK6Y|uklM%CI!I=GNA)G_5bwo@v3>8P2AV7ZbkFs&vdiy5l~%=l4Sizo0OV&JxfQC*;d#%q=XHqXH84> z`%YdMnN};i*-#i+(?9SHT~=Qt%-S)Ix=e!}#qVQyr5dSP6k>DS4)VzKzo@kKvV2jg*9k{87b(5f8%}H6U!>cm(Zk)+JKoIxyN&fLT7$COpqXZ=gXC*a zsh{O}lbMPcNwe97;`Ly3eHkR}{L49GbHC5=sUM2ql1x%oP&V^C;Q%$g#syLaP5Ref z&K&Sw%(etI2Vn~sd{4Z-WnPg(O^wyOfQ`jVjU^$KrQOXn6tEY}IaK0;cSWI}etWfx zKG68&nqiFS+Q|v00zxb0FYkA#hm`}y>h!@G@3Q_%nmMturfS6e9r_KqUXJoYEh6rA zrR;|`1ULn$Pu#nhyCV9$=&RXi`ArrGD8j7`RctggupR>EgjjgkG*~x)Gi>0H!KVG^ zxgs_v7Ve+xI9OPrU@W|Uw9y20)i|1hs>>e#End0T*sMD;q(vuqfFu2eyjNgWo{^Q(!$qS3?bT z2}_70-zzJKg*Bh2qcf%-EGbV3;MCFD^%aw+qk|Jv!c&^%PYVg)9CMkUh3QWdS9@s| zLyhN53J@1-CQ-gee2-XUZZR=2Nx4|rNa#FO{Kw`6a3#JIYIw1EntHDm^=Iee2@75**Ea06y~bLbFinigV9s4Bfv9Y3>hJD zQK>)e|Lx9ykN7W78vgf_0)j%q|N7{^-1^^-zJOZ0C_o&6FxfyF%efTv>-|^)R7fO)pv8 z<2jG4wG>f5d{RknDRMb1Y`lN_SZu~|B!mxbcBuaQJ)nIFmOKp=4h|txAlCo>V8A1U zOEGEV{Y|G>*ulbOe|sHIijX|lOD>1-fA{uh1U&Fd+`k)&(36}=c|Y*!?Z2gw5Z-|Q zZ}Y;;^*57TED}46~FhdQvOBrw|x8-f+e3y@F4te zyOfLlA@c7G1jq^`060aad{_SOmL`xX%Kq=JV_}ow;DH%pIfMUgO)xW+rp1^e zuzy|B|18-5kdpuGu>Y~G|Ia(jm|{vUv}`_iYB3vbKk^(kQ{QIgvHk!p=^A?^PR~~C z2V<9MXZfS7+K9&WrF>2*D&_i=S)1JKXYzYswAh;@W@H`A&&x}d2+bqe2$klrT64#VpYbh`b5Oi znA6bwX7Rj#v>cw<=ej0i(YDhny6Gl?-)rA*VlF?F^GV+Pqqe^B%K1!{j-E}$k-}@V z1ulO`8khgz__GI}@K-ENP!Wzj0rjUd;Ve;oZlS%BKoZ}U!wMq0_qoOAl}j86yy=*c zbARXhQ%!$9$ILrZ3Ex`)eT4OL8ZT;j0yYG=B)p{NIQpiU1Lf=h?!B*jEiQmz4;N02 z2Y;kMs(fmS-QgaAEVH!wrysZ&&S3>1@os6+#UE#$+z?~3BmJ-nXnPR$4D70uHkue{ z@jDI+JwIun_#mXFmGwu@oR7@7H?K_4ABKqsB@Rn5dl4Kx-EJ0t1rSmPv^Ae%REhy^ z=jsAn+pJ-w&K+#KW=2W7dT!=&M*VqCC1@;^ER{L4EqbL93I{m<5*V<(R5F?l7*M$$ zGhmn!pYrB-X(-Rx%9?S(Q}7>Bm5F#xPh)aR8Xm#%)1`0-@sxleoHxQ*p8?FhU;$X` zqw$nanO4~U<3RH&!_Je0rx>n(X#UoeoEc{+S*Hj%-~gHLF=UQYD1`ykoTvmIl^xG~ zco{2-+Mu;s8E9O1$BDVYMD7)IxvAebS#K86jEe>QCdN?tl_UBNhAr_}Xw#kA+l@?) z(T%-wve0U528^Y_A@sc0BO*p?Xze8N4Z~r=U|=w&@jKlgFoUUK20H@=bMI1;<()r2 zI_7(-@@H;6M0e>VANFTnJX@g$9HAg{!jT0MMd>#Q7}?Fjv)l15kLtMrp1SHnsDuug zHWO)M$dF^&!?Aw$u4-kJ@!9`rZti2OprjIa^uIh-D{S*t5FG&y;3e+wMsG#YVZ$W{X`rez-)KVab8^xY`0W|G3|@qG7Y9t zFc_%P%@4gbTQ{|AJEh3UEH-lv2tu1edP z7Oeo(c#9I=P^vDVlge>~d74$VNwM(+dF5i0P&DS(7>oA^(AnO_V!^@?%~rk_W;!e! zM-Is!gLQQbbXiTk4-=jI&Q%cEta%!=i3N*rf$Txorx2GMT#1$^Fo7 zFV<$>B}TpREFU_FI^F!DktX_aqV-aI(*zdCR9b71pu}VhuqWpQBApjUo{~^Emh#}p zX}9pD*O4ShW@lCSYR}$k@B604*U9td)l_3Ihbd97OIt*J@ywcQESdjhD7?;8U-y~O zdqCmVaLW1AKVvZg!k4u89n}|!$^Eo3SIH~%b5qNerq`(9{?BUcHHLf?H|m-%Q%k&d zV|cgEK8hRkT)<@MAoo`oC3ynQuBOmy60WF+WWMM&<2gmO8-#G}&@zJ-q%k!Kd{A5=0#bFQUkM z1Q^I?fH4rW`Lo*Gwacd*w1-b=1EyK1W!#cnx8NG#nheQ@<wY6oGU;`kFFp{b3D2wV!VBKPOB4Z%nhH24v&~UHB=V^ytW4z*`|eMdu0-^OIB zCdQ29Qs}VR+THTfvN)j|UhqN_EifXxLwwVt+*d2o{Ft=yxPX#fz z>v2EDC7azt-GaL=+|2M9%2d$wM!uFL2)_Xs86s>N%GR&=q`<7D2;VX*6RG)#2`Kw4 z+RHuyxp;(4S!i#+F}mnyRO>B_cTdqAbeUznwkqHYqf+(MHa0Y$D%ksBID^l}+m{R& zOcOU;zDrn6QO*FVE=k|Z!JEy^&zRsC!G9qupDM-yN^~I$9bd3Hz8>@VrNA&x(6pfy z5bL+(EsX1RMR{AY3qQK#LJ7C zO{ePk94FJWCcSaQs!oi8PnU++rtpgK?i|HOSb&Fbzzk=@z+11D!Rq~=ty{cCr*prK z91Wn!>ge#ylgD*Fu;%@f;jLvrK>E`qWjV_)S7a$7x)6x-)t#S^WrpiMPy_|bYq>Qi zJG$vgBTCsbh4Ym5UmX2zStqpTGtxECGZGKwAn}-xw5hK8(zVYWYUiZ1)Sw@LvHuW_ zMG~<-E@B%lH*(`UdG5QsmRX(H{3+wI#-+)A*(=S9D%ffDHRt8~n7W;;GbEyW?RG12 zX}DKa=;5lmf2Qei<&Mn50#e3Us(_R7BfsGwg#pfl@?MoO{D9Sft9iaL(KA2LX^i6j zO^){o+s@@B4a%a;N5Nahr_qtS|aahy$QI8*da8W&Ib)g}>M~W7cA2Eih zhWa-7lsbayI^P;<2_Fi;9KLZl{(C>EWNw2>qX;}=8beG(drV?3 zf0pgoI(0hlgDyk-(4_EXMyKU2x2y{jYAGij3VTB!^mv8QBgmQ6IdZ~ex%P%<=I|1pIQ%idl>t~KcX^btQ(KWB){aM{zb~J4(2O3a(Dei;3N0-x05?)8L ztutSh()~4uZGU#6qFQ%dL_hBr(NDLksP1X?BH8#QBc6qpZCI`xh`W2*2?h(J*~EM| z)Z?mct=G;W-NV|+h|4aB=tiZj#}FCdS=Rz``P_h?BUJ7y-d}RLDWVLGc|iRdDFH)X zU)Hv;r`>`JkGxKs7*dbe%hJFHpS7LVSnfJLu6Xpi28&M zcSOM9my_hfjHcrnkaKeSkp01NkWW!!K0r*%WUGRbkyUhCjQxY~YDng7xo-%JBA6ii zha$LsG6B+&sI;?Z81`M`-u?YL{AR69igUkL!y50H_3`!o@!*B|Jk1U8S;XO_QtRtv zdun?B(=)BM0)BLd^h+J8=F8dZ2!yct%7L2oQm8CFx1E2|J*u=}e=!E)9|oVOl3#i^ zMhaycXJxa_MWF3HAfk@y4;E_oEkcCRGy(e{KQ0;DG|k1c@5il_veEXkyB~47vSEw1zuXN907{FPjl@*w4wo`%y5_eh zhv&`{1L~ol+3>+)7psVVETNf@#!QJ9+JiQ=ytz zXDe+|clfWeAs5P3l5XK`T3c-SPyynM$FGi%x{kv{wPh!BEFi4O4SfDdf1WGmXD&HVY(!FWT%K7?<*0Wfo zujHBxsRz^JeWZ`oMo!vXu@?}LGE)KjZ|@fJfSfQ+?q_ffQ@uwEK6v}|gUBP;{!ZJg za%B(Lb<(ik^uUB<(P-k#%h-I!Gg;qX`@5%+I~U)@a=QcNZDx`W_a@7)yPY~NSC4;m z@%Nn>WYzb(6(w=Yjz7`}=W{(Kcg+`nLjbOZv}mz|+(Is;WPv!U;g1B-|5JiYPZkTT zS0dG<8MDr3^YfqZ&X1f2T$HAmyB5wPBWZUMz*7s}3rreBGMA+Rky^e*@+nTUUJV?_ zQ`u?t(s1W)?Se=d0|Wh(O#5Q1;hEK__aPe+XlD10f;RHDer@*P8VwsxR8w-+M2CRs zV)@6@W8a^xNCF(frwW1Zp9ycIR6k`R#(6~q51v~%q{(&k-Dfkp?t>ofZHie$&RtA_ zs>b2R!h=5&INx$&c z(WMlcrbfnh9MN5EzujA%-3h=$g2%R=0Q1`^FfuXpmrRUj`Trg~dGI-T;R-v&b=561 z2GV^F=?%BF^ys4#e3SapzA2PLW-=ADoHoc0^-~v~&9ppP%4FrOR7y=!Q;f}@eZydT zOEY4j6dc;f6}qJRJ#2jE{w@>s?S5C=foZsa6EU<9UH^^1HjLG0_pZ!#ZYN+*6NLEcbKf5v%F{<0qm^Sb=j-&Og(US?ukg|7P ze(BhJY^-*z;M{7*p=_@ben^O?1$cG!60FMm$dzIp$n}o_@j7snbiNw$C3Eup_4D{{ z5AzP1=@VpxyJ^f7E_%*tTT=gsQCibU5K8?(X5so5WVyaM(`PC~aH*P-@`M}5T~5yCRKEf2 z;R!$B^BuexxXD6J6Z8lV{0h9|eG~q=sAw=54vHi&(%cbfVFIQ$HVkXqn&dKBxLA#G ztt8G8)GhO07dooF8fgr4(=_+9TL<>^hmywb#macA&ne#Tm`cT&lUV*I{XPh0?{#55K;%ItVOmyyI;mtITr)dhRoY_eLE;h` zwr%2HKYrhHElkN8(R9!KdK(rqbK?R)Oh$-CDhU1VL4yh3Dl!qv8yn8R%z}lFqwo({ zns>ObnKOKjs;0icTIOc5Gn#@(AQwg$FJnGwi2LQ6{La?az5!V&iy5ACv!D-TkHzab8~Bk(O5WF01&rX>hzbe>MfJtDynDj(mbv0cVd*)Jbr1{^m`-5 zU-7+G23HuulT9-x%$2pS!$ zI*^*RY~N9me(4aa@445|s4cfe`gwcvtUcfy;VEg53=tbEEb-kA^NgFl-Uj7Pea_xJ zmO%HxkjPinPEGwshGX~ez;77Ln8<1VKtCV<3a`+{yV1?p2ax6NiCV1yYEf`%Bd)D2 z*JJO;G6%Xu>*PbUGKU^;QSSaEM72$0V+4|aIcs7m`%*DFE@$qS%@er6ul|D6G~xka zG1?KOhruExp2*;`6R0&qI6rCT&&Xy?c*~tpS&{=Kye=cly;-SI9t+ zlYI3ZzH!@iLTYip=$3c&K92+abv|xS z`^#1#-7$w{{QkO4$F$0^NV(lexepj%uUP%B7%)$|crwLA4L!aEjy(F^6eDZl z-QD#*dxLyj*6(_Aw~;P=cW9!^dn^kAST3sG~Xby%r=3fP! z2uXgxrB0p-IBW4VNAh^cZc?Fz)W1#UJDLOwixHRKCJY0RQpi1(Sma=DeV*%8l`&Jh;|=So-6$&BcZM_E4&U!h&18Z!$wV(B&uQh4 zGv2178#x5szVp~-Ebz!dXgVjbE-dLtc2(K!9u0q42AOvgrBH1%p@-V8-yf{Y_O#5@ zWq>fqfc4ppvlh^m`Vt)9=;>pbZ33`A^>jd|n=)Hrij-b#dNrQVdG< zKb3M?ctS00Z`RxZLpLuj#Pt32GWapI3xq$xKz3rvq~%Ze<5##5ev6B@uU?F39bOIj zB2H#3aZvFX4>+N_h*rM#>@Pwnn$3b zhkbc!!!jS|D=oj|%s@+<8(`jkUknH^BoB}!O9 z&Nl%qY~bf2O8C}@$w59<*8ng(5^KMX*Q#=!%>LN6nHdQK*_~hh6qmsxZ+L`JA9EOe zs*TBH$T2MgjAil1c0MD-Q)ViWHx4WcRKTG7IDckViwfBli=o@ANKs;C=`KsMGuQ}YjX8eBO>y0YF@s6ZJ$@yr1*Mp zf4bUs%$wbI^L1WXzQj>^lWI|4cwSNN^M?`pd38lBrQP3$fGt7;R62})wH*TTKRG}; zQ4D&h6`LgPa}f6`KcVKh?GMYIY zaD``TX9Wog|OkuByA3yz&r0gu4v=BqqK4CkQCVIL-gv1Nn$z*HR0C@$SuQszF4H zw(8BX3y?M)GmZ=;Q26p@)!7cC1-JpoyzUMUN!Lv{JaB;TPxk2}|L6VB==mmvjSaZZ ze&9-$$}ir@iAm+{q$ZZ45z#=}K}t z&5b_$?p$IXE5yGPb~e0R_NyLc(yRf14HziBQNtC4VWy$O11v$;H>ygn;F^eUzrOsL ze#&i5QIEB`HmH`3duDzM($R$N-a9Yw3@uC^E9lWp07EMj6{iBAwIaYaUQbHNrv_}k zXT{`~$?X))hbJ?1jD7P{YL^UOYP%Zm)s+!;_c~Joi>r?vTvOvxErijOY{0_leosw^ zx|7THE-va%?lD*Gb5)LxdkNxW*}S!@Z1*Hz+)SS{DQJ+BM^cGt1(-2&xw$6UpU}W( z3h_cc7P)h_wEl-{ckpg$uJ&iopHn2g-$$cNH}kf}E1fgxY~Nwwa8Upgrsk!^fWL4c z&nm_{K-EkUTtk%qE99>UlRs{{u1J@NOA9kC@XKQBK2lo>as(szC4n@&IT3m84cOIV zZ-8uo(QV~Gflt5`nNsKoDS(H+FKbvda)!WJ_OhU9d;l&B4{j% zk!%cF?qvLl-;)CmOr_pU0OZAi>+p9q_fWL35op=QL)k-R4tz`4{nsv&=p$@0eJ zufr@cdF_9o@Qjnd2-%d6@i8M{4+Hj7N>`g4aOoZbn|w5Utp?cS!WdFa6aNPXnC3|$ zWacIM8iHC@4pLmE-w4Yt+38#-WoHzM*^m*w)c_{qAkudVP&E#Csb{bsH{lnivUK!7 zR)y)g{>umFVkIB9{RnzuZ|WLzqWuns?(L+0U(>Y9ny-v^Mb8^F9d2_>(@T0I%)`}y z?WekZC9RX-^W@fkw3>>4rYm|>t?7u`JjP@3(@i)Z%r88KMLJE(pu=MBb7qzK787_j zKPutHgz{RtJCdD%<$N!ErIa^x3|eKwj|T>Su~7oTJb*;u7rkKsi68NF4#gBclJ2Ar zjx0!rb{Y^7!hK)R(-8yI>VN*d^2X@!JB6V60bYvt;9%*cXZ-46bS&iJ;#{K)%Aa1f zPD%aPrrAfk*ep5uZW_6Bt?Txv?t872>7wB#qA9%>y~ujAxaJU_xd_^pZFqHzI&6s) zHCL+iWwq3+8hWZT`ps$X;vEp$6pJuwyqj&{xbA&574<%{7W76o6WtkE zu;k7PcnK7Y@IZGw7lZ4xUzqXPgS_-rH8U!*7)9)Z4(LTyB~reXGIZ081g^DxVA*nc}UlrauShVa?Z_MSYKprK?meXQ-GZth;P7};Fo z6mU^t8?((XqDjdJ&{GZKSApJ8CFm(VeWErj-;}QGeRM!rExB%+Rd%XenL>Z0i0;+dy1R& zsQrb9$8D|h_}jT?BiPHMQa{8tWIKaQ_1GVGXxhU_I|x;K>{D388QEPEz}{+-Z(KR4W7AdH8!Go~_uCR@}45&OG1{cp%&e^T?&0iHra53c zE|r0X07YTUkD=8#;O>HK+y+w=P`c4%SM)&M_^(>M`Hez5s-Ds zEpW0t;q=)yRt$A*y*$x!gj6Sa|DZ=yD~R%YsmQVqi33=?ktUgdo-I`6p`K_I}Qq3>#%_-M|C)Qd;{Ez6Ak0_rh&}nuQz>`|^8z&0<1i znn$hU6oV)lf&HbsYc@9TM#1W5u;oT_zne%c+;Y(zCHuPMfLib(eQX~t>Mpag3VENw zy$}~J^i0t6VjOzpakkDZUgh_NIuWk>W2j|r+QB#r{6CdxkUAj%v2fFx1ze?@ZaP1s zuUj98%Wr#2b-hQx{%F(634cUo=o4t+>{HEe#p$Ml7w2btWKuksWI*|$68KdRkIzQ( z(d7i$Wo=4=EUXKFJ{f14%-nfQEII^83J$c5j34%AokpQA^SYD9DyvCmw^a8n7v>q` zoczvu>pZAtK_f#hehdMpwSo@I!W2&QNwxga)&|xd8?Up9`&74}-A>ZhSEh_f?&8z= z@-8FqKQvj4cFWku%u>Ey4#f{p3pm#Gc^O~cq=FxnVHdrm0VSr593)}yOq*NR-CnS5 zBsl6+cw7+s3*D@>1}&ncWNdT^cC|xjzE*#JRLmYM$YD1Iy*f=x)AirL19NfM5D>oA z1eU_}Mc++ka^;{zo2PFzL*e#4guP-Q@=eQwfg6I}N50}sT_odnVRVmblXw6ji)M)hSfg)-uZM@bbd;{6>{#ilEKph2kds5I|6xa`_!( z0mF^_Q2zGc;KO>D3c0h@6-idfboLR zFlozx6pkyGg?j(IEu+g!;%2Lls35m5=&+SJhi|BsRfpkA-#%ZH+U-2qnP*c08~aB_ zK6Ug9bql^Qk!S2L-J_&6rTsIy)oJgr77WJ&IIK;-s94SZJmMPu9tK(F3n?oFN#-l+7 zzwLIvU1!I#)8z&jHCql@x#O?Ni^1o<4-NFC&P`x`$5im9D7Ki(dQ<;tKgReWX`k6C z)RnxC*!*(oETg>fW;3Stj+*>&v)dO3P~Fc9L3$?Wj(5fAZ3nOO7vgpHo8r>&nh`c= zSw)9r1{s}zf>eFWeyS^4NDhgZugI_t@Kjfg(CjZU*%nfu3-uy}13A0?y#mJSw5d!7 zG}OgvCw0}GbEVf#D;(XF_+>+kP+h0Re`rE;%UTpq;wWH^y7ChfENnOZ;*>S9{ zwECvx+}_D{sbKE`C#{2b0$Oyx292orPE0`0CIo5XHY;nSGD&K+dH=(yQbC-<>`l}f z16b3JGLZ@W%Z9Y34mkFTXin#0v%^cxP8-hDqhjv3;q~?Oar50oLtIb+zy;t_j2UJL z48(*g^gtaQBVIa_hEMKb>uKf*vpDpEy{@-5a7@?X=ZX=K(0x&7x?Srym)b_{3K~LS z=~B%<#QhOD_6#Vsbee8B(OSD`F*nHHRVoS*o`F#rqyX}~)?EO&S0p%^SS!SSt~-Lm zzR=pM+Oal5o*H*{!a|W-D-Mbk z9l!(6qYFSU>kXo*5=5%=h)mRD-CsFj%1CK|LOmKDPr%zxp>Pfswl%)Jraakl)|@U; zGZl?b?b(ZGTj|I5*uB$VJN@KFQ*zxK`zxD~3^bxa(Y^fT>ow~%ceJDXb=rcj5m1H8 zH>2zHGnd-kh}}O|O8HBRkM@LWth=_aFA#phnHMkaWV+AO!vj`6DZ<8S$pEa`1IW$} zIjbELq=TX*R-h*<)XToC$V}XJ`&f6^DbeY(BW}^Ru#JwaD%j|6H4gqk$%gKh*%Nzy z`BY8krVirU6J{xiPOnaOm1Pn4Y{QB;I%ZI z!T7Ou)vUEjUJ7JKOl_Ec#%q5dPO!l?*#@Gx=m}bfS^!Kh=pz>SDuQjFkpe5NE7N~H z2sOQ!<`EK``6{$o`%i7joDdH2PxLTz&3!L7cUs; zNC0ondFJ>2z$1;8l;nNqncSiC{LFdXWKTz0$@Bd^v5;-uwhI59-mKaA&EJ{=3Yy7M zN37@mOCbTw;u(^&Qz<8a?=cvIo=;7sDHK3M9LFZdCzVUROfAi3kCASPDa-6)Vp^gO zGc4U&=>tz|JC9XjDGL^F0AcM5xiujW25++7sW8bwf=n;YVjYF!ec31hgBz z1X+mY*BPByeO>T&=jqce&2$N?>Yd-C$f4YpK~e9pp;dRg{+W{zO^=v{PJC4hQ%X8n zmg4IR0+{Dj3uAnlP1@iM@J!k^Jyh(u-%|l)dsJDv#}GBIAIx2K+Eg-)2=4Ii!IILe zS8;dm*;m-$)GgoP;^a(d)-4!p)73Fn9ZABo5Dk+10hD10n%$rSV#E8`96wbZ3RXzd04(pc!yx5q=)b$!Eu_OgqXmIYe-@x4K-B&rt=xhns z8dLZ46Vc;RkhPQDZ>I?PRH1qW#FC}e4-$_~*>e8$#UWH&es|+?BS-Ga_)Ut2s5lfd zTES5rmuWZKbZIKhYpRCGFYDD8Yh;wi49if|?eqn&p|w4Y^}2i+*9ePP_x_SN!LLgD z(nB(y)1D}Jc1wbuUhhsa+V$thqxAc^s6qUhT6+#7BtD^$&31DgvN5A^`u&14YyUuY z!TvhR#}qMHGAue}8nZp0XP?XmZ}AaBO_mnBZqB@DN?UUnoRtrB>;L603aKu#WIg+@NyoGyo{}Tvm0T3$3%`vee?eZoz|owJcw8M>77EV$i~9^qCi;uG?z2q1wM+dn8Q-5ryaaBNWa z(G+&ikuQ`BW(~>5YR2Zh6%Cbr&em?DGNp*!-;7#${7X z?9f^hqe28pX#d474jJ~T4l*8FJz0;|$Z7j}xODZSXt7h<=&}GYySfd#UZ)qEYCcht zEU7AF0MGbn__U%d%TaE1Q*-jdZx*UC`6wWFUS|!M5rmz=aqXc8DH`xg)tmP4DHcWE zvUyYKX7E3uy>aFoz`8E1KDU&b1ahn^@VGyrq$@x3g7Gxc%45rJ%63@^aL)Xi+!A1X zQ6$V}RfiQ@(%L`Qg&9S~SbGG;SbzFdJx_8FpR+R+ToAsO%Vr5{iXx?Varm0wo{H~4 zQ*(%#S35gIvtFJbO71vmrVk``C`E_+6E*C7lNX2PA2hET0X6I?0BqBrF72a;6@(vz z3>M~S?yCdI1V}BoPq^3lzbQeF+)OrQRp8KoyqIke2@ra$WCR3>kn5v>jQXSL`DjQD zOB5t$a)DRq@VUOelcG|>%@I8+DPaD-BqUHx0jXEK3!{DKh|_5^rSfy&w2 z62(8){;NQhcI+JabEs4_9bQ_8$)9f<%fi;PhgD(e?|=8svuYgMHeJ~X2*m47kMJES zKE!-fv?T=BD0w${5#j9b*?wwk1o|g}~^has~B42$J zohcDxT*X*O3?K3+nMtcuirI$OYe7&`1u+Nc+1X~%VI(MeGk|eOv_`)A`Wy54&bM|2 zcNtMz`e6X)GXmn}fwO8403p07OqGkW3%fTg3!Y7spi1@6E=9-wg4NG5XJx>SlNvpw z?UXzk3OIJ*qDN<9A+TsszN=~!bA3M_jg(W7y7B$AsxDLZ`Eno>GHG@@2XLhfsyx7F zQNW?mar8Q$P>esZ?-4;2(KEehjoWg~jDbHVDw0v@xD% z3$fL{I31~r0<2BMubsn-AA>MeQb%KZh`TeoBLFZ`o#$tdUkCS>s)1_D&!Zcj+I-5+ zP4UeA@+!Lp?vy3cN18F`a*|Lo=l8N|*0%R@|A$Jn*MjpSE&UzwxTG=Jiz_wo^zf;B zj`Yu(shJN;$mqO|(7uXng(0r8_L-oN(7`r^D#*2ba4qz$VW8X@V9VjQgPG)VpS`ec zuPVJf0y=$1XB*ahUUPuXOk35(+9DIeP`d=d+8O(|^J|aqY+}PcS zx;@vOW@t8C+En#KxYKnQJK2ygac69_V&vD(0+)$XnuxK4O?|cW$V}=|dhHLpv1}=$ zYB4{LTYCzzNrqWQHkx(JAq3OU9Zw!nl#o#S4qe!HM`y(jn$-6ul}c_6lH93p_W|DQ z$pApv4Tot#9Kr_%a!Swb(hL|Sa&qFq5u%57j(;=|22pu2Ec;3+?eSQtup4oq;beYP z%FZOQ3fLam>{wi`;iC&GH-w+49qMhF)T{U$f42hA!+|KRKd8NxGLxx%D%2ZYHPh4M zFP;0j=85LLWXXuJqpfZx-rbejb}?tU0NN68xd^&)vQmM-MBT@8WA3%6-fUfnWC;86 zEQuBqk>}nnKiQ!0m?d>a3rfT_=Bbt56w_Xzx+_vZ*f()@TzyYyUlwIG< zE9cv73VWVFWbBj7#CtcHo&)pp)>9=Q>^F3qA0o!37xGR}&k)r9VJfINGess+R$7{< zVN%yub+4FBOpM=<19(ed5ei`TSq9{x0A{ap&(6s+cZ_1-=+@YR#bL`2iQGpVB_~V(No4ln#kE*Nvkb>t+P z%kVDbsoACo+2;?WNGnLVZCJ$!%C^brml(5diaI3~6}^{4oE_YK%!B944ZK@DTeS3z zoG>F0mYgi4?f)e^_HaM63r8S>pGP$G6Uo59rj=AG4FmP&J$;Va+I)jgNBG5LZ5Az^ z2NZ`bJ?iBGvN8bHUa3zL9mZ7J9&GR@yMj#)6etF&zV2e)pqDGq%HSbF4#u_mdCzL; z>*@8)9MW2^Ziwg@>dl3hY6GIC2fQVXdEKxX`0rAWGO$3`V~gCCVulnQEc|t1pP;_m z*TcF*Gw>g^-KH{>j$v)U?Bg17faqU(Kt>y z0Mq*sNdq2MrR}qyEKO#Ev~gRnqS`E9f3Ooz`~diW&q}_F&nw^Re8NxRk9yv7*4UQ* zDz@@=TvJ(;m9;o_$`PKLe@sO_lF)wqyjYvbCPy$sl7~crHN;Jd{g{Vz%9>??l6bz!A;t*cQ>Jil45<*MaZf=Q zk?g+}IlxhKCqy3LL;pXr-ZChzXlWM)0%QomgS)%CdvFNu?!i4UxLa_7L-61bEVu=C zcXxNUZea`!tr=@)e70o*X*SEWqdD(vir-!ukUkR!Df0U36dV}eeH1$&6 zifAQ+qkUo5GF|SDnD%ODl#%hc6}n{n9?tbyD^*tY%?~}O<4s-{Kn)BQz&5b(dO@OV z=>!H8gW)jR6niX%dx-55%y<(w&`v@6CqzSVZRzfvM=?^z_+|lBjT)ns_A2n^u_6Fl zg!->sX93(qoNph+KZ7wrSqYv*q^6~pTSa93Q&=1)!rkDm2^-z+(=@|9xigwV4`1;| z*3t2I{>(>J&5Ie{iv`=?9;&9&)C|x2v)J5=UUU7J z&Kx5jLN19Ap|?!TgfCvK?jKR6jN8K}CqMR&UXekjuF}tWk_}*A_N$`_216Xj6!Hh_ zPNrj+f|jl$tH+h*a-yY%6y7Rmom(rC!G2y$}@HYMapQ_=TB@r?e&p*;= zBR90xrwMb-w*U71Adl|xptZ9URqXb!8 zN`a^<%Ea5zB5!-zN}87fu{s26243e_LSb=fX}=mvM;^MlWAXce(4ga&JPA)HK=#`k z%Y^Pz?t2Zi=|K``J~+U@{7tA5fwsiXHShf=B}^LRAa~Ma!m?}i5X8&o?ViIt-6mHh zEiH=C=Chom`KF3%+zm7kv<~1ctI_waU?%~47IwCL={vv8quC1A&xRZ^jBhq@V0D>d z5-BhRAzPp8r)F(o{A@2l`EhbR#x=v;HCTKG$%_nn@aVd01;rkyrShP@fGH#|^)u|n z{;h%@^eK}eCZMSkKPG*l>N7yps3Yn)5c7L8@!6R`j8|KtR;owK*!J+*hnT+tv5ot`-WBedzDZ8m}Z z<}JIhKDfuKw)di(1p!5IeHGF8_rftVWbp9+Jl+%CPam`#?;*aNQG@ywQxtnNM-pa0%!CamR*E5A| zXc=uNg_I8C$23w_jVL8^Nh^05FGz=E;+2bTgN<7@^#U2M1r{9YEG^ zjAbH#yw#QnkRw+c*ZcmR?-5e_g1gA0#X99(D#Yo{(tA=Gw?pY78fwtAyXl5Wfov+3 z+p0r^Mdgn)H)-$NE#;+YRy6bufk_7BJfgCE2w6(_YQyAUlZUJkT(#E)#Mn}#QD;wYY_@%`)Rzv%`KO}*Gq*zg@}ToKowWO^Jb5dd>51Qg>RE_nd9iFu2?%0EdF zK+9+JCFVXNfvK?5NnpU7gDLSL{!Z-zf)fA&?hhgSqYfYhGE-C2i>6gUdWk54%X>wq zZy=p?p+^6jo-QKxt*@=`lP7V9;nYQ)n{lvWKfP!2qJe}dPEC0dhvYojc5P9Tw#31NBsN12dp@x9+H{q+vUsy^z?7tM4=fS8ij6=M;_JR~sRWTF z6pwxuFSJwJOy%tJ%JYI|p`oU$E0{O?s)i8Ez8hzfpG;u0pb+qe{sKt>{}NOaCl1S1kU?cGTp7^jTbDMHD@21_Q_>d6YEzse}per z4#&Xl@qw%CX&0}aCI}3#JJg>KZ;lsbLZX0FO65bQk$iO3gX6=!34d`(Nq*;2?Vp_A zN;JcQUNf(&PAhI%KB8Vi7>AH%T`VmTCSH=RKQayai$Bx_09$J!3s7!)_JWA$oo+#y4Vg?&?#$K81o0k@zp7fw+MqxhQK`VEl8G-vU5!6lkV>66x}*kELljg{aV%K96l`$gC0;7ahZRv) zQdA_hL(JYp?_XnPsqs&#>`n z&){L<=81(k3EVKrJJd2nUDDMRa782uuVmv;`lcg3|2X0BZ=CQ1kvB~W{R05-Gd&28 zOUM>DzhF*9{GB3E%-X^v)}?WL$9)#uzA3G3}zJn=9 zbT>=LQQUqSs;Vv~qKf`Cc{;(?Z}X`_(*XxyrwYVg!(mGQY#Yj38`KGWJHPpYOhqdL zt$GFg5FFq&TuQT!1e(0}j6)C+;#Yg$F(VAgQWc!q7?@?ov%gP9)OGf!Gf&P%`?jBV zCvV3{`BeNX62ULB%qp3%G@rX2N|_s*=Zk;M$Bt@kK#D|b0FZ1^C3@?4lKvO8i|GKJ zM|X_A+P2MlJ9<2mH%1;8Mdqfx<;&E9mTsUQSho4B&?W4mn8(Y6X~}y67~bqd_okwZ z<~g1j?}nZxc|#J@q^{uFmAw1EEkFvVQc`^Q_q$}k1PwU|%N=@QEmkJFH|iP?gVPIj zb(W!w%<|M+zBHZ2NTKycz{<2e9LGEEoyAfps0}Wxe|PG@s%{msy{jZJ9 zgm3qf=)1G;eYkI9TTA5y|G3&4*Zq2Uu+{DtU__x1KbLn;@u>ul3n@0@Lw$ zKHBCY(~u}gP17f-&v_Y+g_?5c^8^V%io-B-eVcRz6z_o}LPP#Pk4WDW%+D^O3|`(I z4`=o(h{>>v440ev>36cHAj`otsdE=ymJ^Vsxkz2{!B<=lZa3c=NDZ$)+nFB)XV7FR zdn*VDEJGA}cHZSuYV1^$FcClk-Qre>PH(!X^wwXS#{55p*Bzt}furNX7Qe!awzk+L zn)-7Ph{NGdhui+ToDdjr{-;}S_OS(+H)2_VImoHRr zXe%KpsW(Lafa4p{nmUkeXq)-i3lt+kciR8V0P+9*j$*Zj+5CSTWfd5X$ET;5BpDBD zC^cCKaBR6RJ?4pqrmJNF%I0GF=C*FDe$uT+#kfXQ(u|^Q+`f6o>od^_AfTWB<6gpd z`IHs!fMfm6F9Dz^=BFnEHDU;;>`$Rz!S%I?QZX}H%mZ&cK9HCakp)5oP~KaNkm;%j z1_Ii!Q{yfo;|`6C4fQIEDT2ih@QIDHHG}r-2b=|A z5%(Cg9_~czIG5lVTS=^D?PPC>D+QsofcXzIUs(j+o_tyW^uU?qh_FvC4Ajdoa`!R36SV2N8xIN z5MH?V(ujC__s+wGII1(E;unVvee*oddqNkS6^6jIL>5QFc5b@-i8e(7*Ea4=*>$Ncm~(}7x5RbAP| z6kYYws?sI_ez#=bQ#JowSyLFD97aVkSz;T8TSZq9!!>Pu#8M>nDc5x1%F?;3jC1l# zF;@qYkF?&`m4IKocf_p8s5O}k5tSU-dQH=89 zvb20&fznPaOR}vqOZcRD;-5cHG}G=*cBa|o2|Pc{rsip{Y+)u*2_JuX;4W^pU!kAu z;S+{{79z@nt^rYG8j#pyZ~Qpb$gq+?L3z@9xeH|MvMOz{Fp);CHiq22e_g~J(f@gQ zo62g%gN}|4^b+1ciCFUgKDE`N2xQ|t#@P7)1w3vTt*?Km zAYLNsJ-Hi4xy6EN&s||2XH+At zMXC*3KpTaS#|R8ux`=8aD0UA$e8blA#aQ$anR$2f`8&wiCK&z0=2T_wiqAiyp_IC= zu6gFd5D$;&y4`AAtoF^Gw#Gl)9_C&Eac-ui1<@KA6!JuR4Q?|0n;O=9_YJk!x9nZu z2<O_(BIiutv=g{xQwAY2O2f-H|I}xG&HA_2u_^81_v`4^)Ocgh=Y78|d=g zn=#vg`(*DjlKUQ!b9KC%f8=;s($sxdr`|v2gJs*pF3eZTuW1`nkO=6C9uq=0xFp)B9ugk7v#D;Z^yWX9E`8;D8bm>oQW z&m)Xkvq>0jb529Y`5B9y3`-|LF&MVIUspYX5vB4gmb@cSJF~n`UyPB zk;mgXSb|&Nsy+%>{6%(H^PLpd`&SH{rM}Oax0d}Rf}ei&yUfbNJ!-ACQQTJ)E(p$o zvCmNS2tl9LWgLUTHj^?)G|KEHRqv}P@FqZRTdSUWe;Hk$l-$Fd$tAm-B1a!ZNEbt) z>jQjAAczqN0}DWsp@k~vM-vUK^x6%nKgu+gRorym`T3&y#$bGD#=?7B8kGFn)VT8i zPa5{wF4sC_P+_#vN>z(|a`-lPpseKMyq&k)CZ)n}K1EJ9S-~Wk2+m`NOH?MeB;>Ib zgU{@JsatobCsearo?_5#1BA+ZxgbND*j9uU1MkxckNz{O=GKD``Xs*Cohcw=l6Wa3 zHe`DYz`>0yAW@E(jkQBM-)8755oeCRJdSy&bb`z0>tSoS_l9IA6Oi6A0a3B3oq?u#u!3Q-D_4@Jxy>>mLw zhwqX@Xpbw`w`Z68V?k$Xl9_9s=_BPn2)o9Ng$kWY20>gV#rFqT83a@mrM*F~9u2L7 z`by=DNEy{oZltc278opf0-q9dGr()7Brb4^3M#^2GQ2zSYHP{c2 z2@vI@j3B~RBOd3?B_Zj){ZEc=y1*hneV$wO4138g(IHCzeStXQ)dDk&4(D%q7k3vy z{4~Tvm>iZEomb2k{_`~`Sg_DgVu0HCwg>N5)-Qd-|BlTb7e&A;%-C`>%A`yFV_W6T zhc>b%W4`%N4bn>EWeh9)t~~XJ1@Uq%xWF1B8_d9(9^qNk&cDR6VLD216QHoE_1GP6 zKgp;Hw3Wjr0}^W~c_wtkexqbhVuMhy-D=wIUoij?-@>=xXkMj5>dKn#+|Tz#=0$l^xKaU&9}(ZxqyR35gY+-No6$yA0v<0C-Zmcs{wz5-Jdoqn z7>(1Mi3wRX}0kDh?V|;mq#@!KKDpLcNsdo7%q4Flkrc+K3& zIREyX2-%vrOd?4GXQm0)6f<$+MVTAJ%)$;c&{b;-yA;n-0+HaSkH9NlVp5`F8|1sa ztt#W<)Qx7V@_cS}JyVA|n^O!);$gfCD(+4a5)u`Syj6Hv@@~%N4(D#kbApKIi0mM= zkfQFEYD30EwVGxcNnJZ8IG+R)KP7ZWAtUuv0V4=O$~rxY-^SSUSNk(w3CbEvu73y! z4Lhc)*jO4kZ3N@wWjIc+xe(|Gp`j!IZCaZPzU+g8JHI-6xBA70v+ZHDe$Rd()?SZc zW(WE0-F~Aa!~Vl$aYB`WHHKb|6E)dhT%D!(iIoIn%#8ukmd;x`0`!X+D+BZOPaGgi zj1>O+sjOeCV}_r`vje($wN~gkdDC8=F0*J93MITRSPwE2#7yzj&bN%)e)>1_H6CYz zEr;@?=n4OzyRnhyr35kI6BN;iKfo|ybo>p7^4V%s)Qu~VdWh0y#&?maAE~M_c>3b< z)RUT_qM@ZmOQ*CAdl_cLL)^N~Y_6s6Mr@Ssh%fP2lB*Uc$@V+mF=sG^&bEp z(HC)`%Ufn~p%Qmcng2nGU2|<=_5}lpc$j2I|LN}ir{S<~k4S`4_?w&bE7QMi+n%!s zzZiN8$YnAIV0iBjzNFRLXehjTU!$Y1+&}9-r}Fet-c`UHtR1sAJ-K%b=^4h6mzI^) zsn5ZX;~jjFJjO4G--;+q#>?6zdkE9zot$N86XSoWAT0kPqNTk{avO~|mR6p|qJ}^| zy4cq_u7}~yqRAw4un=SxDV?9~6*qO=yn*WBI!@z)H_}GX_@WdZ5uT$8p0pS~>8fKu z7fCJSV#WfoNdrogYhj;_4Hfr!-S6=vJ1o{=lZiJ&TP&iE;F{50>8k>cAd?jOGT6L}cz~ASRv&%}GLS98L|ihSB2zuA z|J|?I_D|ZEKkx6t3RU7rw;QJ8i@G z6%bv=!H}68#8mXDsO0n4@xeaK9kf0%Xe-gE$`f54YGV5OUt(ce2ym8)N8}ocrh)D^ zp{HW!_?uMxlcDi5yN8Y}tCwX~X1{M$)ARUq-PG)IYbLK%kH8h_@?m_KmUd+e(h?)- z%DoRsAX^8;Sej2evaSS)3F>lTUtJT?_gmnGle;VEjm6 z=X$?f?_?c$KzllP=j1{|tDtYh-u7;}%>bhth-?80q{VP1o1p$OH3LsLkJGQRZ+Myg zBeR9Lo{6pFvG~85e@hR;iD(5R+oM8TQvzY9YhET!rCrv_)iAhCdiv@1PCx6J*VJ_O zwP`?EsB-RqVIQI~5v{Kk(5buwW0DxBT+;iR;94B3R$QaC{iC>6o@jZ9f*n!>c0)@Eo7?ksy+C@R2RX+OZAR!PncnZ+om$> zUGw)rEi}>Pu}{I?9LaMIZ+Vy2c~xyf*zj6MrVM0$ot4Kf6QjKJdUO}aa(rQ=|22%o zpKKN>n?K2YuQEikXn<%l)#^2^(`+z(!UllPKGDgz)`yhIIjfVnb?Q(1o8-Gr;o+A3 zKc1cWNM+oVN#Qh=Wqnfso~{R+CcyfhCD zTvy^V8r^1;?IB67-XTzD%(`usp7XmCDqP_}oc{qSPeAl@@gC!)>;QMZ^1=>#0{DRp zeb-#sI;nh$*M$oKi`9?B*vR5Goct;BgERqqX5-C?d26EMX!@49U2d{G9GmsQkk+jK zHN}|7f=fKC;^yyU{!w{-DX-bbT~EtcmHsFiM#fd;)5c{=qC8D9Ep^HG#RZ2w z(Tg*bgqW$x4XW>MkCUU`((}74)D#R+-dA^o2QE`0X*$T+^kb@gX#=rpc8(lb$$}2h za*}ekjwvsgVs zJzgJv%OQA#+}o8qF$Id(;A#d=`fI>}UBh-&#hPx4cjud-Jnko54!$A62PkvDPiqK! zpEW?f%X>dCaXrvfLhiLaLrWQ*6QLCOni8%-P7vUMsOtH&-l*%mwxxNU0N&9T;Ya%_ z#^f?_E3?Dcx#(Y%TNGf2;3(zT#eaML^#FN1^JM2S*UKGB974sgt@Tly%=7y4`aqX& zS3SOUV|qp-AZ7*&JN-Q*7=TRGA-PEsVPR1Pz|<$XaO1@-K|*g??RwIR{3JmnKONq{ z8lj2qIlxx>k=TD5lq08 z9msO{%kj_(Th)=v&9U9eqJ;v=#DZ4nTGgpn(txxyRkpU9$5m4FG)k-s9PhB^7THKe0iX*m{$J%Mwy;3CXb*21L0G0jH@2R0||8nocv63s7%WD9!VCInOhi1J`QmKDMh@OqFfdv>{~^sE-Yo&!Fu zq!7ZON*KT$^i;{`$Uvx*24_Jm7ks=xnWDtdn7q+QcBa5*^K?c(z#Cs4Sb;LRqx4?h zO*y%1W1;u8AUsY4$F)CyU{MyJ``ig8xR88ryv7#-XxK8bOPsq$)C+Z6g3_M2KHJ|1 z!pskQPh&!@lUCf@+CWCC;^bcE7x63~<=U>TrkIH$!X2vV$uGAnkP04H_J>^LnXTi*|;QhAU*A};jG*^BP%81GDWpaOi z+tSIpY{#9RpX>g@R3AK=rVVR!W9yy7z_zJRby z{Yi<-sheG+Y>=jO=&p~34hy_x1^u#6Ay;&&ZS)dT()6|Df-70Z4|^^PnFl@Q*q{y- zQne?!o90QQ%t(H#p)aW%B;x!#c7zoq=T|cO^8qv(caMXQgU=f|&fk)EiB^nD=4I^I zF)@G9=7kyDyxOK0_DGu>US2bD{4#!)sc_SO(Dd+GMtoQqPI8L$0P}RDzxJoQ#4lN| zHoF#Fd<%#vC|W~@h7tt;m%$$ohbiz$bAS>o#bg~m?|uuCzzqphDR=vuHeoRZ1LXk_ z2(mhcfX0~dAj5qf8RT*db@hCK zv{c}F9TpY<)x@|m?h3^}E#;%DUPY_cz8=%dw0Ist;3Qj!>Cvx(;}A3YYZC!yM>z8G z{7~FX*cFUepb^DwTblU8VZ!z1Q#DC(Z9Z~`0-<+IF*lNi(&@_8ShTm29S<-ol2EI` zB#h_vEZRppti@yc(0DiO3!G(~kCoV~9+{r@C=j4H$rx4?E}F@y6druA)Jz8-o<__j zH%+=}+{H5et*O?$x*4FSfmRU_&bJ&baYy?+w$k{HoRciPjFx2e#O)1teBy4# zM=I`>p)zw3^TY_*5h=gG!5*Ys+aqDhOe@CfJ&pP>je-c)DfEd4$CC!$UF^>6Z}<4z z%JFV;J>#l!YYbIaKdE{{z9cckIS*JC}YZ| zAmjV#ba{zDMoW@b(|p4G3>m>Ic&h{d(^+>{UoL%Bxnpi5SMUg{m&GOyPoo!qN>=^m zB@*>!pD+&l4aOAruj zf5oa3C3$r+M(9kc2z1-yDxs3F9zlq!>*m;q{&d>R`&W+uj&hwM$K2(no0?&sGh{H!+>rq-7U#0X@;zNyxYwNkUEfHGz3j&p57 zb0$M>ehbybc_0x88}I0qg;<=`QgKGiv_6M_I86udzSF_0Ozq;yQu1PaKB(s=V{7bq z^mkwZkeRx*K+MuR}r;GUW*hmRw-j~(#3>^B;V`{K2L2TF+;rQ9b-vp-VzNx9I zR~aWXKdf9j!0i4V9O9E$bUP_vHD_Jm3F26`)3z`_)#JB(`oo-%kSvMM+v7k`gB8B1 zV}UIK|)JZWB~%vc*;L25a|Bo4cy4dvFII-zv`#RjSFeGYcJm{JXFn`LiyUkI8>ra!>>a~n_@K;sL1uGAu_jf~_nQq;8I7_vMm41@+ z5$>Cg;GS3WmfJgQpFcZAN1h(v;c=7GD&w}k7jkc@IF?SMPry1Pj%%CCf2j`*StT%= z{xZlwrKT!SyVmg1&a5?}DnEQY;?B2w!rqyEj}rw{4v*fdc>+JM`iahn!1?4id-7TI zy7DD6GcRE1NTHwffSIigA~=Bo%q+TJPhibEEA_GSZ+N5h)?NrO&N&5 zbdhPk_v3*jwicy8V{D_Feqm>6HQV|@TG8*)1Xr)BUmZ};FS!2B$QHz94aMoR`svbP z8JkdQwbjJL!!!$U#AH{6x>zXcJmIO~J*k9PFRpV^}{RV1GWRo6@vAZFxaj z`0e`rf-Sx{-DPpr`;}K(&?6!4JwlG1=PlTUaq*?Ke9rjs9S*iV0XResxRlTmHR{{e z5VwzllgmJ3b_NgwJ8nM1n4u3s9_=@4^h-5JA1+_LhFV=yF0fEJcp7Ua zj%O9NS7$)eghF|%IO>rps$I?fSCx~RfyqgQM%C%19uu>I{5%c~QfB7iQL&k*b^3dcEx8lvG-GX`d}gR^={c z5cCfq)zE%%y|EXEu_!%8& z<7<)>RhIg%=qNA7b|GSvp-hm;&84tn*SL0l=J`f79A#PK0bEjVx%_yQy%GTXNNcH~ zX`|=L@%%z5sHA)Pc#_Lz5QD<;>-72Fji5j}sxT8g%+7XuV0FFk+Y&4-iQBgx!xNnn z2p3*S?%tI5VOykJWWIwkSQCAshALl}oy_F>e{()AMMfPq)0u2Mo(Fj7KN1w%{+6?y z=44N0z$-~k`e&f7VGJq3Jwyx)B<>~kUnUlG@oZ~gLX2Hn?A_a(OS0~MjmNV*bp#c% zQ3u;^UY$#y(HbCC7jmyIv0+S`ea9&+x0BiIgw?)Lnw59JyWr{6ce(tIuC2nZNS~L| zCFGK*M6GsqI=!eWh&`kOEwU>%={}Yh+Eu6%YRD_7kjh<%E5eJ8`UK_Y`xgB&)npRf z^&FOGN6h8Ej;)hkE#TU@r@~;^5x)7xs=tze_3a=XOO8=XPm{A+@z#_xIY7|QW(ebd zj_0ZLM#o=mh>cSU9v4s2mqE|Zuelg*D>+EtWYCx7SB~_l2wSV$$QmuWL@RF$o zW*%sG4WIprXP2|VGkL_@T3+n&K#1xe0619w#=jE?@dzCHM^d|dd+gnhCJp+VM$jla zkwo;Q(XDefPm7cCA6LONU~6?-n*l(7Q}`U-s*lW`&veOi&s!fmoRP9=wZHmxpS*D zwl+P=d53nPupXYApq>&tfPh$?08Hl4}K_shoXEj*V6cm?TQj4C0_ z?)9HaW5THnr9{0XTVD4Q5zkIBPA<2oBB@`5-}$w_Ns_BhkARzjA&TJshLbwjCYE!> zBk2a8YtIxu z`MmPAXL{@ju_lJ1q|s)9=>QeC`+kacKda>S5p$tXTcXkIiD(4dO<46Rf$ytpeWS>N zg7-ac6CujjIUaSMlt9hjm**m&&4Zy|OaH1$TC8~@)1;%+e|p!-t|@~dlUdn4oBz6` zmx_@x&9?E70Y`8fwWO=INS`W*?fj%xnv7+zYT@dsW`#I;d|O&f$*qHT*l1@ z^_O$h58pOzmuqKAZthTtC05l-0#1kXvfo+ofNg+`;7lW(|72ZFd`$v>$w6HaDeQRU zcu_4h^?o&D2HJzuwe)g9G(l-NT5>l9aPI_0dK_?J-Xh8k>SA+})`WTwvYxsEwp`b| z)##G+T!5koJ0~IEi6DM2aS`Wm@=p=IXUh9EX@Qlr#P4;E-~8)-Y`zak`USh5BtT zEs&~ed6VWKTJAJ*vi-P5BXETVO^vb$ANdp-0`!6i5W#5gt?L0r|1T(#i;bBR92ME? zley^}R`ZX^gf3U_yOkZFuAx*#>Zqy*@i(eLc`MvpWD~tMa z2z%Sl)vqO;gxhD!>&v@baYi`KGxn-xPprJ2elHO zl+s&Su1DjE{W%J1-f}Bd!I{(|YNsb~cof(&_uct4y{Un@uuW1gRRVlS_gP_q`2@xe zB~=vuTDyO+!q-P<8k(WneAVjPuHs)6Q(##3NeRrCxy^OlP0^(!OG2%`v%}3Mnwv7o z;J++r=mW_m4JdLNk$)Iffp=fhBxR! z{-emM$H6#4>q*a^zlKMwCO07udVroGx72^4rvSb35_y6yhaKKB?p+z+N$_^@%+GCa zT>vseD}Pty8)2+n7C`DLuu<=X4PKgMEPHCGoe!?C9~R*&pf^ykCP@Lcb~nkbk_A?* z4Pv7Rrbdy4Gu~iUBaI3BQoz@Hr=z_HBY#BN&`0KY!dECX(MyW~9^}OrN$pmM16iV= zb|$4tFN1Guza@d2ge9F$R}6Om??pre{O-CFvIP|W9D~PQTdVN7ZsS-8A!D|jcI3dg zpEpAfk{}T5b=oOZkpQQr2QIX)TV78(O{*JUltK=f0}Ru z+1ySE&48#A0(jOLHVF3r6u7rN3(&82+g^qh^H&0@y!pBa-XhQSP{lVcg~Cr_l%Z2N ziUX|IDa1sRj-g$A3=5!?-c{Vt*8!7tW(qQ%39PJ(1CpR>{(dcjCf%?r`VW={>N}O= z#ChD-qD=U2^0y!c6IPR+H4R^WVQu^W*GT5U?_M@QqxX!JvLZ<&K;w3j#jq0!;`=WAO~f^ zbFk8m2E>>JDeXM~Fc1|CvJ{5;-up(|67qcmhR7NpwWEb}tm*hK*6OJ!cv4^PD|{wj z0zwY1JK&Hl-pEV^duu>l*Ehvi9~9rL?JYJ5h>tV6BdAzdCT6<1Tq?ho z&zx^;)XHZN?7+OK7LkD;V5i_?#=6y@{#$4^u=58!Jjzszhs76K;}Zr1F#^I~Z>rZw zVFjY)(jR}wiDLzbWkWvCTtmSJf(mFqA5=W~9yz_AvA3VJFduCRmfF`0hLJ%Hc z9aG4DqTTBLxt;JoEeS1;plAIgsTd}q7~ zl^kkV%hzLFj7**GqQ|6qtr(#_a5;$FcHrR`_5~J&E?qGDro!g+W?4l~%l5S$5wGfZ zP3VZN_Ii5?yFfm`)QW!HhQr}865C{j&!xp~fVt{u%rLAWp@VtbxMqMeka~NwL`{1# z%^KEvecd$e474#0I&+XtQY&}y;l1gwC}&T=Bnw|d-a#%%?Bk9>S1DZB z)JD<)W2ONrjb*_5Wb77NC^8&krKR4c2)dGE|IG6v#yNm{{fU-iNkl zXFL|={oxYI<+Yj%@8lbptL@Q@|7ykoNSWZ}RKoJ)>3&$2k&l6pFHxA*^{2Dfw<8KQ zNPx$#>)|n+h*=+i<=?K1b2prOs^O6;^K1Gp1(}+5&%hTr_aV=IWHlQ94dLV zTBca!0c|~^y?Zuct$Vh%H~E_{Kv#)6{z~#K1#P3c)ikj2vcvt}P*HXlc5+q>f)yOu z?{Xgi3uQ}Wzj4Mqz@Ky+TvX>C)ty2~y?YkL5sfwkDMFDq++-xcfAuU8&@dCjZ*@Ns z;JioH%8xh?yVmjVfV>0LpF`*`av25DE0fn6u6}ObUxJ#i#~u&X`xk1_LAYI6fHgW> z-P}>Lz^D@gmC$;G6{?E`-k`EZn0nIb8FNG!0Q?6;yVC9Je7>%a<1+5SVGun&VtC3% zSbr;a>TqYfVua+)IPwee;ky!nyR1gC@l`xeOrGHp1<+WC>5J4AJYKG6@gjR#i(0Cz z(a_z=TIU760(?V2=IP>qOsj9YBC451_)gdJ^?$atJt6V9AJkwn8w_K-X(>d1hwc-J z##RYW>bH@_3Z~(p1wl4fQMuchsE@lG&ng*VKbj`9_a5^Rpmq3z!tk> z@c0y1GiLikAEay;g%BcIcN<|8d}eCJMF#$P-_jtqbwS=Wn;lJa-Xi#E;uFTcOeo`e z%o#NNu{lWLJtXm35TB*(P&5S?O^Mj%Aky-xE9+Hu2c_hG(%9c@|D^EVsuDK$MRCYv$FcChorAx&p ztyna*i+I{0qc|p*s-UIkBe5*_yRMLUpH`M>GbAJ<8uIDbyT#jIOr!Q&Uo^F3&Fksi zwkJdw^1fs7hZ8(@o&FLHkyMAWww{=NDjS!;byYO8H8j?>CwN<&P`fxFy9SGDKBnm+ zOog11ia(Lkg9Cd-=9z^#IYvmOI5IWT?Q$Yox{$KujhM``f9dt_a(T*0J*XL(T$YhX ztsOd9g2ZS}8Me1gzXbp+_l(;h=>ud*QE206W|SeKK+Wgm974b^!$66{h&!8{LSDaO z!Y}JiZg<{)9ayUNqxs;Z%W8fpCd!c4Z&KcPqV+J-g_N?p{jjOpgf#hrX0F?YNcV3e zh1!V#USSq=AYj!&U5=*6w zap8!U$CtBf&5iKbDmc!`i9};abvQ2K5s{3i9?lTVI`P>O4iAqi=NCIM}}5~5crt$&z?nK@P-u`jlszShV1bOWs`mgZKCyW&k4vlDnmruW_; z=C@7^ZMZEHv&nwaUftLHly5oP|7iuV*+x6+z$4A;?|h$^H+JiD(Kf}%%{_-_?XG95 z2uHtMm*ogAV~vdz@P@1)KwKe!v)?^}F;fyX=vxzZ-c7PqrPKp&((^cTHOHgQmM$$y zR53Gu!pH9x?6H!SW$Qjm8Xtcmt?*)Oi*?$o;-c{J>`eORGk*+M(A=6gk;{nEDj#0a z(pm!$HGyV56@NCq?kxiEXeLQJpO`8S0N!ArP|;HZM=8pFq~0(K*Gsr*hjiHV7mlcOy{?)Nb3ttPYO6`~=CWI5{2pWyWl*ri*f#ezWw2)ckB z9#>TS)GcVl$T>aH#P*tB1Jc@I0yw4EnR)^arBMJU96gw+uV8NTA5#!I0m6qmHY-gb zrEug69Ph=S>_p71FYEicIvK27fA>%lSf~*JA8wNzAJER*FkdOuiq#F@QNl^rm?hZ*ox>I0N($bQmfOL0v z3rP33?(K8VdCob%?;GFy$NT>Eja`2L?QiGvhJCx{;*+$zR9h{Z{+u_DGNCebDA`gpP6c?Tax zk_WORf*O?}n|DV6aXn@Urv!3HXeex4Yaf>znX5cdi*SyBgxq|}ud}Obf~x50q8TZ* z=3Y2z{<-ehhUS-(cs~g;--O?o2QKfw5p-8sG>gF_-DgNdD@4zAwG>-#-+r#4E3ZB> z@?1|_YUGk^yFMTPi%a9@!PET0PamR?*cl>Z=rYwcYlhwz=l3{NM2rsqc;VI~-y1X< z_VKTPttB410B5GGwGvT z1=-}mjtRL>7WU-mt+bMJvMl4grtf`I@Z)GYeH~;-nTzkio>6(f3Buw}X4IcQ=+US2*X zfl=RJ5ijR)bA?la>ubcq)gqBgs=erc2NX&?d$OY`i)icVzrJr1Lqa$7|-AKPv2PfB7zi=(VEmZe)$;qCRg>A z1P<*+{H|r8rs{}W-JO{~%oXaZJ6Yc%7om&rJ*rzC5#Te3H}=qLVO-JjqgKFa-A8pine<8%D7F0Vp=_7zf%DdFz*??#dCUdWn36~4%s*29Pg{l5p<}+LG5kJ1s-UCKD%^BD!Ah|s7Jo{0; zYU?fNEKI@0i)t1&j-rSJiC0$!;kdZ+0Z1M{61e)n-I{X>0wzYd7x>}_ce{JAV+8IN zs@AQpJyf+d589{!z#1EAkC#wvGc}Lym!dz3Up{?HGtt0-=c!l1v2w*2yzh}_Ob5&G zPXkumzl&%BYzqO&k^xd|@ss~Su?}$@84)b70cOBsi@(qI%wNp5hF;UXFqu`6xsxPA z5&c$0rFsY|lXzTTvO*xAzJQlc049|rT}5hFXO06o--w^c7p)v|W{(rudyG1#AdDdv zaSM)xC%>F%K%3I!;z_*9>wgloc^f27ww9$^G)M`xbTC0gPd#u>9_AC9IeU#L$5;iD zB;fJ}if;lU9j>fFBgfJs3d~B5d4x&`g7D$tM7{xzsdB-nvhYs)S6n zEAN-7v+r38O{|la(n`C|7|7@8QYHp^%d0gLIgkhQuJfX&6-;4~hx+R7@0b+7u%Ko{ z09-`Bp3}7Q&Q$e3uEZTNZ!QX`y7Qj@jv73gyF&oX$ifa_)|UMAq2rB!M8%BoJ@bg# z8--Q;tqM3XBPB>?fIXIbH&FHi?(is++;(iUx)G`YQRB2h)L|pjTzn*bH%G+TqbB>G zuzC%3^-2epCkB>n>>vHqfBaN5^0bN8a1n}` zvjZt@MAWjrn@j$f4%&fvv6Pe)3r`d;*EhbiZto^FO3aX=o@=f~c+tKh{v=dk-H;}V@0+@R#s=hzUv?lT~ zBqhcQcrw~?MPz~BxVeg{Hl}qi#B^?!xRK>>fN)YPqm`Y}b0o;{np2jz0n?~(RY$F3 z&mxfl1*Ew_vryLE6K!wu@&1C!;7c;Ig@m1)E!Sq=0U$A2CD+ z0~YNZ=S}oo+@Jrvh4cmRJ5(rFY0+L%YfhZZA}y^JqXG^3pbMB7 z>6E;D2|6?E3cIU`gUXE6YAxuiGM7syS$H8v#|-*Q~M@hq-eN!YE!W{Sul(q z?|yx|NV}RVRC8-O``fI;uUSJA_($@BG`Mi5X338S%`EYu2ic7ERu7N+@ICVaRGX5} zX{1S)Lqba7WXi?F`F;2UN=S6R`v%k^3nAgPU$ZVf=+vpOd2ybU&_b0lri{P-pTzr7~iIV9LH=X|`h;^6XT2V;%n z9^R9%zAi2|`U9)a#Ud)XB5s;!dh&je4NIp_3@#{K$#2>=W zrOe=;JHrXS7iuDkI9_+m-5LZ51p(<80(^YTHukHiJy;vM3V)O*{<=_UCb8jjujbIE zo|*mn^BivGAZ_Tv@TNqranAG;{*afA{2(16Cv2it!OiD>38xLwflHtn2j`W(AGdH) zke<%zGvB*?DlAg^duT7uwLXY^HYV-}^=!Ogb3a4;-V&DDa#xv=^WD1P*PWa#xz7zI zXtLFUnhF=zGs>Op_Z&My zxs-ro`4Mg z=wMt&g$r*Sinoywplj8ph{gA&ZWMFONy`O47J$_z&3bsj{pU&n`qiP)ZUBe@ZvDA} zR>7TUkrsJ~S{rfP{^mwJUm`#!xv0za^(xUI00-5)8%wxI7$9y_cE7^BOY9i=LqM6C zCU(H8>CBZZMMzf30r2AGdnKNN8V2*JcB{X&=rRBm?1 zMol&c_0!)?OE8z)>Iu0ik^}#gj%t9W8}KGR@=oaM2M+>*H?zZf&RX1GCNOkWmzgan z`19M!(hIwhrWsvx%KW0u2wx;^E9sPALpF-wW1rxX_*QD&tzk&_gwFb}7;a?9*4B1o z=S1X_T5ccm#>T?I-SN7G@^~#Y_(2s0=V8=Q0IaIy`cU8_m2mH*qTb||y)xAUou;Ym z^7e`+G?=KR{jkShF#(k-AQ+bkBtKRh4&7t!Yunwob6PnhhVdi2aGUL=WMg*~LiBSu zWn=jj(OxxPyN41Bfha`0ok|6p(#J>wWe5wSB%@|rD>mBt?DI&4?U9f~9?ndK?$N99 zy5dQ8MPhg$tOP}BJ2;6Eal-}7k8jS+M@=?<>szr+NlIm}up8XY!9n`Q*#BGrhVDkF z!jUeMuz<@%Wk?qV<`oe4O_E{fOLFY5KhxLeMM?k@=6-Oda&)iJ=J-9V4P@jAGWd2i zkGyBb$%ceVA|ae4)*fbKKh$!YVly#w^}fEDRl|kI%Id11>#TAD#kL;vHqt8GQP3F1 zB5doK!=S=n{oym$LmANuK85%bov#+6l!DPKzts)T0mIl^knq{c(K9N8?W5OudeVb# zL}=Rd?!n`XX+}{Do2iuQw4=Ts9^camM8FIY65AWKLuOCo z@hPr%XLnfdf3l)*;oPxS@tWNB8{g3r?}jNtN?mx=gKJF&R~rN1AdXSjq!UluzpvE( zT0d5tm1}y{m<0)Gmk5dOZGNdVUi0`?!Kzj-c}B$KEk!r4`}sxbMoQG<%p0F`0x&GWFB%hR8?R|EQz$5v6lx0nlu9q~zvH9krdc4O*E z;FEH}Gnl{0wVEmm5xICNNJJ9PaKGfCtSgHGda*@zM;&S1Y7<2s$Av$q=M z<4awDJk2UO>L*T?8IRvMfAyNgF?7iqh=`)`NrHYq+TmuRq^5xlDHcUUVVa(*>J!$n z!raO&elTiJy?<@#$DNj0hs9z;grG?k11}w{}lw@bklBjCFBu>Ldk&cY5@hQ(#XgB3-X%UtoX12(^;wVz>?evhkjFp1|A3>(Tja`}bZ53s zrQzf^$9SFotVbawbl9fhY0+bd`P;iFMMz3&W)a7}tKQSn8WJ)FM71D%rK4|1=X&-V zWLl!5LHg3Bu&AC;*eT!I?SfRoIoSZKWrU$jl5}n~LwU?0&>{)MoWr@Vv5E>wsSGQ@ zPXg^HiHsVP3QVv(N9~XXR z+AP!w=q^0<&Gx3R94do!DYi|~KR#bf;NZC1LQ6iUsf*}iO^@)MZrYJ>3ylF0?V#TF zT9=IPRp|{^;@TI}nE<5E2`$mnT2&^0=^J35yp@i;6yYutgt;4>x z^sL`s9&Yj*BBVZYRGiK-o#h=HOkpkgBHa<7??X7)O&bo1r1gfL9Go3Qs|N_tA0p2M zMA!p}l__#GPI?0xp6d+!es<*0@J#?c$}*iR?qyciC*AE9^k)RTPsu5qbXehK zON6Um_OV>%7CUK|Q7XxLWj499h}5;<65M(>@x6^y<56edi*=#dulM^f>GH(o=syZ} zwJ*t^^;~_2qIov0Qg^(aU0;70hqK);?8^vq0a5)r@r$IbNV^K5xGz(-S{W;=UqL$Iife0x!WD~X;fz&eR*!r@MB}+ z2BX8Te9?dZUaxZdmCY5+bbE8ZvduzXmK(!phY?XEM1K)0r$Cyegv*ly>60!f)H8R* zFO61NrW%`lJI&ZU<{#aL0e7@=^t$&BQ*BGPIvtiuX-@Q#*IJtk;Y@d9oTmCfJNZe! zPjnGC)1q+OAb)Yv6Oy}K1?g6wx~F}Kjqmc7;ykEv4*j}&^g8+8m9BC~dovdBf1u*^ zy+zpVV=PLV_qd=03Qnd%j$+Pmj87$1o@C|Y3ry7qO)FkaV`OYUtPFPpoNrP5J`F5x ziUBy|^`#y+)3wNG>_nm*&;mq2Is%bhQ6DUW8*~dj_m`-j^3)xlP>VzfwYBr}RP&`@ z?A%;>qaPfY{SGCq*i$e#4zITO?s|SwP;#$q^P=gT*C9-053p0eO_@8MJ%(tvY{`{p zk(CWC?zK?Qb=xMpgj_2LllRcS}zZx#?_4#Kejcw25Gz#$T7L0|_!dxuc z%k*)rIUuia%nk#%I@QKVMMWyH29%sUWAh=)#<6{Rv%^bj&k`Y#z4td6B3Bm|R#8vC z8(cQYGggc)Myt{DuWc{xn(qyWejsIOmnj@?s%Uh zpLYSc7_3;2jBqe>Jh{;KaU1ODpPbsg(ZRJX_BQu$;z7rB0SW4&IqhoJ9#a0$9BlHu z-rV%A?6G)@!ZGGB35g44$E@kaD3petb4Qg=!fQ&ZCk+j*DOttu2$*n;ntJ zt8uZZ5;EbGYv}~`ho?3yCgk5Xl>B(i^vj%5X<)$~Qh2#dBap6R%X2h|MymM6&WYP_NFE}77lR!K#zelTi6_(5m9 zw??|v&elJOvH@LiqO4Kc{~J*@T{D3;?*0H;1Qv^Vft#co}g_8L^~-w_{RX zEi(^Lneq1}iM@AY9Q>w6N=QPWbfs0gD5kt`Yqo|V%407UjZ9=#A zQe~@tJhf-DtT}3QA@+l52K50I`wxv|AAY1BHb8Tp)Kpn@WfD%0+beISseRXin#3cZ zJyYPdQpR-!(Ij?=2xJE5MS@vK{2SR(!n^y}ws{#~e<#uE>OXn!#(eI9QZUhF1t-z& z22l~0fI~(_2M(-6^2cl;U$JUSJ?-blDwUD+_wJX;GzdZ!N#l0y=XRx~IRHF&W?k(h zaUa$}l0K&UDCw)iW}Z#KSTsfD9+-<%iOky(?KT3791gb7n~`T_HJfS7s<3IoQ=(nl zP2kp^=yX#~$~B24y|)WL-E#}!UxvzNkYKfAMi9@nwD z;b)|xV?Y`cNPuf>=`O8O4r}eVsKD?~ey~Z)tI@b;bz|wC$7-D-@p4=?Hiud5H%~9< znug$HRi(!Jn6EIhjkvrPQIjHcUO0cQ(|}V|qt3f#-5bu`c@Gxq-*vB>O7mSoT-De6 zWEa1)qem|OBF)G7RqV4R=y7@aecct^a_ql8EbqLvqhQCBzZSHh`b^^qC*tLta$LS>e@-(Z-RVzXJ|_t!p;Nz85`L0yIgwk; z&j3qoSb5HT%_z8dNU=Q4sxZcCq+$TaV)BDHX0J`eIJTF8W+DC79qdmrh#fHxITP{8 zWHIPklAH@Eg(HjgQ|HSxG-V0CmOAa+ga(g|^B1Qrkbsyanxlx3Baz1r`NvPh2D5K5 zWxNJ4wlHbr8*<6&k9WccNTzV|s-1e1|yE4-yg_>89 z9wnTEfdNcDn&9%zg)SwFH@@sJhgB=vmlIptQ*-sz1Ee1!Mn}bw!##HE!2CUNw3)9% zSxxSRv*pAM2gF4$suWXiW{sP2PK))nj>--s^Za;XW74rgP>EZ9E6CUC^eYR+#^%-! zv6GAHrp7z)F~EZ3$38d6tTO~U=<~YpV7=O{WFf9ebGJ$qJv>0a=2Lm}Q}UhbYF6y# zln5)8nF*q0>o19lu=H}n&AVi=(=s04PbLRHb}A@gW+j^_e?m-op%hBOrNK~NQAS~Q zVjvu{xb$)Zv+j4(x3e)=NzH=SPNx|mIjJ0}%k9I#+^ykJK4#cTIY~01q(EAv)L*RA z;$IiGW!1H0cgF52N-~3jSVl{tRhRw5|kB^W2os({0v^R z!gaF=3(;?g$^+kY6WZT74AFtxajxS#xkt0!sHm5f|Kb+C*z?dSb1oC|*rlJ#h@q9( zax6RY04k*Xd@m&bMdEKj_BGX&7p?65L*|qrZG4+xT+_0`+lU@-LO&1DIG0%eLF0VO z#wwn)9Co@o!mWODbSG@!H|3r6#fAGkepnexx{vL6-KsYD!XJ+@mETFOV4gF`3H<~Z zI_9}y+0MkheAGg!1$6700_jP9`6lJ6SC`D@!&*IPW)2~DAK8A_{b0mpITdNI^Tnlv z>{b(q7waWJZ_VkLjMae}v5e~u_PPqxTxec?h5w?WOrrzo!}5!vMIA1$eVymeC8aKJ zXF8V=#S^M&Yr7a%SFgLP0bo6{TeXw``OYJjY>o%>93I(nu2JE9+ZqNrog`n%+ptv) z+Sp&)m^#BlkHjvMx10(=D{rSh74eSl0-kY%5H&ESoc ztqK@o->zA@b#)}1msin3ol%xV&(rN#I5EpJ)xY`V6yD0ghUeD-<4mxl-LZHk6$%xI zb2*-nAf2wSqan@su2c(eWHKt@C>KXmc4Yfw%y1q5dQb4cJ0hw(aWXu zXD>OHUSzvcS_t8>&|1)vW6+PA;_iNaQ}ZylHv4e%Np(+Bo-&|W+2_G(n}~l7_L>Y# zu~rX16cCxNc;Rutbmh?0_5n+l+AiZgha=VDT2=(zE&St&ECrd(mbBMsl*TbnnNMWR zm1UzvUQP#1c~Rc_=Q+!;UN-%pQ_C*m%6O(NiZ$~+Che43G1>jz=l@hVq6y?<8sHfj$(-L3+xRWG~JiJ3X^)Y8*|QY|$^0>pri$xuPXn zUa>KK!;iglsoucsxmUt(y3`rl>3r6z=7lvyVP=pf?0;_eTU{>YhS1F}F{%jN99(7}|*W97@Gu{4&vnk|33g{RYY zJfNk8eWejE3cQ%*VTJ{tOfnEJ+W-3S)mV#Yu)7uG@UD{{U+lSkNMJ;c51<}Dl7`yM zd=y<+3P{hIY0BK3HYd1)3w)2~e+D}f5l;q7oC}>c+GC8g80}VlyyV2Ltbcb|s?(Zt z7$nqQB1k4-V7{)tCO0HL2^fE70|9!KUz7YRkc+PcEq>5AT!lCCFs%0C*gby_yXzBS zlH+R(JR~#xwg9!`L8zs;)c$e7>HH6A%ts_g*rQoM7FgZ^ywD=fzobaXt?ILxamB`VE2)<8maLxzc zeSfcn=_9z!!Xc;YMDbWI{oUje_0)$5$2s*O^%Z)%-VYZ7)sjxV4^&%Qv5s@!^xI&Q z^xS95K|W?1`gN{^X0~cYA0ohDJlBCK)EX<)T4zZYVjk7i^Eo1}XHINvh8xxF`av5a zs&f<+!&?dy@6aNtz8ea{nu^3wci0>s5Lng3n^-(e(G7XY1$)e#6F$$f-o{E|{FeIL z?ioc>m1fC~T-#fv_YG5IZ!32rAJyM)_*(EYc=qyk-nFemN0moR^8of&!`S8Z9uD>* zkMdnTAm9NcGbVMxt*WN0Yo{2` z!+VT4WRi2IzfLywtFAosRNId4@I3q^*fjp4plUFZd+qXZ$ufl*32zjA5iPBfWqmq9 zg*^5bdEz>{3B#Dd?O0_?UBJszy5;Fs|y8Q2Ge6h)z zdaWz%J~+Q>2TPney6GKxTwc?eYkAV$eMpC#!aM4?sSezd_yGDT;s5^wcCVbblSxh!5?0 z{ic^%XxtT%zlD-LO85I<_mN_3O4G|)sk89*1!;(aeBH)qqLQBAl*ax58ldyT~HG#+2-P#wUEL`%3i#`e*J9 zoiB{|?6FgNVJ8|^Y936smEE;V0iy-%Z`t{1<~S{v7LnpZDJ08fa8yq=7|NnvIa1Y~ zZDpd@rbwPzg=pl9tS*;)#eJ`DAhG2ulhgvP_IYhkPkB^#q$Pk_ktC+z$1`46)TUUj zB^%u@U-n?`Wq7G^3b|5}pWAFR5np!EtdpN3rJ&qg&4+@Cay^!++2k%h);{iz0ajHC z4-dZ0IT3xSS}Ddj|B5T--a$~D$j^M9eYqRLulY{(xG2c3x-SvN(%D5p14FwFVIP^{ zjd&-D2QaDjHq{%W@A<~!zLg`x8%LMv*JABB)H$BF?hIBpp3GerkmjlksWqK5247r; zd)>%xcgx->P-oHyD zg~EVXSi4fXa5&vwfCgA1=nzpj3DoE^1;uMX$L(pnHxVt?v8CSI2VQgZjRbOsKI1hn zjpg4)fC+OfAH=1j37MaL)XyX`u|r*D)V;5t`lhZXsG&osEP`nJBYG4>rT4C*uWCor zzvxh~>?G%-Z2oHw`LNj;-OIOS_jh-9?3jj{VU`sudp76qwmd!RT(5p9#j7%`b-HX092D2SQWO93SP@a*5xEZPW(yYf~4`Ypbee z|mDLzc{Rb|dz+Rw4r(^&^+Tt&Q%N+SGV6 zHFiQIY`8v8`8!%Q+OjuWv#{VbO&xKB04W923=Uu^xTcD-?;FSy`U1xzZ)u%=_^>HP zGEQDt3e%nVI4R8|sy>yHy7Y3Gq~Rqu-*BIMc&u@mQuh24NlD?OY#Za-ScRefA|TcW zlMA6@Hl9;x1k+sSUpy|>Z(WmzMJJyZIhziRW$tH~^KVXmN42Z)beeJ#dLnCn!NQ3I z)u5f@!9BP8>#+tlQW4`*O|YIRohUFl6OtdzT{!$@8wy<6S(lT zTnkL9^wxyZ)lOyOR2oBSFu?@WZbgd!0MEr}IH6~k$ez(EeYQSUR>}qyFVL3_aRXGU z{Z*q)Xx+`=8kjc*zw|#tq64O3ai8}PkmDd&3=vcV`x&Sx>$cb-`m~8wB46V9JgbS0 z1m3tlpy70pWI+f7u}^5A?$2Wsii5NOIvkd#JNGq^q0-?3JZhT(^K`-YL#Pz>a4Nb! zk;RDq_~Rki*CPdBlW(f2Fz)zh0CzU^*1iVs&wi1iHNVHE?IFwMJMoPeHSxO(ulS0~ z1EtCCFD=l_%L7D)ZmmTE4_tV0P;ue~7!3Ho`2p&G5p^cn^kxgrFI`-1_I2V*kcQv_ zvw|>vJ6G+SPd@R2JyZpd{etL2|0c+lRDQ?|%**XvO8&5Fr2m(mKVKoqv%0y4cWGT( z84r&?6#ePa0(s9efhy9}Mfk{jF>}!Ww!q?@hNC@ba9JSJj09cY<5PpQPZ{*mTL00c z6M+jd8Cap!uBZkMQW3yRR`U*9<3NA+7R!U$>Cz&g1N!~u>K?#b&p`s%n$O47DO-x@ z()8JY48gk^7{cE1web;6KNLSxT@V5~R|6)@Cv|5G5)zy-0WvT>YrhC4wbXwM;wPfCuvo?3QFmxe z(%6;HlE{5XDI}rz2j>eN0j-KZM}QNGS8{xy^aQ+ep`BUCK#+L*zd_ z;w-0BYW*3plS%)8m1z1kK(sX}k9z`)3>E0)l;V$73BX|j!b|tS#-@w)gp(cuD%!&6 z3)9m))lm(+MSVcNs#yAYzqmK?pV%xgCXVK*p1M@}qx~&0%#U2q?I;Tbe}|t^0m8~6 z210A~cu&C$OU#{p%oQmeMx{hA9sViiN&c{4BZkA~bg+=)rlP8<>S{5fXz}7AB2jGY zbA8oT(b$+){Wqk#vh(jOMPg&rkuT4j;l}SRwvHM@L^80}cgRguvIV%TnbH{@ zHcUvix>8^PM?1C^5hfm_qi(&mYlxe}MS(};{RD7BY(7B#VEe`NOhLsh?G^&qd(C^G zQKxMJ6S(S?=>R6++|pTDHu*Z+E#Ex7aTG0s8E${xYiP@9B2wnF&fg9w5TMJL5@_|S zaXP00qzh|&$iX{(w-cYNVI_WcGq6-hAg=O9OML{ga}Dnu*<9xSzn|1;Qe9flWF^sI z_5=7SI9!Rj)MNj`-nI|B&kh0VK04ugH*AG@w6KAli#5wZ?tKoc56#R*58w2c2afjN zp4@9aPpo1bNom8P;N$ILE znqPk!&8VzMBeAg+<{RxmQ(>h#B*fsZnAZcVZm2ua5`^T(BMF2c@w_nopgw{r@9Uv# z=Kk2MVrm`zo1~*~Y*+ZFoZ{W2dtJOm`+>UvS;49R*AtZGYU zU=xf&B%@@0wG%58ilX$@?;!VR?9D#>do*a~5s?IQ2k%=P2zAN|d$%A_ja#wdA%h6v zxELNGK<5%52|Z8%rLFm4jvWbOj>Fbax)Ad*EH6ReLuhcu&vh+q#GU?TN`b!++4f*} z>d&?H2mtcd?Lh7{BM@9_~35RhM9y_i}Q(?WWE%^>EDfQW>Qic2HrEk-{t zYo3w~{rbEyZ|^hs)BpC5y|*dM)^2@P`HwfkrRhf% z7$kdh|IY{h{gE}Ku!;l35$6B=Y+O@hz|Jox{A-Q>dc?;LQD*YYdz0Y5mdgX)s!bdH zAKUupBh9tm^gHfiM`-`GLo!4eoh3H^fBw&Z{4%fG9O)?X>HNQ!`_Y@e$RXmn+>IIVzw)`(OJLAhCv};^c|^*K+@_I{s56|5qLVWj+5#PKOWT0m?K^ UAIrK5a2^P9Qp%FW;)cHe4`Y)EDF6Tf literal 0 HcmV?d00001 diff --git a/Svc/ComStub/docs/img/com-adapter.png b/Svc/ComStub/docs/img/com-adapter.png new file mode 100644 index 0000000000000000000000000000000000000000..d831737d380a686338ca9d12576a1fc48207dc70 GIT binary patch literal 90892 zcmeFZWmr}1*Dnf)lpv*2A`Q|?H;e9WkdTz_ZV^H0?(UZEP(eySx6%U^>^FcZ~dvagX5#MR^GfG(t2uI5-R`Nl|4uI5bi?IQUc)BydN& z__7ZU4qd=pL_|?aM1)k)!PeB=$^;Hh@xQTkjPa^GsBIM}dY8k;x7U_a#keG^@VsW?vB%-F!AtY-`G5GbVv!=M;DTo3MJNkb6?e4`i@{M-URgbhEW9!OAsKVEfq4h0-T!0uvy zGZ9==tp>5N_U+DXg;)%8&pN!Hs7UJI(E6&77YbZUG)?>?I7sZlnhIJc3p)Le_zpNS zz2{$(&|cAg-9&3qu)!tif8TH)u8J;!z84WvMtm45tVcbjxE(Mh)rt2JPSFgqlaj#s z0n?taljDatdZlbe(oKN;+9KO%5L@Hice2vNke0}Mffq}!_Qq~miEo=%R;7`>H9r?8 zQ=x{%4G^sDst@Mc5vT_?Xv97vxL^6CljNOOBY)>}b{WFt%uf;+?iW^xteFogaWjbU zA6Alee$JljL7~b>CqrL@plhILQ!@PQ6e&eM5Ek-LOdT<;HdZbj!P8D4dtDuS?Orar zr?Ix}&qm{)H|Cp0_4E13%i5*VbIRZ%ES*PaxD;gS0aGspX_#J_vo>*s5Ocqwi2ByI zRPV>7PKt)AxM37X5dBj#&)Zz@=BHQXfR?a)E)L1_o{yMnE6A3=>{k!IHX7_AVAH== zl!z4MFtlUx5;BN1+|#Uw#9|eUU63-N1gnL16)nxZ$>X=7?!kyUFvV(K!}~_tz4YO} zoeqi9|*0 z5b8w_myA9O{>lFEQGg&Bj^A~bJ^Y~_{PTC$lVs}l&Ts^W3&Iz{Pk%pJ;=_9A@T*l- zK$>lZ5u49H^f$>u8 z?}bTpln9m%a^apmP3?B|{GuX^{0sXRPgabbXSQAWO2PAPKlwtE((huI5se*XnfXM| z{H`F*g`wL^NFDI5fj*iIB*!~QT6HWoTI%?M=C{^Jf_xZx#9bfWD!*5{rsWWfP_0&R zBvOuAz3jezZYW36$LU$PZg#svQZ*E0eLfUFCA>rG@{l)Bw8d6oN>GEy)lanoE`xj1omY8s#oYP=%lsVI@=?1(l?5Kx_1KBCU@K zlEgeDym)6=NLL(2n5DiU8T+B?haKB9;t131m|;UFfhI)V5cRC)VV>hh9;mJ1F4@dK ze9#T(5}8atavR8ohKaqV)kLEHY-*UN$*mqZZYcMgTfd8^Qg4SszH^i7o~s`{*CT}v z_j6+}>Nb4+i2cs(-%qaTZm{;hwqw6R6nV@4Ii!Oul*$+(Twa%{|?{8a+cj8MK6tWIp0ief&}&o5zr6mBXgQq|)>} zqbOO`vKW&+Jy|YIL|3LPFFk7^r%g#o>7@$bxe|8qcXh3jDuvaSK9RVHV(ns=Vykgg zwW2MYapGbcHQSQ5tl>B6Y`)rPWqx(<)a7{PJRw(^;u?;s%Y_HyrbTLn<3+kko<;IX z^{Qq?3X06?%o>7)K3c6B0okwfK2Q9#_&!$nHgso1tu3v?UFuwtPM_^^>VJmf+ihI3(@_zeb8}(TFosw2HgBvwU6_w?c?e=vCbj!=%_^F+6^>MR$>0)rHhX{DkpHL)J#t(nl zU}a~+V2?|-d1=iGwKBDiH{h7Gs+jh6Eao2N`|1_vUhSR{_@N6wWb+C86ITY>c-el2 ze)jlvhD9AM9V#uxPsR0HbraQVns_>snv2z0)92H&bwyQ;rZP1qGiy^epRDUecIS4g zcIbAPW^+#WPKB>9PKhZ{DEK6T#Z|)^HZ!+69G*KB+PiHOZsY&rnyg$nSd|QkqNPZP z;Nv_@iAhl@ALS@$&Z!X(3`^!MHXpMz<26fn3_N1TOP2Z6&yawWpizEWjxZTkUO%^C zV>I`qfxX$=`OGe%VY2DWP17ycUDadG*n%}DDI{r~A2l65y_zq=!{^xHjP5tj&y$4u z0N3y{rv1I)iJbd6^$0ljl6BNex?>m{*hXko|vqe zb}m5s!dy&weJaYxEVMP&Dw09gMv^R#GT%yJlLU{==A@xqwSFvmjA*&68!xQ=#b*QI zy>~{q<1`L5&txfbsq%KEufBvWsoP(Ta&N|Mdh>DEV(i~v%xM3(NbwuH6pOF_cdusD zaN1@}BTF?+KXVCRiAK+pa=f;_hXV_-Pyre`Gl@Znjq=_CpM##ZUXG+pEQLjqF<;Re z<)A6OSLA!CJM8W!D*{pt#-0Mvf&%SX5Tcu&dTHz2c1e;amrv9m`6Nbjtr|p`Mimx1 z7tfE0sboAx#=GUf$oQ5r!8h-8nYxK-_Q}*L>BD!~jA_1puZe3d-D(lj{Zx^(7}oW( zMtMh#@7}!3=6a)EITzLIf;Utv3CTFMI8wa>_ZJ>;Fm~dh;nguZXw}#Z*DL#McCi#x z9ab@ixQ8&`@N7-iwm)R()f}lC^WOYs(rJ=y!Wnq7~1Y;(M=wuml;?r0;2q4igu5a<30Z>@~l8xJu^*MjudKC!rc&flD`rZ?IvU1Emw ztK>2`9&j$s;8f+6_Z1g=(c4@8nkbmXsZYBKyU;mt3D`B6ZQsM%-Iyb2uFjjuY4S+; zRi4NGCafmk%ynz;l;7Wz(1O^aerJ4Mrw(%`X3w)t(E2v)-Y?{2Ocu9p$b&<~ljQUcN{3QQRey!H$0*TWC=@Ccb%m?!id+EpjFCOpnv z>lZQW8|%k)PaEcb>`gC>y=+=Of80)AP>!U>?-}N}J95&qP0Wd7GuM>lQGN8}R{d;u zZnk3Y(ZYq7>nZ=2){!g1vwjkMfx^qLrxC4bduiRzkOZu}ADwON87(a1DI8{aZ6@Ew zp4MC^^;U1$tncOUf9BsE>gM0~AoDqBtY1+W5Tw_iY2iCgxYaN7Ho9uklhVUz(YqGE z9SE;4w@taqxgu%l_dL7s-b99C@(QvDreDP#Z%(h%>PzZR_|!sYjv23KTm4)7;a_Te ziMvHJ_>@gR0N1hr564IV$HSMQ)J;3+d-(SGV5tM*4X%1B_G%ZgpZ59fv(X2)HZ};K zY>D`MguG8w;j+!)Iz17_x=acmrjM_zOKXvRaqL*zsMvJh{JHq3E9oex!PmxLcKq@6 z+|7f`pI-8fMje76p!jH_DP<}r2S*34QQ#2a3E}R8D|qk`fG7Ipb2GnSVP;`r z1WzzJy4yItc4M@0r1)cyzs3T=95&J4KYy&##LfIa zGub%)xh=3kX4p5(FPUC2|2;N%l@E58N73BP#7axl+#1jf%pt(`l7;W?`Ty;k|IGN0 zH#PtBCJQ_Fe|hyEU;VGIsyUiCh}c?#Ih_Rl!>>Q*{pXi|zR1T6+xkC9@dusn?gBy! zpz$&P%`^ct$wxC!03V;4iz=vszd*|Feg?ts=imeT3qJYvPg0cI;ou-}QldhtZty$v z$Zk)&F3t}oTYKi?J@;E(jjW73Sc!!(bEDox>ywgEA|m)lBBAyQQaTAg&q~DkNV~_u zH1)0Zj7dhlo}pywHtBJ5>0oqejE(EQY5N&p<=&}_nVCSf`<}_^d=g>VjI#h)3l;

HaLoAWe|wrg*F;I` zfbrj7+uci$F$79dak+2s|AS4zUIg2k{Bzd-_M881>%TDcUvB*+IsXdbe=!jM>ek6#T(Kbek!)`o^VB)< ztqI%b&RdfSJST*bWjwX?T+tPGz(Lnw7A|;WT;|&Ua@$l+sOp5k3R+zu_Yee8dwZEzo zbFiDGj>4t+ZvC851kT^?0oMNe=38@q1eAB$er}v&^9sw@C=p-|x69;s82-lwlVg*5 ziNe9Nf)x$yXlMrlD6A?>n!c=ygVny*kz8vb)eSF_cNJVYQYh9h?L^;vr?rW6ktsf! zROC$Yt=k%X2TO)3DN@Z?5K?0>AlbHEatLe~Qb>yq{6l>*Kgbs}tbJ;$NhNy_s*tXM zXI|3eLBM|R!7t5oZ6FrI_}uvc!uPG2lGMlB-s$NJQ6xEjea5m^H1bS%#r`mSj+G0s zf1OpDbP=_qTTj`EBHe@}OgX3^(Jo9FiYXLT6`zMJxG7aBKU6Ki4;KSB5pYQtFhbLDDZp%~ zWRR8=ta(u?Y)B>o7#7X$91RxeL4sWyQNX^30l#otk&6VuTtCZTbN!Nslq!kHH}CO| z$WoCV!e+sOWb*lc54bY!8KOxJCJ47J+lsUl+i z76*e7X-LEPCi?{FYNM+;5yBcO)_(G2K@AER=(jd$j~izVYVhvW!^mHFulAf5l?Co( zObCHqz)R=U_LZ4p$Qv{Sltczdi>1T<2nUS7L_mmbU(r5>M{I!^jBjzuz+k|~0Q$-8 z>CU|Oa|e7`JE3KS@wep(3d;h9HNuh~?Ydxc zea2)BBjbO@{l{cjFSNjhRu=NCQ4#^;EcG%*$YIN|^e0`O|3OU}-gd2RK3`if=`C|{ zhg^_QpUyO@#kWC=|G%OWuI+Ujo1D$^Kj=hob=Lc3GM%+hjP3qE=?r8(46uc>JoY0T z!U9lCk7em17+e3|X9pjkpgU+$bO|+hO#1=t(*Loaf5^jkU=i3W6wI+< zT3!o@Jg|9#i^Y7sS<$+u@h7Jhe+CE&8XJ_n!2yEw9B|ICVuTvTIZrUpei-*XU|E5z za&m;nzJ;lS9JsdPm-ob$d#xSyVun{J2h&b}3g(N%g00;WiS9)bC@&*mNXbZ(SASzaRu zbpe}B=t4I96f6p8(EYcUpHJ)5V!^D`XfGfp|1S4m>i#PX|Ek)*mf>H!`+wplsNfTXNtqvtY*GNTnrd<9h(Az&4`(7?t zCP9cISH87roH-E(cqV_YCn$6aRPZmunLoZMabcs8cxW?E%1vPI&{8N#SSuM%-CIW0 zsKQyKRBc+*b-&IR1S30(*)#U%k?e|NpQKdGvync|ob1rETaKfZ>ZRfX2>1g*2x^cM z0sN~dy}=i_@u=_UQYrzWaqgRmFB=`}`*!*S?y%HjfMC@9zG?thtARk>*&LNg9lF0& zIUk#*Lv?0XykeR!qddAck}YCpzEBr1R=zznu+VsWk+7qAk=Mn$cSw{w)F2f#<|Pj2 zj|GeQ8jj3)5KyTNgj;kL&TU%XW2gxmu$s?h$I-Z>2X>>agmCKH845RVS6r`>P!_pA zxT5fd2_MD%w;x@lAZ$M!=;)qDnvk?I65)MksAgy6afy04S{}tQ?-6(5&1XH=;+9^T zco4qg3w>AIY;!`y9zTqyPca`9VQ;$zf=$w&B@jiysWy)27&1RUYy@g_MQh#DKn6GH zh4hKUy8qXe&=g%wR1o4mi!H#uKh$eK~VI{h_U<#O6hql=~?_`8Aa&D=`vt`!W@$m0CL`Og*EZ*wG8 ztIaYZ$8={ErlYIdZ&l0}OBQL*9#{l13%bcn3?$k2jbiefC8P6iXRGXWKZJoCJQ$lj zhoAI;IJ)}&mlu%LJs}*ddBPT0KvB#DfRQtAIQY)@zHG2-Z6fV*v*o%MdB1?$Q7oQN z#W1ePoXMojzzh}reD3}t#lGMT(KZ(p?vfo-z`l<~zV;q!Z~@MeC*l_Xv559=3QkZc zqy111_KI+@c5mJ+l;_AcZU$MXbxxe-)7|phFTHDV8gflr=EcCLyGNbIh(W{|_l+@z zKgoWWo51!?(y{*7??aw;9yQJDJEn4K25`~4h@3GJc+GDuE znhb&5s!Jk`_1N^M&7M%Yq?7B#)T)!xFsMR`#eD+sxJj*tFc}SF*Tqfh>|T@$|0P$3 zJ1opTr@|V;tkd6J<^#An+|T@;Do=cx-FSWfE-7@yqC{S|ADYe#LxqTRAm-5Fra2Xc z^Z$8ArEJvYW&q6(zkPM(#S_~u=g(X3If$OiYc_s1$J{(o9+_4W&%LP7_KRba$N1ez z5~65OASaN#7!VdH{741DRLltEe_I|>)9o5TB4{&zrZC$o;!=J?Ep9be9QNuu2Dz9Y zH(T%YVqkG$`CR|9Iw;S4+hx#f0T#~YKR|rEAMKaep`q?#@lo~`%AEEjv}uEm-g9v} zbK&VgZ~SJ&JWXKtVcEcPMT3$@1pj<%$kEMI6h*Wzr4Av7b(YW6Huo(3k$A?sn^F`d zyRH4mURR)4bV?K*MhY9qA#G&p0kp& zm{4Y<(71|SovCbCXm^=!Dwtbb$jYvpzWR*^G&C3%J`ggVioyAl!gwP`usC03?9bqJ zB)08Ps8Z4P%K0`!o)B5@_|(^UG@E-ufQS2_#?q#8;VRCru-n*CbA^hzwnqQ=^$e#=r6JWq$7g+>YNqJyDsm&odnEg= z9~&+dhIsb-J#+dQL4r+uKqs9|B>Nfipp-()jPsUs0JU71{n}yQhdI5pryqN&&>|ie zdVTz=6k){b^OUyN4DmbOA0qEx!FX2n^w%;_S%Y zJ(ItkW%hbZhI0FJPS<`5U66~F{a}F^M`~s?sZMeG>GqFu>%-wiA2Z+BkiDk%v9nV= z3Ov@| zDsbEl@;V-Eq+o7QZbE-b$E(2<6PMAt|6RBobBo6gGxTsv|B^J4~^Zj z(X(#f)Ox1>(-Bj3U-j9jFa0RT+07qDlN^|X$L!%kK;#hr6uD1!bqwz7kGENVR35CJ z2{?>URr>ZLC7tz+PMjiHTr>|Sc$JK4+OEKB%$+5&Sqw`Tv+Ql_y>;K<9;FlsQ<*ht zy5#c+)n>kzHrJ@LVtx?{hd_n}5^h2?qoRoD*e}Qy_|*`y_ln1>1)?95$kltuEgH37 z`gbdMK$=;M3VEjY+uJYN9Xx$I?`!k`U-Z$l)b&doXMeoOgEX)AN4B?tHG3mp>5OjI zPO2={f}*n>9?dbQJ$UK16`1$UqqQgN(@;{KSpm#(?kv^}F626pCCg;k$EbP^#(*>{ z_bh>+%X7B?NZ}t|SoUZC-l$o+ozEMjVv>X?yjOarmdfMDUCk2=^=+dvtlKomI|*$E zO`=q&@n<8|*y+yOX>?KLD@Z%}VvZ)mv&;$g&DE_}zbmV}yA0PISBTP5HQJRZERXtz zZp^6QwlEoaonu1wu1(b?&g?J64`$n&hZ_C))$N^L$pI2rMmR4i)hvfY=pF6{O6T^hg=* zsYVh1Y7-*3NRx+*DSRCCJTafHwlP_m95f^DPxsm7JjlC3%CA--u=NPzk>j7M&J48` zJ!WxQzdc`2UbNO}(_Cv;zrk$~8EVr!zTKHDnlat))`!6i9+1NsA70i3nK>00%!obE zJ!5!(N%&*A&bwQo$j$}dTjXrCfQ0!hx^ZVgB2TJhLXGgO%<9@_!qu0Y_!9kj{X;L1 zi8ci}$K>gX8Z>xZm^Gx2@hjAbc0ak9O=B9vjC0)*oVs{5{c^0ORQ3e!Y<|!_%Jw*b z)&nQ+qoEity#4q(Nsk8WLKwrB3oAyvGHSId4c}w(AmI!KfJ`mPX|9Ca3J~<$hZ~=o zl_XBc3mac^DF+Xsyi*}9bW1?&L~L7FfG$_0C8>QYrs22>&v>e4=~AxEI&4WTCmTX;76>#^_cMFmfT3JH7DJ@QXY!r@U7mL;e?2~S0}>fh_um1vsEO+Kf1{* z$m-RLQCioj#)O_oR^}Q3&nS_s1o@jq{bvs9*<-kjo1NbSEX2hkxinjKxYb?D&nmneA1ibJ=f-c5nCh#KCE^~UogC+Jz(;k;Dfp0ULG zN;#)~%L&PJi(7bYR~o)%oPS|Yfz`YWr-VSQXBV?Cb69eH=?HqT8h1oVZwr7FT(|(e z@DAb^K14vF^n;<7SVyjP#aj`Rka%^i!Z7b){6u0H!wm2mh2d5fsBV!=1aF~D(dl~Ys3 zXk%aCdNwDz$+Fpp9;zTHBd+gNd!l#CdX?wPCDVDL-Y*oj&_pAA}ub zGfVutvtUup9a?FVSvk<1KX9L(-hxjNjPro&ZX-RG{pGF7Vh9lJuH2yh8CR)K!&)+O zhF#mJEzAprFQ(LQ7piwQP9~*^3+@~(WRN%w+ON6p#fEz$bKha*H4wKYFLu{p!K=U= z9({@**HK_QFQ!K`4Owv?zJ+NYeB2MWc4vZ(&M(`~XtijE+nDAmvlm_TI|w`{?Vo8wcf_#p;w z!6$>2dRK2%IU-5lesRAPI(O@>G%?jsi+c;gnu9-bx75G$R&U_Bw|QMZ$e)+&Yy*sY zICIaHr&<5%M~rg)YZ2gFR7y@&yZ1;G_>X?A5c&Lk>e$ktsdsgfHi)5qR{GL|#?>zh zK=)UfK9nbx-vn-9Aa^9TOI}eF73>E0bx9%G%cFV~T+p@{GlNt3(2GG}^ zJjh)dJXq=qGZk+f7px|3g_ ziX*>|m=ivmr511=0Z0}J5&`dXbIhp`kWdn__M49G9S4w&`dk_$@h?9UsqHo?;dxIe zhp<%SfIAmAUh-^jzD3=X|CZCTTK;$QN_tS~ncli$X!{}cCckO63NiHe5D_Lct;v4EW!gd9KeXYleQKb!ky(g-}%qo z9klCxJrBx1wUtXFWP7fOL5~CUsE43^d<}~P&#RG(i=+KC|#(-byVi&8TYY1fjRn7t!V01 zo-JR-5wtnaCr5l@jT8q;2UHM&(R3fYBE4g{1d*pF)kTGQO6p<_%pUbl$ z8TFX4ZcdwV@huvv&HBN9JzWXghLydb(pSi5zWTA89D9#Ch`@a6e}RMCh1>qG(EzWH zzg4p6t%JANtm|u=Q$gM~Ss7H785L`b_q`4WN9b9#(>@~|Knh{u3K8C5)!?#TGIy20 zWi{`4;(6J=WCXTR**sv=`DK7$)b(6ymAvB!2QPdz9V)QgLsE|oV8=>fuq==LJ%|_( z{?~|K*g)PRRt2MKWqqv=neJl9=gl|o(yLbD+b!!#d59BcOXHB%!WEHkg{fMpT8VOR z+-lrs7Z@_D0zNY?&QK79uiAegv-ywZfpei>t6T&<*{gz-ME}do#}d?2>|=Z6Rra@H8E0?zU^aGHr8XIFW2W!2TB=T z$n;w-Y}xNE@og_B%2dSo;N};S%rsVQ>?V|1N6Ea{4jVSz-!|f4NTiin@Rn;=Q)uIe z2a#!ka{q*uexdJiOtlByuP;Uy6Zs*x`|#$&Z80ZpfCc-|3n4SpqzPS5>FvGN9hJ1> zdXatj5&3}zl{m!C;?(tAv`_E=Pm9CO@EYJV$x%onUm(0D%ye+=D?-wm>n~%snt6q! z&2xL6&}Na!5UqbA+cYwy!47Mavt^kdvt%Mq6&@EK$SX-{g@;8n6p zVt7PDI*^D`kw*iE$(a902s{U%l)jO*wZ-`D2nr3`>O%fa{bos zRHo&MmV?~ODzLimkHOhyy{$O`LOv?6b?VgcFPA&?hR;TKC-1u!sy*R#O(+h}Qs;!X zU(9ztoMu&+8jt$5u1j6kd=mS_nzt`&em3?xmD^f0I*^k$zQ> zkG4Rw58Z@^)^3>0mtUSNZ`tZ@SKq96e!yjcp0zvV-%!sX5bsUP2w$WFpyeg5$nw7PJqi-4FBRUIlTj%w-10 z__W$k{?TQCD|d$N`Mip9i9B&ppL^<^HMge$c{Z0hAw@D^Pd)uVp(~2Hhys(y^UeE2 zqn;PDMz(3sbHsY;O+j#622?@a=P>EJ5!}d&>(G-K+&8n*MY8a#yCjd$Sz9Gz!q+%U9#TYgYa|ba*~jEgatP(}933 z?>cB|7p-a8A>N=)?K}i>j(C^Bmi=kT$a2)W{WB^X*=;A6Z@vbaG8u9cRim$BbDah9 zoUcBjp{b254y95B2bEAUBQ=}qO*dLJO26{z6ZkH5dPEMdl+g)AER_%DySfsrHO;Q1 zw|ld$evbcexg{Mb*2R@yb&h3-VW*n=QOQD9`8k=+Q+B#7EgMnC$7SwNc~Cm3$I%zZyT(S%|IfIZhg2L z1_aI@!BDXPd*NeXXR9HaNQLBAnb|_|UyQoPR5Aq}9&*d@`;7?k2WRWwcXvPh;8At* zJDqr9y=_Yh!Pzf;>RO4dG9y=72gEh$xFE!~(Tbv9Dzj_(c$ zS*_Jy-0ZCLFtz8GX?&(xt-rnIO%19p3gOFBQl~%DTcmhDg`ExfZ^3YmM&vR!q=OlT zb5y>$nzf$a8lTNnl$K9&hB3D+Cs^dAi03f{M%>&aZoJfkj<81QJNx#A>9`_f-|W3# zgsSk5>FTuC>ZuW&Id|_fjs&oin#Sf>+uMo32hh``BY7S7m|d*r;$^4s!k5HbQ!=# z=in7oXq}iL`KH)PkFWc(+`fdv;i5G{bAR3)p+H-#stPr@TK_U=N4xq9oqh$m`vtSl zerJtGj{N&qdCv+3p)>o^Un|TcjIXDbmPinVng1w{c&qP`f;SYyyl`1RiUt*#bnn0_ zntdU~a=L3D|7L=BBQJjFV&N79c(tX_dL|vp2YSAP-0IBBr3ILSJWh~#%CuirBwlNQ zEZ1`~r9*nxZd-4wM<4bcckek47A-od-V?m+^_OMWSzf>>N!vfp9KH~2saMU;^K8Uv zH3BGu3LMr9t56mclIUNp%0n2K7-C(=od&thX-_9vj(0-Fk2`xO(4$iD2JCIn{z_@% zT;$pmfEqsQvjqpYMH@2?vE~Ailo{%@A-pffe+6V_E_u^3u%0ecS|GEUh4Bd^qL;>-40FQeY^so9zHli zv2;2c;X(|>0SP~68qzKN%I!!cZLH63-ws_>uB+cXEZ1!!$ zIS_J~=TrM=uYV7Hqj8uo$Y&kK2%>N7i=Uz4x>pLR#SS2wff}t7KUiO!btJ;ndPTNP z=JG9KH~kkg!mmHi7C%?;rkS@Jerv8Wosf83Cwfb|nHNOFVZF9vHt_I#i?zyVHDR!> zhqF~Yje5DFsW&OCD}+ShDiyijHa=;He-j;UdY0l=@A60@*W4jRIfVkbQQCX+@+ZiZ zrKq^>M=IQ&tfLJT;l2ne>g*(Bw=9N+_kzUUWD@s?+Od@F?jPXb%M@UQJ;j~RfK$W< zb$Iyjqrk#sL^4)T$g}t0aF4pWuWl4bSGfO1-L^c#_^wGsy0x0w?zT)deYpDeu-IS# z-LcNYuTU$+WkR69LZ|Wm!F>Rvu>yhDc%-=lin9FCfKRu805fqS`@UN5ItauL>TbFl zK`TQ|C-TnAHRZJ#;USB@*PI}4V_US$)N-VuPHuR|N6#W*3ISL;dUMRzu2WqAq-{0< zM9e>Xu`AN?^e)OmFcjm@AyFjAR*x7yTb{2d4uv5FC56=EcA96!FMK=7mrc$D=;X9( znQD~{OHCnT>r;Q?#?#HdYu?p0l9C|n_u7jueO^&x6JevIK@<;|P=nvUvhd_Ak7Bo& z5I(c=Z8G;zPk^VRZ{I(swb=Z~V^ZhRpYUM(xP>H^@ac#G>2Zo%{t0C7dAC!BSu=b`7It%2g|qo1RIospN?MKx zs;Ql;6h3wYdG#J(Hnlcg*q;uml$Iz_Z*Gq=M>VGoS}ma7ZMXHp9aNG#OtpLd6;e`!_l<0OHL;peZBk6E|DCB zZj{Wk!^^aqjf=JpACBC!Xe2O?9xGjy>Wy3_HnNRa<2!wM4YF?MSatBlzOc!K!e6 zy;oLpYq@40tj4nAs^6MuT~%SggVXRoTyjH2^E(S@ctw2QoJP9K7T?7siR5G!McPmc zDCb1HhV64UqR##y2$N;};OVL_VZNVb|dt*SwuOQ?k-Bq0YyV!pz3$);0G5EhF2Fz^!7=Qg=0RK|?{}z@1?@-nsf`}IW zxF;%=!hw=k=P=@FT=tS7EfYhu;mH}u1+`6Vb{-gV>#1rUwtqpO?dgwyn<~p4pT^X6 z|DtUoFa~%?E=2rHGzq~`Y2XU#0VZy^%9xG}9qIR7%fv*=t8@FLA&1=V|DYc_X9S`97}SS7E6#ISKc!I{Nvmp^W13U8hcAIvi^7_)*B^ z8>GT)>SZ{X6Dq$i|0pB!xP~px%}p|Vm1ZsUZJBH-F&!QDIW3Nd^zR-_`4pYB;F+q}eLzF4Uu z%t5^^nI0G1V4_g`$Wf4v>?%?k)`+o+8tJE*9x5?Qka>s_ZwSk2_#uv9634gBx?Z%^ zIFzQ8Bv{BV)~O#VpM7h3(+5@(2?LL%U(K07;K&RDM=!ilSkoG;0YdtP%UvhcD{wu? z8@vVT94YL+O`G*wyUsH?Z;w0HQ7xsAI}2KTPPVQxSx^NNnkyf@I&l$Fld?i z4i~3U6$|T=J7>;BE;zNC-Msz4&u4TQujcTMQWP_gmhe9{jc^FRz!5fvg8ry7$j!9? ziCQh2!Ue+xy8=$R?UQW$%E*Kin%N2K*yU~oH>dXo9|6#!44Pny|3ablS=Fza9Q5tMTED#T zMqvEwz#&~&6^0e-^#P$_oDD34F(@0*h*~>BNgweG{f|~N1^1nb2$|N)lQ7}u3{3I2 zjM|Jr)e-pPOoSlvKzXO;hbWrinGR2v@tK<#CVu`MA8=`m`;##oj(e0ar7_!jfG$aC zRlhj@sCW+qrjlTL?{+xoV4YmCU;&I>pOL{@GGhS=Xdeo|kQ^#4=#-0`7tg~+DeG9i zy>33<7@zGqCF%Pfb=Ib7Vm$li5loCZ;Bm0L_w11hy^z+Oz{>rQ5vDh_s*Fa}F{Q&Z z$Wl^DI5QINJ1KmtI{Iyj3zs$MzzI5nk>O+`_RCZKe8&w^Y*j)$xxLK{vJx@&Pm+d~U z$^_8R4zRE3g&Rx^DPfIy2rh(bKu+~RVCKEL2D2=X@8H@JNd4PsZL5eSVIHCrWihQ95_Hd!CU=?hg8}Pi3yAlsJ;y*eq$?sFkCy~3} zZsA3xgkAF;m4sD6A<0qJIZCj3G-2Z1SOAopAaxW*`Ww0DiTNHaD=$|!q(XTq z9oH|Y;e2Ow7@_F&JWLeMUl9%1UB`M>$SNyW0nGLpGJLXzn)VL#eXuV& z(3%?#Rh63k#3n#5Q3iNy1Bkg?XITi28c7vt!EDkmD{+BhXaYOZnWiub(yJ(-I`XcI z6${NDnZ#4|eHbCZ$GSbKfk*=V@&{r%=9J)FgJM8xfiqAp^{2T9a6d)8EaAE(=Oq)n zKnQ(LZ)`04gXL<6G0--;qz;C+X@36^MwmFDMrDt1d4Zb>2CEU7yI=!nI-#Hxjy;p;qp`!&{0qapJH-n*6)X4zc`mvwQt&%Bre=P&xZL$HAbh z^#6>?dLG-(<`XSq&u5Yy+4S`?S{WW$=S2Yyfl!H(^m48m1V8A5o3ILI{0F6aEyD7t zT-bNa#qEyhU+5y~He0>RmzM!So^!#t^F(x1AZ(?jb^%QPPiZ^~KIpEs6y+R2K@=wY zJrRnTC!fZX^~SQYiR9!ulv#LKoe&oCCelF=vWNKl;o|igD~EMLZF;S-NZB zh9Cg%wBcy>@*jllfKv+24_ z;~thAdJjhC1|TY7C3~4HKv@03NRNO12Imn#W#;adn*b`^{}%e6XK-pI)EK!6%}*S- z&I+yO5}qwjq&9KI8wk{5dxCe&!5T-NdBOTtabQh|!yciRAhWj!tgBCmqW}yc)Pd{D zlUz1Xq9@<6kJuSn!#4fNC9K9~RNdovmmYwR-{tluu}?8&UQCwh>O^l%#!+0{R|e^3 zamHz2P{1-_xMQ`~ttJhgF2aCz0^fgrTSH2IhHR6=DwNG?jxv82^ftt%S;k9&x^9r5 zfFQ~9Nc7FD32a7%esy?r_R#q|d@q+<$7QkkcHKy>nx*-4WeA(){9vo6aJ!((ap8`3 zt8A4rW?$4XTaj9QIwiX`Q*T4iV$J+LXI zqy_(vfGq4}wbslW58;3wYk#@!fL_C8AlS9v6Ov|pqG}*e3*SF$0bc8|OgD9Hj=C-;?k*iW-s_vO!wLn{~VRKlv>yx$-geMpM z4P&eSDnz6A{XDW*{S`8ve5`h@MQ;ncj`78su8&&a5l~zIJGCwPLv3;7e}blh7;pk) z@||k(gZy#Gs^v1CBRD`>RgaRA)9HIxVjEvoH@z;a@*#-cRJL9){-S;|QEJ5bH_BoL z0$nxB_*7z&10>%2IQ}U!!}IFcrW2yR4Vm&d(908l(Mm$(Oq|emR$Q|?tbnAzzZjts z@BUB_sqnZoXjJ?Z3u-le8*iHsTgqo%h=Wz}bXEu24Pn%3;}=uk;Zik)8n#9uc4~$w zKSTJd66-}O!sD)i{NPwT+b547^(0S|=-j3$>*)}&+fs=PCQ(btNh1~a&sJpbraT#V zoVGD#Hb+@hgya+8fxVAJHRKLdR0-zM^9l-SfU8qAnNt^B$?)WoYeFYvk{U>sz_4ed z(cwqA$#X7c`dWi`P;SmI?FouUe)hKWlM#EKMQPJXeJ|1Y_Ur3m!Xh7OcLYg7vkx@0 z#%f;saQq#W!p$jJ@8I{?l6LPBbVBZtlFxZs&_ zvG7`{rIDw0!Z*NkI>L z-d|)$3HhX3_|g;juFCndSGEv+@zLmsfG;MZIZ5!K8@BTmFZXIN3>xi>;-BgHR9-eN z8%(oOMx{e})bnzkw_*V-J&s|O+yEe_@m>s*d>RT$D4vWL2|9D@(Q+0 zsl_&+qX^c6gN4!zoXb=N+)RX@FM=9zz3$6pUCSL0P!lfQ|1d45{8RdgXK!9$o_p=@KK$kw;kFo_fQ-SthIClw97jCh($vh3A_ z^J&p)3027Iu5Y`sT*qOx#Iv|>awRt%c`6&U3y4X6ZWF(KShCH`xbvT(r?na6?MO@U zido|xS%Tt*>cv8Kgb(C*POIzAX)*mmY>|be9%U4iQ8tgZo#>jmuUFMQE~fpq-gX-5 zj9b~C88zbhT@=>TMk|vBSLc0UI9<2&!18KJrXqp5*IIfv<~a$A@@apAe2-QAn+E|Ko;kZ!hg!(DjJz4!Zm@I12Ii@oL?^^SLrF_tx% z*~bIpIiLPgyjpVFCS@&~R7QErx$>`V)3v)ZD(iBAvQUPU-T;W_Cw+rpe!X-62<6xK z;Q+;&-$Rv*VQZt)Dc<)?%HZQxR}XZ8m87=nHQ_HyoJ}hQfl`snE)b-kh|Xm4J>n1yU z8a_Z3=s{%_uY6ORP3CefJ#C%xN`>J4+oYH~&9_X79_Byk3_Q6$Ibl@$f#r3=o-9YZ zOEB)xc*34Fm$(?qjDETePbTZ>TD2%5c!d%u233)>_eMiM#+x6_%1xrDP7qKUPhP!Z zUh42J1o{%@IUAjtc;`=o$z^fr8!8mSlcpVd*_U4C6qg=$J*P$xvz^CW3K|i%hTRW$ zr!YJ3<8a5u?UG>Thr*AsJd1{_=%2}xvM?B|CuCXbwy@`dcr9PoWn%*eqK3v*Mo5TF zvUkdMX|JYdDma}IZ#o{5B|T?H*720;&~NZuf`Aq!`=|+}f$tiO3u(F4!KGb~g~_qJ z)lNUthW_SQit!wWE+BfnPttS;+AN%a^01FnOgvGY2UNG4;~qT6Qo5=|A2aMLnQdp* zm%N21-nTdh9uyl!V_}pra*C&)brh-$(2etozy#LXtba^wUX*Sv4H(BOOOkx>>rhm- zlTHKGUNPbWr-sfq3$|CI;g54P2^t_u#VUiidh-nl>;`jE>RHCABKlvR=Ywa{MHX?_ z1TGWfR4t}!>$%v4YnGnDpZs`!B=swsBypM0&a7#)jNFz~nLW|RDxr`jpMJoP%aL1zNH(hRBU#HY%*5Ix+A8>5H4}i2RGzTbPTn&4(b=`@|c2nw+-|2FL zrIgWix7)%mV!1StZ%zx&OLYbf#$^oB&(n`iXMDDdUWmQY)Yl~;Zldv?MaLyUOsq@^wV4zAMISTRb3-q=DAacXI+#O(+wDt z=eJ8OcJbMySqv~N1ZS@K7QP{2UqEI2%!!(moJZwo-ik1CPI^=4eRK@wQP&55PaqtF zCV;6HgxHW=kW;*(6aI@DV?pX_V_~1e7t-lF2+NY_8se}CULN^msV)e*UNcWNI<(@j z*^>0QZ-V1HqpyQ$Y8@x5{0QxFGVj8f(3k0kNX=6@uS#=x(@bf%wFCvlf+&sF zAITACD}9ztDlrdcGo9#eW}A}#ZTtl|DdFIrY&HO?ZI5c8s&xbP1V3@yV@NJ`JI|ZE zU!c*pwzuy|)Hs8sLF`B=EqFMd2xQx7)7J=Hk#gnhGAOOh1Xv=}e0Z$^*TLL!1z z3TrqjF%rWU)*(23;g;mdaBv@LtQru$ z4leC)nTlG$S3xSBP@{fq)@!9T^L})mIxqDeRfbb&=hG4Q!oXI=LM}XO*A-Rtymr7BNl@dAZ%g z#1){vyEc2492-vD=cT;IYd1JjXZfjrC1p;()~;k)v1**S&?UvyVm_)*K2@XsTsd!F zvA(~qMow_#b=s;9BmAVK0A<+JSg~_7BbLCq)trVhqqCmTpk;jia9Vh?3Dijg6Nd99 z7Jvg`fU0Q?K&wVWcItCt%*cX~m%FUUP5`>;qvo>U7gnhxjsVtZeX{J@Y0{h?2jC5x z%dLTqE4JhJW+v|iuf`_nH+EX#eL?1qd7S#}}LYaBy74{@GnD{|5( z1-8WW(qbQCTPmb9`>bnW>z7z08-dm;qT10QgQ@7Ie?L2c7WusTJ1H0zU6e>$gz zT?*@U1oE@ua(3dQNdVer_1d3pse|fmw_1%vGE)}Ccn0&#BxmcsuSgLb<0JtEz^V+! zSQ1MuBJ*SSi-O#j^KIqo3~7tZX|4_v4|BBwV>Xq?Eaz!jvP(Zkls{IP#n%v|h23a2EWO|AS^XgsYb?zC0QC~ZZR zrZ(;zyXiaaTM^yW$)E6z`{;&jyosY4tB#8?HKro16)_#pNS0$4nyuB+h?OJBga+uk zthFE4qpu(hIIWS8%PQqMv$-bK`l-4!uy#Xl+NRxT;ev*BHBVaOA)!%`j*<0@QOjE^ z0rjru%adOD_6dXGvjNbUYDt<`i7wpOg=QRG-Lykg04LL<8Mo#E_ zvNq5CF@G5H1t^wL4SAH>TRNIs>D~(WObJ_dG-!&8ORs+eb zN}?JGn>1bp85JnsRAW@Wjy8!K_dGwGOk;%U_zO}oy}HF%_hPLCaf|)dHx*T(Dfmzy zFPBEAPH?7ATD^G!N$Yra`6A)5^9dSH*=GHZpP5T&0LoT(ZCBqbUnd%21J@=QbZV07 z%&Xj5vz_vhfNAcilGfxjfaJ~hAD2e-KkS$b3HK||J4&bG^GH_2)23U`b~W5;f!!jr z5tDJfwNZW<)w08B#j&H97;=}B9ISiy;4nWwQ}x{GekD%DgX{oQW3o_>rq9>JSH0%C zqu!)b&M3`I54lfD@`ZA49;H`!o!qFIz88KpwOja_UwE4mI)8q{2UNfslHwfwV)l@* z>L6L)>vP!cPKr;ynu8C`ocpvp{w_%JS(J3f|JaYxOK36cxt~t!bqy$f!>-q)awcen zT@lr`D`dLNTX%U>lbW?(_)u_}qhM)qIAb!=s!}UJiQb(dUE-5&TrLUnex3n}Ou_ z=vT7Dcxe5=&6M;pKjgE0tq@QTH!;^7%pp)*9d_GV!lrk?bE@z{}kKQYwSfa=ZXc ze&{uO^^n^ePcg9Wx~|L?Z_@3MTP9D!+2Vlwag#PyyK}68;*>6SdrH=^Oj>4=I8)Ip zuwrmj?ae4jJ65hI*U6@JF?*K;OlvGY6W{~IL7y%-DT$W#cJHa?{n^+^HzGwk0@LAg zslRu&A#b_Azqq~Km)wxG-i`Y~iuTJh_voA4T%Y$LX<}6>^Yp{rP}p@`l2flHuZHd9 zi1=}V=p##xl}C%Y;}8i6;B7LhhSd+Kwk27Z43Sub3^koAxw-O&?X=)jzx6F@jRh#q;kcWuF-NXCYx8`%xOX6xGmBDW;|E6SV017l zA(m)7={7h|F;%1QsCmEd1+uoGBvOY$g-g|Gt+9hG07Mfy&h3M>(gB2o*s!XFXNLLZ zQM9bXX9sokq3FbHg4e*S!c1P;a(#Mz?xD@&R4uO2Bi#{)Q`J2(Oa7=W&tGteyIzk` z=|-yGuOqI;r|GgI%gwYrZBCvK&kD)#5VFC!&?yKT;8+d~5Wm1O9OUvs3{xwboS+m1O#;0B* zgJ_&Ub8g6`a!U`KmH#V115Q}6`Mah6*~~OBx+EDl>U&F+)b*z^?gsSLsnzd8Jf7lX zgmufy73I*vJo&C;%MBTZC#gf^-p6gzIX{NpeSR3BU-y)-XPWNy)~EPS1OwW>YfTP4 zEpknDaov7l$aV~S)NO6M%$~5V6z-RVPJ1l^AYsI>HPN*R_X{g9Rx=Mcm?M*vQ;>tE zqSxoU)0q!rcW+lFADydITlkWV$9+x2BC5d&Pi!)vYGv~I(a-ue#av}u+vNilmrYr8 z&GzwNKWPqri{Y$d>+MrvvTFUe_^1}CL8 zo#yl>b-BT9aB4ujx@P%`x8v|v*-Ju?qO$`-8EhJKF*#Zsuq;*@v}QxskXGH=8YDH3 zolke7^qwC`dgV5J)b_kCLK~jP9|>Z18m<3hB`lB%^fgbf%0xM`WR6|frHlG0lC0n7 zNF>rqBuvvt=aLKDuQPOr(2%cbf?qS+M(@4TB&kk{<36m7upHADe>@~MdT>;^h5t~l z@o9~T0bjX}-jra>Wq1-T?dp5_cQ4&qi(=!Qy*IX1D?9taF3T8?IuU#E%o*=Y5GsvWDXSSM@gnO%KdU3P>+M_%c%??(1Qyi)h$sVkZt;mJ`!?OY z4Z=TlZD?DhH!=z?ctjfni>(Ut zqYsmAg7tZY6ej_{&xrehd+Yx`+-GyJ=@XAQ`D8h+ArxxYwnR#{${}cB0%x2cIpGhjm|?2TEoN2C5kt!EZ{v^#U<5115-t~p`vs*oY{5aF#^fBfL|--75dpg_$!~sJ|zBv)7t&d^$%0x{t)62-w7A{ zbV*p1^2B4&NfqKuMl`vcw>;C?9}B&fPWD#H<2@yC&5Xq6myZWyD`XW4D4Z1v#KSt? zL3@Z0hpxlotva0j@q34C@;=4way|WZj?L3{y$zhSffu{K_Sm)W__wCxcyWA#>&~4k z++}yB|J26XigajWxN>WEv4?I`%eA&q1#h?Y*+a_e!_pmTp`Xsv!rYvd$|f8Xp}sv- zwTld|uQ@N=l|T+#n?~K5alEAC)?XXBuqJSs7^1w8j7Zb*GS=Aq*@WsWbcj^v*m@5h zCY1*QvQCXm11p!2t);;cE|yWl&8_q7GK13+Ha3H^{|K16a|?2c=B9FO90TVzwu9Qa zYO%?%O?6>bQOApCZhlVTQ})6I3(iV|I3WboJUN8N!h=x+{sSiDz}V^sJ@@UJu~qC( z1D@es_wNwGBc^RYMzpq#9Os8^=(yOjQo64O$;IIHJ>kp-hc=bTZ7IFW#<&VL$UN82 z$uZOSSOo9{xZ#fVZXV-oQoL$=9i&~~Keyh^>0*S6by`WV-bQ40#2ChlS|&U4J#0PM zC@C>bO!1~ATbq8hRB`&W<|8j?HnCrFuek;bh2ifT3NI`oqDWG;5?J#)N?-R8!IYdx z0GE-CoxS;Ta9?NRoeF*n!Jri%ByOiF@5{@J=hc3`=e`5)Ls@*I#cW^MO*4HRs%zA~gC&nw=; z-ac$w1245TbVVAEMj-K-^Y2Y5IY>j@7oO!G7lvw4`-?LMtR9>+m4B)y9#0LjcTMFW zw@R0mm}xtFf;lc$LB}qj$o+4a#wLSm4-4bSlSfkf1bpt^Ujol8n@26|dAr zwo*UDHqg!k6Jq9Kn;X`{RS>x3JgTLjJ@~bZO+(lBZcGHtEm#@3;XtpNq_til@PIrMlCxQW~KGveW~pqBmx}H=nEZ8Hxs|6`tsE|!&m}fqs#!~ zae5zh#LrI-RSAb|^5gOkY*!wl?w`27eWCeGl#Fy)LQs9N0ov4qTvEWZbS#C9(~Y(o zrnef}T80n$H?zeS61$({d%Hgl98EuAZTz_nyyJxl@#?6$3xk+Cy0KxQ-rzO=qUKIv9Tymp#>puyk@@)(0!2hk40s?X)LAFQ~F+$ zoHj_7)jWLe<9+h-+FU3z9`80@56PoVR<5#bmCjO`yw-hA{J!db0|uczPSEAKzVOro z##a_dnxLmCk?8aZ9S1{TqUM`|B47+>Ylgt|tf`HraRg+Rsq6$d3UI%X?x)?>f}Uxr zVQikbB$);eiI>lLrh>?4xX}T zOPe{4U8gPX^4C(L;^~LB$$sG6fIOEg7fdlF@!VgNk2ELjeit{|<{do-7QiEapxdXI z@J}n|uXwgkkpB#mO#j!Wgb7Nezz6y8Kz zOG7l2<~zC^%YN5g#_-wt0SigpO@wOjp4Yei5jM@3h&tR@B2K<$qX3`uk`8 zUe(aSBR70osg>t(n7fSXi`x@Wv=VAc=kz|mf}T4fpQhw!v_%T8qRSAE%@t5ym=z?z z>)5-=x=Ar5am(FBl%C+BGREDiU?ej?F(=#sD+f6Tm|QgPo!E!N9;d z%lD9SsCFVi?n)V4iThkT;?QE$Hh!`yo!ED8gF*NoYZ)fG46PubsG_Y!F?$$p=s3Gc z7O|=UjeM|C5Y!|a^EB-^sx1Rz4iP_d8xU)3Xgrc)L_jGi=GUQ7VR_~^z6>!uE4^U1 z!a@^eT?G(ysIvhP{cxQ)%G-l*0}qmBRz9hSY?svi<3?M30RN+hO&BKqPchaGA?u2< z`kjUiH5^$IJzIx`v`mh;-=E|(ZoYRp5NZc{p0YI3SLvkgDYH^nIiSi6L1Wmu2Kh+C2-X2kT;H)ttn6rD>) z&)>tGi{bs8Z5zAK2(LHWfOO@*x{5~J#qsB77gLRK0nCfRGvbh2w9KWgx!Hi^HdA5? zLvNn2x6YiH3;HnZsenkRL6K==A&-AZfy>s$;_Ry0_O^bb--m6)(_a{%zy=k0h~*j@ z8e*Bgrr@pM4qDMrZj;GN=kbtKZFj7XH+8<^XYx2JKYRV%X4`P58L4{N%?AA)$CDfx z%prI>%;t06Si>46;>X1xklN7YRdae>++A@@5%JU1WQZ3+k8a?ynd~eM8p_{KoGn+l<-n0$7|q1o3p^Y zit6N#tc;j~(C7Lj81IgZK`mGNEdZsUvgzKCkwaM;>k4y~f( zyG180l*>8XP|v^E@odQy@ma7~T`i{YTBdOtQ&k&@XYEqCw!lZ;?eD9)nS91cp3SS; z76b*DC2{uQjB)Q#;{%4DSzIQD6m#X&KXcqBgCLR&M+2(Y0aJEGLa%j;eV zX~a2oeF?);8@tWI<53G&ls_s@cHuHqBk7l(8! zYL!EeV)!e4NH#jLRcqX&tq+|*)vX7eaGAf;)9;xNwW^ISLPA37ArywfFVzDdHC831 zL)5Z2B_y7swtmJbQqfQqJ^2f^da>!bL4$80SD_)1|6)Tfw&@B*hY55WLEB{U$Tm&j z8~y5sOS@hjLGOm5l}KCQA1m98R1&*ihHpU8KGCMlPHS7ez;9SQGVf=?p{F5a)ma{W&lo@NyCj6hYkIxcU%oHeJI0=)P3t>?QN*q))=!dU?s2-nXvS04*>w{ZO8y5neK0Yg{t z%nC}FV<8}j=mjT}Cth&zFEu@td_1qc9+|6go|vNdx?8LBi7%%dezr`xQvvFYHib3` z2LdwQ@7BJW;@`r1GsE;!E*z_wJ91gyQpp@#O(kmI-CRY9<;k4$e*We3aDV^f)s4vi zI0l`IG10WbT_Eshl8y#B@1wliPZZXCGUKwRTU+g1_dPTeG&zTCpGYjTpAUffQt~Ib zGgqmZjXE*lXq1A#=_h*4J%eTOqv+CO=Nx@@$u-u zRUGW)6`1BWJ-#-y0wt{WfQDv$%f8)g#Gs1l=H@Se>E$7{#i2m9Ajtu}{tQd1+#B9L zcf#^7zcfh+h z#&s_qklLJNAwO@&r`o(@9l%ySVBwe_l?AMEs`;t|p08t78;Kz@zYW2|sD zz6N#OlCH<^bba0Wf++t5&X<1!c+{J*_b&Y1<ydQrf zmYU@nkbFQURZK0&;1a1%=OL6#kUmBuZbY31YiH?Nj&LdqN-N;nca3NYR?62N%5 zEI1V~$x1SO188_<_|d>7wAunqt_vX7_L=Dekb^n52X;bCmF9HMXR8ep0lS`dQso#A z)lgV9&s(_!ec3aDmp^>70b%)KvFnuYFg1n7 z)2%-_+T3DdGzxV}#fbqR?$^IkLUqD_NLCaaKBydtyPe+j z(s3I8l=?00n-Bc%$;!NpFU9Q<)yU!2OQs|;#YRIy97|^ZgqLFIy9O&pH|NJ5i(My$ zwmsJbv;J{S{$Gf62U@NR3yJxU32LGP?TjFjb)?_!ccBk8#)DP}8 z*t}7_Il+IjZ1QB>SUrZAsF)jxtp?n$ITwulCEI(-y@-T5*mp3JW`=NXDcLD}S;y1) zzk0UE=!q8F@=g|x1P(YKDMq(Zqkx%+#XgdsGc(x>qegz_)uz3XEQ!qmRaRypxb0Vk zpnSM<0KdG8`}_Wl68T9C;o)Mp`WGGUb0)v7^CjpseYQWt4X3k$^_cx;lhs3@eMlD> zZ{`40w{(_X!d)BUlEN^vM>VnTwG@^H@#E0tg&KxK+R^Ik#UAe~?TsRnw#sI?HB~CC zk!@HBBX|!R4#W@9Lr@SH)g83O77#kZr304Rrqaz~9BBW-!) zEl#TybFg8A<+j*lj2ru-X<1U4xBAT0I`%xwv&76}aUMpepyT6^SGm{%MBj?tZ&Plt z&Mspgs-Avj$5j-C?W;C9SvM!Mj^JJ;n3Nr?k69_(o!4vUnbdmg3 ztPWh*n{R(Y7}Ka%cjI}w?Rw=Z-8*okZ-3z&OX2dV?rXcsV1o&fDwfM>*&di&o0fby z$a&uA)i{~5>$?h79@2$<-Kacs(EdV4)6}>?9wFEw>FTQo zVMcbMtWn(7!O58CvddZQOsq;>orR`5!Wu0|UoOzB-q3t=r>5Rjk?i`T1I+@Kokm)) zh+9r1o8ZpwMlnz3mQV%qP}?`^{PctB>hdr_A%6-6&bY?R!CYz>B#M;RjfbgADV0=M z`>GjGnTtA&1rh_T;6S$ZbC@RX{0OGZ7qRf>)!JoucaI5$3Qk-B2!QE8@r6*>Cx8MN zA%O0Xmf`Q=3<;_1s7TB+M5Cxix;;Q`&CTM$;5DwYLt*&cO6ImY=Z5mKWLXBv`eZGU z+s=+od1?Um-Z}+8txvQ$$8pXt_2N@uA6qS!85k#jo;dH^ZaE35sH&9LMfgpWPZ8EZ z8x|a~9!HZRxlXvQfi~Wz{`{^LT=K(HwEfrMjv|j-1WYvwZr{3@Ag*vgl-sWMvO!td zUf>*dri;4qW!GF9Xw^f;q6>L+ic7I4Obh1FPSYWTi+dmGbYNRdOJDkKC}@Bt-yp@ zfbwV02G@l{i3AgnU0v9p*2Y#`K!JL=vHTFw8GzX?aL5kAKy~u-x7&wjenv-?RQM69 zgY%R5ktc#}h8^L<+OJ-W6~}KkMR0h>Wg{R^Wm3n7UdpN5#ieJ`imvhYs*s9}<<$aK z@Ze(*8|sOUtvp!Q45Dj0lpG0#I7-$?fQY^l#>HKA(mt%i{e0SFxXn=|aCWA08z6N5 zxB;9L&%|dI;AKzn%xuhmwe2t_M1nyaI<%v;M(MK|)DzkB4(ORVlkzNTxVV@{DSfB= zfc0T`tZwkduqCdnkU3lEn0yI`!b$YPA9m={to`9rpodZuz2_V#!u0`1@HcVm*cc}l znD%;3Ie}tjiH|VGc%6%pE>}xK^VuEW0DL5Yuz#dkm+(cZq+3 z#8AkMo{EA-l}HE$C+u!g5=0MaXf6z0Xkv1?Q5OAzPaxTKyhOZX>-}P@?Eczm4@LZn zKZw1vtfp&np35`)SAN*#M#B~XInz4dh!+JMDf!1~YEs`_UPB6lW_U(%y4pNWMHk-Z zWV~SR3kH5^4=q-${(5Phgi%a3MR$O6upKFTw@f6=_shm=)YAUg%*}(FiTI z8}j+Us0l;i%DS^MG7@`o2oj&o24=_US72a79JlvqTfL826O)oS*84dCXoCbu#slJ) z8t|>i-@X8OOFz!HF;fhIJXZ;Hq)-DI=NJ;4TjT8rRASvu$xol6^WZ*Lk(;ByssDsH z(Xomkc83JSs|Ed}{(g(#&qP+v)8Xg>x#KDKo{Ljod=iJLG`ZtiXXgR zQlZT2t>NDMs*8rF#M8FY<-AR{rq8fdvEowF@?{+b@BR-i0PVKeAfSNYwnqk7$=x>j z`o+vZ!BoPD1T&?TVDe`L%#AZlbj7niDaYL-C(G}ajNWFGg2>;#0-HsK%gp=*`0hAp z5`Q`05Cn}FV*G-(sPELFzae~hhn@JMXoz1eEGFhNmqBv4UO&7S$luRHWq$nhDR(r& z@y0Pl7Og+hi>9E~m8pHm;V(>}NWuhx-s<;V3jT#+9W*E_~TRMK`G zvZtGNx`{Er#!DvqOvgM00jwKaA9)h`P4J(gfVBwu?gxs!b5qb^9h1&vl%QRPaSDRA zwY4o?ZI^Pq>a}qFd(+dLBWZ=^+hKKjE&>KNy_u-6wOYk0_ z-_MVTrv3w>jx}g>+o?LT-e&--lGpO+37Ig>{f=hA73EX-qTNG1<;mfQHRJpmRI2T?+Gv_h*7Yb6Ah^w&`{;2(?RApo*g z!}M1>M?wm66@G$9XWhQT!OkI*vX0WRr@72d+R!%XX z8v@-t&?JJBPaJj1y@ZqstozxUk#ahN2b8UcL7WfP#5-O;d|JQfX_jZe90)o~%>WEJ9*Hmw z2{6e^z`tp}k`r!D^b&8?Q!dd6!{zMlVRCw2vE%KJG1iKQKtmBu@&SJDUx0;xyhVxe zDF&9X#`QIrea`^}rBz0H@i2Fi?lZb=AnN)e9a#bgH43&R{zsE-f7fsIg8m&=feOL| z5rX{fMW!;J#Xc-<8)yzw%#{bd$I0Y&NRrLslmfUiQHxT_6-dZD%HU6t@81+Rn-oZ4 z$AzNdsWScYIe`nvc1(V&X#1X`%w+LVBIM3(sX4Zo#etn#gJ=wzu6tp_lAO+4^$1fm zXszOe`WS#rDj4GqU;z`aLiO!9<{~D*!w{iP;wcOWskNiXo$Tbc3$eeXdmQD821l^E zAISoDtVy7m`1yj7ktk;Y#1y3IgSkj@Ev+Y>jbn@_sS;_H(TNVh zXJf}V`hEIM%I>Znr`i{TC|4&l)Z&6g67KSfl3dO{0zfqF*c%W*{_6y6fY&pY@5@gJ zN~9j0+z1bNr*imDiG%Xom=``jC5TWHWXhbY0z7yA_UjP!*gy$wV4xueQJ<{+lK;&_ zs85cJk12Y|K6;U%!9>BmihoYtl@k+%&nL2Av)U_4#`Y@j-F8nLhKISorx>Y`5y^Ae z)%BXdfD^3xAG>82fq)V&{?#2$o+tu4MJW zJec%>C#f-fI`{~r8}hvYh?`L=>_+F(gA49x7^PO2@Gjqbvp<~Z5Jw>_8#_X6oy)V% zjd(V??x6WyC6+B5{+-%(d=&_tO1E9U>9`(WVWyfp8|<#nw5#2m!)<+x7uwGljr{&* z+Cbgz8*ww9@BhEF9;ZcZXnyj~+pcL#>98bfb6bw~Ym}(eFih3^3Ni8h`buqlQPkQR zgynuaW0KV^00qeesJvCbf>8Qf2KWaBu-|C)yRFm^y1hEF_+m`@f|wZn-5-bDYQcwa zwsCHQ2LBSE5CG(<0fX7ea@r9&Ltqn|4Y@SP^X23rlMe*pe+r zx3DF{OD;^K7;wyfsfvh-PL?K)SV-QG%(b=M!%$u6SZK7sc!bkwqykQkI-2g`J>cX% z0P6qHLxHp^24CFhIb`T=*w1`}uqziR(swnKWUX$D`x(#v4g%OD-fx2kc?NLihJrHR zC=3P9)hYblTFBPncQqkCeC+ec4G?i=;URg6?(-)iJkhW565F4mqo~(YyXCs$-T#>~ zsnXLwg5FX_2&IE_;bDUCtjo(=KHQFKdq#`eY)~|2-p6 zi-nUmalS%B1pfSo<-k*_1J*(Jud1Q>Me|MFd@EHVKq`{?p`AcrydwgZ*vWq6b<4p* zn#$T)on@Gp4{B*ibv|8_+jsbrm}hI)y#3$Z%8$+>`cuV?QY$adjqV%<$08SShKwfJ zmbmcC*~8VSjZLu4t~$M1{!(`EUf4HeN9%2q=UwxgD$!!b#Ho{bL9E30HH&TSd2x-W zi!%2xft6T6mPzf%WaGYZkwQ5|a*3_Wpg?NBQ3!b+9EJU-H;&KL$$o(r2&*CvmsP2b$Py_35H~ z&Ej;B4MpvkBAbPW8h>;AG?Y94f~3)#NsRtDH!Tws5<0kVD5JFMah;2>VzZf^x8|x5 z=uiLY-`XJw_zAW1eEWB()gR!W6JZ6N*2|hF&k85!_HHT35|9T@D&*ZLPtegC!&8uR zqjW@0;_nT>4?ETQGqT7r9EWZWrc-f!A0*ZxNmeh^f}wW{zJ~+@gx)dFO$m^7 zK|rs*Ilne>%`#m0f%b<~TX}tbLKf!5gBfcs06DMBACb7fgOWuC?tmsSW?=EFtRCPA z2tYkjztpGr8vXoE-Er`>B@P!Rkm&Qt!AC0^F;c>Slu3+?K`v;(Uj{=UMQg@&1JkFk zM%j|eO1P(gji^;ljq^N~RCcb%J+mkkdtdBLn0u-wrKX+OYe|(_9$s$$tp_u*bN};s z@84>c#^3!9pZ6D-^&Cbu++}kb*mzN9R#H>j`|e79M;|U?Y&55#EIW4*C=O_L%|!WX zXsxrR9|lC9KMKI3@PuIn{(J-VbbvA*`7b3Tl92V5#f<)rM^ypFGW03zD#PYL3ipt$+@1>3dT>_SPj zgE5q>jNb9E`%H%EFgazDL`=np@6Bw%TqZ1}0sw9K;U2No^STxE7}&4%mYE$#Qn~|B z?ay0b#>09_+q6-Qlv;(hERdKeN55rdV4wC>O-)U0%J*&p-Sxny(wq;Z*X&Rb9%||Y zb~EM26WIh&5HCbt7CSI&`2n{Rum%kT@*T;(Sxd5du?C zGn*`wEsuQfM^kdsI*xtp4>G=_N3p)i3eg%uucR0pr9+lF}(NjB_E>^3%|9EytNMn?AqGkg#f+g34h{T0~vob)N ztpXJIao%=X{{UDnVrK4~)L<5~!crlTI1Mdz@h$JF@El8nDwy>F77E$}i_bq7b&?y^ z*$vMT`D2)ipjcIax2GI8dR+LW9MZiXBK(h0e1x_@PE&K#zCtoAEI#9zXwAzuv?5foma^vyg1H<+bC-FN|FhXcPCs;Xyf1X5EUutus55L!V zIcjV+IVlI`sOJlQKlNr}jmYmdP@dWhu3~|L z`cKclqF)vd#vDOjdi!eyWiUwE?(b9ImJI?oH_6wO_}qZnA4k1{4sz^EW}WD zr9hoahULc*X$Va0Q?t zHG=VyzDH=xv1}>oBw7Widmu-7_#0oLtf{&89Fz+qi>BUaPx|~qjpO#~O^K8hNQ2N`WLO{QlfPm^1@W(kZO3A^d;oydS6J$T>q`6hWlT{O_1vJzg zc~Wdr(db^<>>Z_PZRfCoMD}|f0jTM_p5T#EB3}_QU2S$t=Ur-zOiN4qv|`FUx(uvM z)5CL$3kWkCB!Et^4Xh>V!otE*%Tc8s8qFHD-JIm36;HG(LSOj%S^!X*WlX-NJ5Pyu z@i0@~3w$9<0o5axg}|clRqspn&*7OIAy*?Yxd5HbNG{wCj7B7NGRC*aoecOU@P*iE z7AZ0&b}4I(nQ1{;7(l5^-{|PcYiXsMQHvhpfBnYEllih``;w+OJKe6VD=09|A&VB^ia5YIYp&GlHuU^NWGlVm^3SD(AhekWqClj z2UElXzjX$XhgE1a#0kf!>nKSPc($kFC+Nd&@~_%$JOf+MnoTJQl%l*5Gl0VgG5BUr z{G>iuXSr*i#%7jexwlS_G&!|h9IN90@S47b1hQ?Yu|h2(ad)@H}c({)aomXc{5c9x(# zr#OCUI7|=vCgL$A{)P`AAQ#~3FZ+Ym_#R;w@a>gsx&mS?kk*uwKw-b26G1^ABHx%$ zKLHeT3!B`a*7uer6@^7XqL$mC$2aq=j{z)l#)qjS_4Z;~WzRFqg0zjAmY^~+6oSU4 zlo_M^tfx^`HAO|Dj)&>Xo0!q3wv|RBHl4vSCM~u}-S{{D>jF~v@}GBt2bPoRyYpKk zYbUT8V2|feGaed&qvD-xu_lYpRg{q`5@Gyr=nQR zfzB(?90cH(MeZ1>Jvwn1mhf2+&_z)J0z%z`SXjOQ8Ob5Q{gJ@XRon3+p9CcBbR3gi zK1m}uS>AlUm4ky_;JmEZE|lY@{zJ^*`nCx%KnQ0&-&HHN@_V#7yRRuW+usx~GE^;F z$&jt}lqsP_6oLRZfu+4;@DYo#gB$)TLh$AuAUUXgnt{DlpVlo591xK^G&l9X-Z+Sn z23$(+m(ynR%(2MD4)q8#YTiB|Juwfqu+mPw!3jw63IclNUd9Du@~@v{O9Pm}y4x(I zV|ygEMDUZOq0B3sx;|tUZW@IJVN-+CEHovV2*Mft{)~M7kP`y;B%;)p2HUh!7cAhM zX!65F@S3e46c#WvGN(oWDoSO&+S0NB8Y`vh~TJcJ@{@-jZHz>Eayx^I_KhMyX*AC`l_aeO$BnzC`jak6`*5Ow90Y; z;Q;)jqw8$XlT`;K8^n`;kxwS1-9$aabwF-X> zqNumX9RGC};46@WZ1=>De5IXfmUxJMfAPk=OKOM*?7hAKh3X*8mcZ zo+WU?BY1d?ZI*yG;pO8ztGUA;K-lMg(o%y6g5*^DEk;hjxELoGS@n#KX z)cSH0Tnz30Gl_}+zx4oDgj6zKb=j{=a<>_s(r&8r8y)38Bhw}Hrl({&g0 z8vkz@0T-Djcm&*aydOhSnc~LV4NQOaH_u|?$&%iYw$GN`C_M=M#2*~|Ff}?bV4o|P zbGp>Yjc(JUG>5({0IyN)GlihQcu@1Q)SDw6_`QAkX?d^a0nFRvI`^lkl zO2tCgi3iZU(pW12Z3h6U=s80GMtgw8$$moE9$JGdBs2FrxR21hJj+j)x3DN?!U#ci=Q`Pqklm8(>pqBvF3@m;jy-_VYUC2jNdU&tM|0$=!ll~Yn1Vjmg*Bwj(_;w2l@K&yh4D9M-Xdzxw(M8kj_%Q zz#QAG-m%?ct0uS&k>+_1GBDcm$K^xD&g*i(ARti-%6@0~pEQenX8NS3BWnb3>WW|G z>EA3*_R5aMcJ5EfKtn^1N#afeWZ#BTNaT|4VRl^ph+B{k$DW$d9tFV>= zi!NhJ5;HEKi#t6|a>3;|m+gAh4+_Gc%olp@Pi&{d>tn1g08ep0eH&hWh}`<}uDhp8 zPTY(t9OP5n+;@iwy|P#Gy$%-sBggLwypIX>(NU<^YNZvbf=60VK>#ZT%T{4pUf3}A zymrw;{=7W-J922~vE`x_^#j{1bYQGc`70mzca8J)xlgSC5BKtT44!{z_XV3T_kJ&( z7T=8&L@@pg6j^H@dxJD+(_nz8l_Tx-EzjHV>i-@w^kS9ZfvJ;dI`WhT!3pCdS>$(+mqJQuJDF z4s3}vT0BG}CVgSodM+*d^Fe&P;4xv;i*a_S3DA|ZruRHn$Ex09km>I+9r6Ipb2kB*8e z#n4us)?;ie=kW#R=*fUDmE*{3X0GRBAm-HQC#Vwd zZQTCn$15A}FE_`0<=**AvqD1;de|Oh=qQ=46!8|snZ&7Ce`I6<+7kib3~9uhk=W*O zl*J6;3@taJdr0R_~3nUThx1?Wt3s@xT*=053y1y~sxSg+^&O?HPufuwP@GVeq#4CpaZctnm`& z-onjk)^(s;!k&?iL(G2&gJk_iH~I3*0@-;VAYXZa4hjWInnts4B5y;;=I4`hjMqj0 zFlpmfBoS}H1R(pGS>LRGBzOiI5Z}1`*i2c=nydZDrSW8IoSZJVU!IVW$`&j~6WvSI zsjDjj7>!TZ)}7>pzg?I2tS3Zw2c+u2C#;q;U)q_9g-E_f9n(V#he^mNCnU~9{V>mw z-aoOcfZrPZ;kuOJ`=|SVotop}^+digZXRN1B zRDPocreuQOC1r98y4GHYYXu(DP|;C)GLs;s=V@4QU$eAlGQWofZVel|0*%clE3-;@ zZFM;1Wg1cxLbjbG=}!u!LRw*17n1fb!%(04OyCmnYn_T zqDTUzspyhIk&(O%`ZrTDfB>lqRt9c?g!cgKPZzC75JK9~XNHBseNM zK|#0#ER;WM;agfA*i|8N+6P<`1Rky%?fg5KdtVLZ4D(?+$j_uG2~ps~^rA<$l3YoY zzOG!O zd`%881Pa&)&>wHJ-N>p52}2Rc9_`}KHLxX!W!wQO!~H!iQuUnWes=1>7(I2hotR;= zw%Y7o14#d-`K1bg0S|`0n7~H(`hJ1c^Pc&rCSPy?Wh|2}VWCn&I`>mSLnDuED(Y62J4p`6?x%J?EPt<@Cfo_h|Iy8Xt7ObsI`F;63NH#&esRkX^X>bX_ zg4b%4#L=CC+)?_pom-@Lnyjk;l| zLn@aE6!0xTGgbNrvba#%A4_F2GH{*1SJmz6T3l=Jf zdf4Kkki{kLq+a<|vesyzf{x7jJhr(@#(-i(e6iT_uSyMRu_QW~!Xf@4DeN~=YPc*= z3j^2ba6`B{Elz`)<*%hD(YEfv-q_e=cGBwacq;bp>e6-7 zF!iXND7A*?R@+8O{qn%)NpTlZcaQX5%UxFE!l&y zP}>ci*7Wa$t7!`xo4RVZ$qRmnkQ4XS9K$}qx2+|?&a~@NHI|SE2L{4b%Ctl+R7*%1 z%9tEmn!hc(KJXN6?CAbSKk#}Kz#tOQupt2*V7c5s^$0(|4-}&GyZ$!Y(8i`EN!O{R zDRB(-50hix`GcQ%o$mL>@NwBkE6Ku@g2TcjcbAZPMQx?{CYTE-sLaeRH*}xBKi)}t zxXg1kHkuxcNflX}I_K-_)4qPyY6alfj!%Vz%*NkQ;oen7Gg4CePNqdYT$2#7gdzH? zi%}YMX0(F=m-^J1o>uPW=GG(#Gnz799^a|K!K!PSF5=#&+OT04gr|Qf_w%KDEfpn` zOc7o^Ddh{W?4636OYQ-|WSCmZtS-0>^stW~dd(h&dD0@GH~wjW-ws$Y;Hst=Y+3*V z_F99$K%9509^ZvejxS~fAI~-;A4NDRc|VsAEr|FZi|F-lDmD5H@a#((+a+*1Zerte zc*bvHC%3{r9^S3U?Qc@u@5e{DE6UG^5#n>2WKWMGz8RbOm7$fo_dlVt4j{op{OXs{ z%;F-50y5wE?!n6-DCkUzSS}|<=`x`O2NMSOo)#NDMxPl09&O#g>~6eUg8z0$^+j+d zOcKTgos4J|3ZVG8z`3jewHz1(8@caoX@p-EXE^Nb?d|A3#sGkK$Vhw77axW_2<3GI zGDT*x0X^j#MhD*8^??75Wc&^FZ3D1~N98)r+Ua*1#B53qjE%1C%u9-^j}5f8n4n(i z?q!eTtm?_HtlL37qW7BG*B@-O4rD=8#x# zoE%3wkkx9_A;k~!8W5?$GaI6#y92>nPKE*l{MP0A1O@GwtG}YT2#8x*+LJ3q29!{D z+ezB=8pzqSA| z6llc>)_Ae&d;8$t#O`&(0TnHaQo{BY);Nr2oxGu8oH`xen?mGm55B*q+mB>H_pb&A zgJ>jK2M9uJZH;9uf%LZakk$eKbZb>i(WvwV1xNGt9?{%t@BBcD! zDwAVApXW9fhig0&m(J1~hLXZ;s}JhVEigE5j#bVFWLKMEHB6rn8vXKmkUhMixFPLv z0P&wc)HM}nDT(tO(TcbaOU?3CIMUKX5*)MrGPLh7;c6>QeiOidM6@GNfjX?R*=hm%q`DybB zb{u!W0Z>b`U~5SC7X6-ykwe2Sx>#51>k#DOE0g|}BBATKDd5a^n7Q(FCaWZ`&f18K zTl&sV9@Q7jE*{Jdkk^C3a{K~YZ<0v^LvCm(D`P0pZuyqTpf0?;ygUiS$>2!5Y{=lK zB17aqzWV=j0^g)>M3i{V zXYEd~^+jOv!r%PB!D%rO<@O@C)U@Ct3Zo#WIK`bTe}60u6xGknW&T(iF!au!X^1Ht zdaM4IHf(q1sGc)zWPsDv`$V<_`>W$6N35Y_W`x3@+Sc2PRh=NB#+_yZCBWioLO`G! z`DI}e;i%WRHPGNzeN;8FbnmvL{@YIXe}?u2LrH(-7J%0eQaJ_Jh@w)}`mZZr=J$HW z1&f+udBz9i2%*sZswdGKcZL_F%zh!jmyJ`TA7vEn zP;h2L<2%lK(9k3|te? z@Q-1lkG*>{aVOlS$&Q?&S9a&g!FSx+Nfm{u?v3Gk*5f^LDAJa`{w+zM_m@1F~NrwF&LM66?Mr4S*=k4*-_}XFSCG~1^SvtMFSS2BLffcocbG)+PJjkKIq(lEJFUf`p{>8m>B;HWOyzvF4LFHY{y&EcTP@DO*48-IRD#{(GRZ*b~fT& zq_-V0f}&3!$Ww8qI14Cgsfg?!A-oRAH2CgJ{wl_FS#(B_mQ6QkRMhbX$LDhY-t_?` z*$eh@J*q8#b5iMnrL;9LXiLP13IPcn^8D=W1@W5Ekfs9yS~@!P zvS~8q_4;B*5CEYutl} z>LKr%2s4s2?YVS3-=1o(Oi0vL73@No`vF_ZUz^&ky6hEBLXvH{P#~je@ztcT?mBJK z>|~Vg-KCT23Cvy@5vpI<$0VI8KgY?Vm9&cABn>cEs?V(X{OyfJEJR2W99A95QR! zS16Zm(1aw1ht$0%SJ^7|Td|g22R+VdjRgNMhm6t8z>&KT%fC$UdMJU{=xYjoa$CiJ zGk7?tZ;<1NiKLJKDFxlcbDMCE)>m_E{YDsS>0 z6N#?J$XwGxT|^&T|MF9X$ph-{)5Z12>t^WrfAAQzOU9V;b5v3|kd}UO*u%pO7dogV z9Lf3}V?}0&Ft({)j2;^I`>=})a!M9144f5qcJ^ZQUXo7%#eG8sjXQTh#BpCA3!Y@& zDD!@Sn3|eu+TmxSUIOB~e4V2I>)eH}uLzLfYhcl+-xIBFYzP5tNamI#mf~08dM=t5 z9Zt7>M57cA5g?61mbPpD&+uU2UtR+MO1vHN+aHtBI9x8{hZZIs{AVI9Cme1@*|8{y z{F+{6cL0K=B%j}%q{xDVo5$z&4kLvoVLO2HtbTAfU~v9JqkDT9jc|>l{cp__sJq1H z1~&qBryvu-BUeOjw4zUTv|my5(;YI$x}(X0Fr6Bk@{`>gJ;biHwe1&&dU-q-b1^T) z_7|;r6F+e#q7RDYTcBtt89*Q}wfzFhV$nd=u-)95WiT|5E#+%Y4#Q>tmy?sx0Ds>W zTWSquCaBSD+G%g$zD)EtpsQdes2J$DM+@XKrgz?sVtc<`@V{-hV0w8eNc~ zt4~9)gUQUvueqnDwq}gM`>9!C&a2A8mH^5UD4&Hj<%DrxpLX>#P=RqpwJe|D;i8oY z2Q%mAD=I1F?3dEU4iEO{0cA*GR;9#=5dX`o#ok`+8?Sb=Q;Y=vCqnc9**f}Clha1$ zMMh-p=V3M~t-G#aC@?nl?o4BRK|x0sb}$*qQD@ErNH{}jA<8Bl8FgCG_;y_{A^$== z7=Jhp4PP})Wf82ZVMQ%Zh}^vVxDX?}h6WG#?Y?ND{Y~_|2s*FAze13ZeZdp?(`+B` zLUC?@PIq~9dxRET%iYV8_YT?n%6Ro6poptTn#dS)vi0?~#g-?YsVu*VEPDr@wehQ| z6F=SaQC=b~zAIe0axe9U&pDV_ACaCP*bA(mq_5)xU{KclU}sCX?Pu+Z0F}=2rJHDi zikE&^I3uTeu$pLIkAJZn>K)9RjbGn0m|xY)mV%@BK*u-}j%7wgQAD1YRVh*a=<1U) z)n|IY4uf?{_YUE(kOQ=C#HDWs@wGM8qf>)%O1f^TNft$Y3nS^@IzLjeQ3dwMq{;Al zx60su&&*7NA0fy;orOwbv`U<~UoQZgnzW0l_Uz}7iC_;xJW54BJn1}U5r$5g+)V&+3%h5M?I*tJQJ?FyFqVlW64?TfNRsx%L{(TW!bRH$0OsX z?Q4*-X+Hg8Zef)Rhen}rmOyhD&l<$G=)_*q@`My@=aL8@LEn{nj|9~BPiqtYN-K*7 z6HF_urtgN*SahCvC`$_SRb7lm598q+2bvwv51inh&K9^WokwaM^2VF1h0QHaGFGgX zY^t2cK(O_n{4%xS8sZhPCAkbW>rtJn+STCT?@p4(Ld$1TcynkLUXjamFJM4vJO#&(|#Fsvt94TCCD zb9Hrpcwj%g-z2jz9Y2Ida&c?a&;QM#uBszS!RPg(k$XP4d7gnN1k=VX{#!>!@aK~d z!M%;MsO5}+Ni!CY&eX{It>_zDVP6R?WOfEA(sj$kP4$wTVo{Jbc1peiK=gKj7)E^e}@2hESR zXVtc6PU)YY5}Lg{57`pu_s#FS+g|uXjnf{U+vHiw&~1za9?HBg2`A-LzaaD7VI@ucpxSQfC83_IqRAB5sFf#!1zACjLnf=&cv3Aj z>X+E}K5yB)h{cj415Ob4>I6CAwXaUlm-RQ5;qfrf|5wd3Jx+3>_k??=vZO0pL6C6IXvzYcqODq2xs$c?`uW%ssbFv6z;yXT z-OW(Z!qMmTCTF4Ig&=^eHnZ1&Z&RRRbwj;-c=&a%p}NAaK9^#(^$1-vJLd@T|3m{Y z2>RE+`r{|LBP!JAAN+r}5FGVioS}&fEJ<<)H3f-d#`?E%LbXxK()dJ_Meg<=Z!hOq z46jP)5sJgxQaEp?(+ihI#VX>+CpJZBC@ERKam{NKmS%mYCs-6eDtSlXgGlFdDk+1T z57epYYRsvR>ZWQM3&IOBSV=z_q$2X&;@0CY7MgnP3rib@9EWvaKt%K5wDUF4;3ywu zWTe+H2B_lWSp+!c%#Ku)loTTEzYOMQS#;CF+VSO6TK(=kdfCu@iFurpCT8;D;-0?_ zWeqO2k-qbJx!_YU^x~n@XozL=Sz}T}Gl?`B^(br2g1Ub>O@9%|T$}b0&^Ny%hdHL? zPf7a8e?y;~E!ui;NXGTcAt7*=_tNFYO3nx?Ou`J108d&AWkN%Ru-|2@Ra?VSsuP7n zijWq-!L|s~_LT-e4m7uX7ZhaRHQ6K2;;%>5kQiVCGGz7pFS3>*0bMJP^Ks}{SduVN zUq^?R9zLT$_8js9=aLJ=W(^HNFVU{$`?J*(5;`cTFh&fowy-p*D7;L;%Po{zQoH_} z!VW`?dCt0u>tSb`oa>{jM&%t!@x1AdNI*WXM>V9EV zJG0<5wo3yuQJ6OF0ZX`sC5cX5`lt@)-to*zQV^r=$zl$@ReKLjlxCtbXw3~7z+oh$ZSYJ-N;hn8z?&H8)ci-Ruc{o3VoNW#dfrK z8ER-Y5j$6Os7iRGYz2Kr{d8ifli$zFnSUZ3g|Gf}f>~p?AZOMCoCM+M*h`#S8oZ)>egU$V(3D+d2maV@bufhABE~ zm_=qRp@wrCu@+oYQ^a0GcZ8g`?w^FwPx05K(BN4ua7```8@&;^`RVS04dKt%cUXl* zI6mo%9zChtTtJmJKqg zF6!7#H#wb+%>U4e5uxJOY6WUgyv02_Xf%wUxx~{rD3=r z0q|UIkAV-OCM?Rz@HntIW@AUiJ99+BUr}+EBev0Ht$t2z%1{8Te z_oq}7ClVZbsqD2-1G~HAsklF=Xg77Nw?j#Y{p#5B$hV~qg=p2q6!#@3rA|VP%^wXg ztCF%pPvMktqdOL2A2zuVI-?8ixpXWqKHuIln^A*ekwoB9Y*e za7{V;tEkLZ&Bi@HUq3=on5f!PYd?<&ciu%RlVul|e}l%W!&MnIKbysU#b{zlK@EalcNRbyqf3g)d;so(*yucL*z{4qqcR+Ujv5V0|=2 zMc_hk^EU4fE39gXAgQMlM<#JFY7M=}8cZF`_mN{1iICiE2+N#EA)jATWVF%fqxsb7 zKlNjc;rQ>T-mFMM?O!r~o?9pXWX1lt(Z+UMo`wdZZxZFa1G-0fk7Znv1Dzp?SHDuqLo;(28MIQ04fBV^G9pZf$W*UB!s;ZOa z&>KY~zk%#?(Ig=KeBAazn1G2P&zRqEmrwXIl5tT>Kk5%AuRt1p8+|2{M;9#OmHst_ zJrq8@-iRt996p~JdS zuclBE>N~1r0#zEY^yn5B-z~w|*CBAXUK_3}Ax7yzj~fs1tL)GAtKP~n!fo7v;iTb$ zO`}?m06?*sSUT>~BibS>S}6bwpy&15ZPi3IEhr)i-J4F(-Uw7kO@Sr~L(Lz`vs28w zk-Vb$Wd%QiXQq^T9#-s#-0t%m+j^qMc(9zZJ;2i3Tdzmsy=P zmsD(FN*g%BHY`P>irA>sNf{HaO@;$0<9mDaTwV`Q1HUHgMIf!&prcL0Cw!{EoB0_fb9kUgYd31(hu5DD zMk2?%%5j&;Tt0`${_6LO9M~4wckM}9;NWLg#3$UCN{NN|Xf-C0;O-`8R0RQ7`IYc7 z1-LTP>&#la}Xw6jHtIH$H_$!DbKAkX`Pb@n*Vx6$5!a4J#K7TQo(DQDZ(yheb^%k(yPF zjY^;#Dw(#{RCMl)tgJ|{C%Pgxk(tMf#BW(`uX=vofj{E3@OIBqyvCMH`c?uOgOKEbw zdp(*mi+655DS405Bs*rd_Hu%cQLQ^*O8mLvvbA^0;P}wLso-{ z@)Rd^{<@Yrj;Sv%;v*w%Y@!_-A))h3*}Bqb<*H`wmF_cJIMvhSnH=BdoY%{NkK9vI z!!;7w@gQ$~@`G*Spy9!M&9-$ghU&T0y2w#8vtjc!CJ{+%@ld6c$DNCbs~TmuFs?`t z)0jLh$M>}xd2}3{PX%N1jqX6#YfXeQx0zv!mU3pQjR{6s_>BpABT0QVfd=FlT|S0C zgkKEGsDf~xvV--KlwI?^0>ozkIu@;pn>ymrHNDvBY^lq9AZ#whnGp^}?LztThk0Q| zbt{~WCriaP2`1J6RZ$EN{K-{hC-AICL3 z9s72VHwRba5yzLoizsG>^(f>R%nx?6RFN+^4XN56H?G~{D4F`PIXq9)=%-j}%=0ZP zU*>~&+2zbmANU?Cq~}FG5@mdWASV7p%{rilNlxC?E$`_`n{UaKH;iA@7TeQMTPp*H zUd-tv=_DQD&dQDpeI}&6F<6-i6{6uI?8~9wuXN?YPlLPn{Ke-*+uZ0&E37lx^D?pz z%kH_=NvkxVJ5=8CdC7jsI_>KdaI#d-fC0}6d3H`|75fFE$>^UgwrGYVH)KPdT-|q zaw?g41Rg%7AaZF^zHs<>ovwGiDkoDC0_foO!hx z&QP7hD9heF9_jG2N2tt}ma^9$WG@s(7cyYRn1tXc{aP&`sAXNyjuy{vd}LFi0MOtR zl+Wajex9n}zzXY=>k4`#WCLM~0csvU;nQUth$>^Le3+93;gS@yRg<>I)OpPbq*8D{ zT!36V6Lqvjg2I!`h{K;pe!7yCKxa1_Mvc6qR}P06IA<6W(P5!qXry=+<#`}*A5dek z8l&E7rWom@t~s4{QNm+Oz{<`a)*NR@q%vqJY#!BEgd{`wo>;^|M4FOEuQ|Xp9I79u+|9!UxezPIHVO{knrAx!6WfwtA%W1VjZ1b17##eXgMSGr*HW0 z4JUbtd97zfNikJ*bi`+9sMSo>N}+0UWOaIfWDyISpORF%n2tQv7RE|1} zVu>ckn2B>4?b;p|ScgAJznhzFR~@!AI2bVkwW1vkLHSJ_#v1xXa3B%kx@`pAk1IeI zzBB|w*5^8nOXuR2-EFIY=_w~?iQ{~DfV@`_Zu`*fZl-8CmM)44Jk6bXFlsx9i)-)? z&72C~z0+2|0pNN`kW%^XkWv>gCSoteD}8+2*nRMkHxNSc>Y>OlG!XBMiK|HOw};8U#7GoRc_*w80~LTRg6?)G zMg?96wDUBaR}3{K%+nnXGbH>|SscJ~8FUvIOzV7AQIqqh=~v?^fXYOE{I^JohC8cv zlWinD!E$#;HhzEjk|5nt>gD~P@Tb}SWK9#<9PtX#nOd*8 z?s!cV?t)=ccp&|}=g~T#hw37eA8+XD?y<%B0fkB46T`8OSO?t4autSRQ5X~$`tCUu zxLT^{nvQmQJQ5!t)DiMz< ztBLxh-@!-nZ(KfNk>LOYkl&*!23D7Keh7S6*gQLPd_LHDH2{kR#ntkcK{tgd^Unch8b5&PBRqW)XvI$-&J^7q~NwlPHWkJLF@{QG>@! zl|$J{M*R4^+o6@P@0Gj10@ejqUQ+bvt`cw~m)~AQLu9T79}2XDyP>%L?|^UXqO%7Q zvnBoCvjmm%Rn;hWD*Sv)UiC*bv8FqJdkJ$l#l;=BwaC3r&+@?_AlN8?>9nDkECEn? zk}sxYeBhxZXCh^mpw+~B_QgqkI%33?x!r}FU=wv@XWBN$@5Hg5&ulHHX~9z@R%VJ_ zksdlsJrO(Bi-LA>3R5M6so*vBCAkp7>LK2jOFxvk4_Ytj&bMZTp8sZ38&$yK`G35} zJQvqeTF>6#2p^FeHu$(82O->WGdIF#jJeEW(wX}7Q%vJ)=*zGkOy^ljn#MqeVJn9& zD**g{KXG%AIVDOoeD<1pH;nl87i1PW+a)@9R(`LGh#Gd^$^g_UO-S1XBfbM3H5Zox z-E#tT`}1K3=i+pSUCp_Dc3*i`WmxHj9bCR*&)Wdh8-oc9nY=1oqG6Z)ePK{Xp`3&` z-#gd3oc_q==|_<(X7}jiq2)bb&>2;*G!^8K_Qhsmi@{vEhz>Ouaw0Q2g_l)NZM+{V zOX?qjl&I`iYSmi0%GWKp223D~(&cq4&B9 z%@9#~%{TULx?8Z%p@~;TlU&d$6LZhJwy0ZEnQjt+|)M6)`Pc^?=fazx{!BAb+ zZ)PRs_!XO)-_APqGs^J_+HO=+i5QAjW--nZ6`K8}LEeX@j_wb^Mepsb@wnZR3M26* z6ETY?N0LHDQ_f0spBB6Y%Fe%OvC2p*6+l;1I}&fdw{R$)V&&WEGxR8ne(HC}B&viQ zJB8>X#U#S%7EDhW&ac#1;3^aF-R+Y_JKmCjB27rou}oCuK)5FP*x^Pfnn^nt85Wk4 zp`-sW)H6BUwh{r+&4y}c0Mj%juKp$ekh?%SQdvEC-lEs)$coxaiap$$RN0K;r6qRd zX5D;d>aP*WyLJ1y;)_FT4`%SJOXczTE^_Id0P(*cWnv!vP1;Jd95;F*b59-zZeZR& zT}1KaKyrUC^%{9TK&E6P)|bQA#M~9|y`3k(+)=&?z33`Ao%5I}bR5*^H}c>hDqVFP zD$c`gdu$vw=y>;RX_lPREiDs_9& z`^2!)_#Ks`ld`zrJMUlqq5*H)AlK|z^y15I9cqzUPl2LPn2262Aq4_S{2CMXj^z#F zB;3XjWBqPvXMsZ6gx4YNbMsOKo|0h-~2Q`t<^oEI%EHn8S>V zRFhWGW!ir4wcHsFd|kL%Utj50<&a{EDI%1p2)_e@R1#-8mSEYzOyXCsy)_eqzlZjF zeY^?Ot{v44q#c|WB@wAlH*L=z%A_RxcXijTGv4{jl0CQ=gNz#6Day^KJdBg|{A$z$ zZaWy}MI|Iw0!_IPT|xWsk?L)E$E=Lj)N_VO2j&Geg?_0x2YdU06a6ix#t_0&*e}s` zA)VQo6@D7^5#+6^XCfPIb1dKnYjYd4f}h3Y4>#*iOJS-dgO}2u4uTg${m?UViQst8)FcbEItK;jXwi$pvYAD}Y$ZoMA8i;7)DW@J&zl z-wZ1G8sXr`Cc(kk$@S=CHP2Rmz=UpAXC}{RUhPhxV;e~E6sOL7W0{9nmd;^gv%(qD z@X1$+U;)ocoL1-7r;nT%*E0R~g$|TGg>SB#=n^`7GS_n)m|1-tE*l3G6a-w!`mHk_ zdVnfIQOJaF(G30`ajI6OcDuqR+Q;^^96&-e+L}o?d#kuUlk|kneDT?v?fvVp>PaqR z@y}|KBKE5hSe&=YeC6(KH}hcz5fvO%%jcVQ4^v}MIY|X_n!hZMhYPgjMhfer?5M3v zN>z?`TUww)bTt6JfP-r56&`o2CI(CLwLJZn|f$$AX_5{ z)V>5qCK5431cY2YOxpgi6Oeb=^`pmUKp(8?4YOze^FK{3On53I(94C-ODN9%J_ob| zdcNNCh``4EZJEvZ86-@6`5B-0(*g6<#*`(-E;e3RfFp2N|CT)pZ0uimNCDiqucuY}Zo zd?L`>X60);%5ZaXUr)?sp{HKFfC}m4KsDE04)K*kL+!`ru_C%Uz6KRW9d;du1mUDs=hpEmRc&eZ$lJ4a07k|89)r>rK76 z`N*j*%n-4O_4gXY(wa3fKsO4<*->MERsG;3tHNy0f8T7_v+{IdhL0Z(6dYz`4$)PU zqTlzBi_;rNu`ZTiyB&spQ6LBgdE94pgpRmm9hYQ<4vggDr)^J#9_`k2&FrceeOA_kL-!20869EAWU@uA5dyqI$FZ8;{ z9|-cxf7W|nv4F4g!wB1LC)XT1D=x*rf<_K+#h_i+74t?@G>@5TGVw!J8Ca-QO1!6_ z99{wQ_bFT(O8!X&1yhKwfiKq+Q@`WTIq5^m NzYJbATO}4P;Z}P)*9k~6Vau}gN zC*VsdCWIn%~aQ+3A!;hJEr=J?y5Iew~|`IqX~M~(~XJi`d_ z*H*gAg7HL=j=DBp_Y*aoUJ)lb%#0=FeU2w^%?4x>GsBo>cMH{~Mwh90Wo z6=x6d^=z66s@atvTxzp7=dFLJD(Yxua%V>~^ha*|jk}ZAph8qwSl1=1!4jZyNErjc zrb1BGA+U&vNJJ7MgH%HvDmWHAF&b)%7G+E5e1e+(h*U04w*69;fXNOx=x#f?#dlLLhKESz==CJh}DOYOdb>mz3!8mqzSY(O0-EaHGGuVlN8jbW7f2{`bWHv;<^sZMrO$H13 zL#iK(OAi~S%+brh#s0jX8FQqKSMq*;X$(0(Z9i{*3N&jz|An1Xb&b6IwK`_fWm=LTO5+7 zp$$w|6DH|IeaIRDmYHGD-VMR^qGMDGv_D4cW{>NuzpTYD_l$>2X{h&5J1;<%W zgHa+_HG%e6pgAyfUvBH!u~~>tU?DYQ;cZ>8f&6^VmC9wW#)n7M)AT)0OjEb

    u`w>5W?+D z=_zZ{_}2r@E^8}_Al@E2xYSN~U{ z`u_iLbrn!mc1v3jrKAxMX{1}aQ$SikIz_srIiz$WE!`>It)zlCr6_C^0OQ!ps@mWZ9Dmb5V zfwZ4wVv+vdVY{+3hbZC>&fJMtfzI>k3u5RtjX;6j*Rr_th@s0LtG?1 zYHY@$h?fR6cSv>fVHD=r_FYHNYl{Pw(k_6_)s* zyuKz8Tpd>M2r4K$b1##?cZMrz{Z>Yenl0W+p0194<;l(F@&jKg)xaK}?Eq<(e7_}g zFOQoLjOEeyJ|BY~sOReRb62C3~X2I;V zJb_E09If#^?GM}`j63rgDzK$)D|7@;j+Ck!&qD|i-;c$|4}t^_wQbi71|oVN_v=V7 z_)e?3Xf3h(*PNLR1imAoOsK)>O(OnTD)I#Nt*iFF44#vGankF#o&FeI9SKOqAAx{t z+OVZQ1=x-^Y@AEdJ`}GQ^1M(G5YmMl14hCPi2>jPMlvPGOR{9LbM~2WP{i|gZ0xEq zgI2CSmyo=<+onTduLMqER4v)fm1ucw?^C9sqfFSSqi zJum4U4l+NUIL*G=-eb!o$7j2=T4ARkWOO^B1 z{6dc%GwY0Lcr{;yG<|ePo?|FD8%=k7? zJ*+Gju=LgWw(x>2Rp~|VX@ESMqGj|q3b?>Tx(pWg@;5>o6e1$452oVh)U=R0%K?7u z?=<$LKv+;fO+fq}HLM_vyN@OQ2d<^Y=fW&RWS0mO&~s1&B(RD>zRKu@&3ta7$zHO0 zOp>ZlX|pM|3)rsEIG|@)6oK2qUmf9ozH*y_wKZ+7X^N3^JI-wwYG85?*`n*&I5yrd zI4g4b1`)Ce2bp^U+4Y(N4u<3T+ zsylT>OgTSiaG_};9NdQ>M1J6L+m@G7rhM04 zmyKPx6oaK<^KQ=atip@Yk4Hn(R50%w`cQJ<)8(kV1Kf6P<-}-N29#>4ggWPub~A_E zVmL5~jQ8?F#jK=Mg_VNQFX~2JB@K)zJHaB!Wzcv{a}<|gq%6Hj>aeVo`$1z(Ja$;U zC>;@fwV9F)J7c-y+0hR{>d3<25amJXe(42CSjh_QJ|5Bdh@Cgx%UsuwJq6`fcfcgF z_pG=iiFx&b@ABH!P~RhV(NlR68*&ok`W^tC_utKrnU5}~r$ zeoix`!@|AshtG&x3RJq0lED3a{vX47+=8GBxB!WfC;^s#OTqmg+Y;8d9w{1H^^c zHMf7F(>@XNW=%mxd>#zBg)Z6U{a6eKU^?uH^g$LM(~wtHO(w1UVWvg6%s2W>A*LJ6k{nJPDiJ0eWLKAGND^Zt(#0k`4+>*ADb>Td=F%G#cB*F| zyX2SEXj?}VDWugU?Fo>XOO;;f>ry@q!p&n;6aRF$JX)P-@@5Vpq%6TXd|y10-l)`o zB@f4QeCcG1>}E(oy&pBWw5XOW`w3Fm!sO}Grt46C4P_*x%a65FU$gFI4Q@bj!+`EOF6Ho*z5O zu6`K&H7Cs7eX4ZWX?NYT8g|U$G5mh@CG~za_TYyZBa^kK)%$1LMR0GkZ*s^R!Pz9I zB=8n#AVq;DX0^E{$jf>w*a4eWKT{=pONXm$#9p486ebT;CJxu95Ciq?;eK{>F*_YY zqA+Kklr5WD@xB@p-pr6pj-Cr5QqO2+xCW`Gv|Rk~+W?ox(%jl~)t-n~7KXoA>!a+F zM}9r7)HEhSwBGa-Rq9Y-fqQ4H8;+~TWJDU=RK=;~KGjr=x$&1~?VK(S@QQ33Z%X>$b8GQ>CI_rVUcN0ks}qV*731pxMG`DcKWNUGa77(_<}gB7=~LX zC8gq3$NSjC@u~74SJv^; z5@!`f3l|G6lJ*P<=*JtQOACIjRG-dI?^vSD@{!ou8<4XWNGtQ1vB9Jlgq~(9IaQmK4bH zstOcI2he5>W^+q(i8l=^=fsUr8t>jVrGW|&n%oDNNhm>~^JK>i?;YmyNs->ExNoGa z!}txg;_81hW7HAPLncI#f`s-v3xboan4T8#!3MK7pAkp>JRP$3tzQ212qe{-4{D8%a zkT5E@Fa4`dfZtGfQ9*|H%~g@E!YlR9A1b0-`G0eojgaf=9WD+JaabRofaXcmopb~^ z19Fk?-O~X*T+JUYnaSV_aEYJg!li?$=d}DsUu(X&Fztp%1f>tAKQJ@G?J$4J?(-)- zhm*sJ0vle$puX3JUdDg%xu#-OVB*6db;hgNX&*>?8}n zp=Xo}n$eR7EvGBXF^k+HK8!uKr(7E@Y^_{f-F|PISWk+a;W}>86_-f> z83Bo-Q=!^cY8F(9MI$IEzTmVSPZQFav|`L0?P3b)PueQXuP*nlq!6PK$5d?@%B`lk zJw-Mm&2#aD*P$}lHZgx2GDgv|7m9MIZLHAE|GyPgLSF@-p)Q(g6#&}=E%6mSDq>!k zGi_@(a0E}&hb8|wM`WzjArx9#nCKe7m_S5)IkQ zU^0Vu1pTj=V8sGZlaKg{j=T736BQJ+5UZ=Y$aHYu=tFKoDSVrud=b~P7X;(?Z)x}gg}n~19s zNm{n2jsoWHo2tRzLLcB@5zzZg7yhE@86t4;2(4N$?=cDy1Y1i=GRw*&r;CA^bu=$Z zg4Q&Z00e%2UzQdQ`5G>^qUQ4%jJ}HnH9@$aj{?78V8n1yq-eYN9FGV;KkFEK6!=gZ z@e&!aPYba#CGt^#ftnU|rl>gw1@e2_bczyR%5qTOTPz%A4pt{F1WYH!SCO|x2o^JC z;VO)}A{04>#{q)P@7_MILxA%Ifzdg^-FnTTt!&lnXwCnFy#VYDw8b%TnlUQ?AB=l2r(Nk_&LxAkzp`MTo8qi%BA&7y%dsZVwFhMKm872`ZUiwtGy(~ z<@+#0{qt2zR6`Uda*40wC0?dJXgPWV0zF&o1Dk?ZaBk=I8^2mz65HC_Ot$lQH#!Pf zakK-ZNSGr5QJ@`+AG+i^9MFlYZQe5Yug*jCIt;)aYccpcwDt#Z_RLwqA|No3^dctSqm4 zW|>*p^%KE%B-LZO(owbPIEgs$@u-SWyui*N$zxY}CyaycSYD?f?Z78#fuJfUY;HQT(B42Gyw^*$o+P%M-H&0(!Hk?G$)JooeB_M~&_e$w5$*Uf z98~1~dH(Ad?~-_O_}9-PaCIGrNolq^ z>ElIy*E=aO*S~qz@aci=lSbsim`-}kV@xU$Yg>{PwyyRD%y81z-al2m$>;rTDcHEt z&6Y%P@DqC$q_{rx*TDk8--WisIVu%S!|>bR8YObO;~VPsWYo^N=+<6~bss~)y|4RG zT<@-n0dc!X2Y02BqKthE z?f%Y=a(G|>Yq*l7Wl8}fs?b*qI6hgg^EK~EdVFkeQe)Bv1nXK3?!pTmv7<=c0EV=}u%eiyhosJ3IDyq$s>` zC8r#;{PpIOM_eo)U=6xLGiXc;sy<1^zuvENxS<#D{iex{)zK1W^hz?&4| zJMO0E&GvI_jAz^(>SuH>tExwI9f_SDXkdtTlHQeuZ1F6lX1x|H! z)n=~X>5im?G?unt<$P-G!A4DY#B=GQIHnxaO(jX+AVNaIs@uUgU?y0C6!G?u4fDAN zoR|zA0k#;xG%_Q``+m6~vWUVy$OV$ipQN(f+y(KZ@dH}MNIY@Iw10WE7aInm|Y%r9DP zD{XClFeN3af@yW5X?-J=9ZCi!fdwWKErz~=7bX_|D__wNL*RT0p=G>6NLh(0q z7}Z;wYPq0bXOeiHoexaSe{nEf%@pYc8-K!3WboiWv879ljG^+tx>Wu5Qc7gxOZ zAPAT(w|&@`$fE7A-ZMt_XQgrg+IWmMD@yzmA<)3kt5xt(@R6R7*I}oe?~(xC*L@#n zrfxFon4_+j%Pz#k#FcUMygOT4WIh>w8eFfODow2w45Ml^hn+M9`eQ(MQb>;r zC@ZSOS?N$P*;@JY0Z90>AK@b!(_ zQxgjy6CmgtA07SqQ8>$MkeZgQtgh^B?2k)IIjWf{GdD1269Y@5(z4Ey+TtrKuzw>n&v8uXeD2G*@=v&6|DAAUg&qm*~ zXa-%c619ee@e-Yk;g_{F)ifAOhtYYl)I-nQKlnjhA&~L}=7f=F@P%yM6`V*dACoy_jzb&~dwP0EN^JauPPGvw+!e z&Xjyn@5B}bcnpXr9~ba-|6`yTp+RkYBBMRdoj3lPEM&Dt@sf=*3AcXM7GgjcnP~(rhXzPZXJ(nQYe(D%-3U7NK+&-UK@jCiHVf`uVw&iM;J!5}}D^ z>&{4S(dh8^@bDmSk*5m@?lde5x=mB*Hp&!v4Y9z)3r>i9<@?yh)?M}2%^7EFHqA(G zy_8e&ma&WFLw7f}kwSA@j63t}tu0l$n3-g+S%KCvm^xIek+~JKELv-;H;8tScWmY(t-1jTANC#&7q4Q5xl-^ ztv^EFJW~2)U)|JI+#UGs&YM#~Q<+#s>bC}L@}0@HOW5uW?s+%7VMIL8?jKZ%@aIq# zdi4Pon%iZYp#L`<1Vkr8Pc3mjV~~tT=rT331Ei@FJ0%`w;etcO!UXJoFXTw1Mrm# z%z&*+Dki&>1$h+J<=N~w0Azy(R6d){|0EL;n4pK?U`sU^Sok1b?X3z9op*G6qnb(2 z4qv}Xxz3x_dw~ag&kAtnc(UOqq@_jAe>BDv&F9&AGtL_mom3iMl0nP^4aDRqVP~P` zNg&=Aa&rRlKFzcr6FT+WeAY~B zk1gT*cLZ0xUVdM1#{aYv0>lW8>Xfk9>GaUa-c54Qw^qBj^eE0qh>gV~L%8mUhDXG2Dr~**|Ud zW+12a<{Ei)baV%`y$#Po4E(}#Z!uP=Y%aWqqExuR+Cc6Do4;SnU_e}G`2a)q-d}RX z3yqy1(b6=n&B#rj?^R!{7Zfyo?<&sZ*2F@GSu6x#bF+!DE4!<&z)fzI!Gw;Pg~dxG zc*r9^;83vN+mm8*w&~$uKMpR7)E&3_y;?*`ru8vH{VQ!y`=R+sjJJmDAg7xscQodGgNA+B z&DGX(H39>=GOIy=(_zINbT0np=~c$ry>>Rknb8&&)GZYD zdOoA*4`9Dgf1gj^HN*4C3pWH&cF%{NNZB-0ogVLJHyMHQK1H?dzO9V{^CP%(%`t=5 zi}Z{>WH@X*==j?3v4N4=P~5gAP9$Va@s$dbw|O?7v=P6|*L_NL*_&Qjx1KfbDoJ@R zyqt1%xixs<*27SM_w8-|9p6aOoxrlT-2M4VJwd<2adD}qAMP>S(A>iSll>dfRCpM2 zq9`DcqVI%Bp<-G`4?S}_ZVlT0i*qCh=!ZbIq5o#{92OKzH@Mb=p18xlr?se}SZ~*p zb5S1-Crp{$bXYPg_faobto7nug z$@**j+JRHBb>`q&=7WtMQQSCW;>+eam`bu%veNNB;_>0#_6Jlod`7Z|gQ}T@H~=_G z$`BL1=gr@*3kqOwc(6IG?yG|JoM8F+m30BG1BKyxJ?~ID3riICQ8f)o26jn(o*B1` ziwhcWJxQCgDQN%H<5zstA4OgpehEU3odnmXD!~ZV0wz{IiFyjK=~LxvD*1@WIaYR+ zhesTqdln6s;bAKPVF*+*9(U=^=WMUq1di0bo0kw$bY@z_o;wpbCdnB{7;+NnmRPMu zu`fyYEs0azu8ZHmzq1}+O@Q~{!gsA3Ple<7qAd%pW*Z;p_%lmmpcH>({}hPUIHf&OKBVD6)}WXvjDskJUmdwHSJg$& z7&F?XNO`Hp3ZR)TzWh>lHE`^(SXGq{VX3waar_e7tJ8m|hlOSH$|*Sdpq?DHeWD^>NQ+l_zcgl zAC=8nK2uY?7h}S2cRr};OiNCv&sdsRI=xr5VY(OEJ2!+lXe%9p@V%8h)pN;XyO z>C;${JZhC9y!!dE&kh>q*4ssV0^y`HDv)`8;}Vv?lUnXyG69NpGtCExUGETvNEY;9 z&qW-W56T7=R>knJN4Lc$wKn9B83B$Z)yaYF z*#^@8_#3Zjs7toY#e8^=d~5>;?f#Txg^2YR+gWQiR zqM!uKJGhsY$ZAggs=FQAd;K*f&1u%Ii_cnliR0#{YO4&uO+2PyI{3lmF?>X#*AWcX zdnkNwRm%LqhvE!>XyWg`&q5c7UYl5mlkWl69(a4eX^{$1z_tltU{sK2Or5ptQxU~r zckhT%lZg~CS-Fo}0jw@s_i}_s)!1DXxDp~XN(EsMKmWeI$7U906{jkU5N)a7Vy+uE z48hf9F1um105IXFVYg3s<6{^%(rx@BUns1wm)9IZUE5K~TtbFmI2AKw&E9okPIh#5 zR@T#X)uBN}YwKKYAzY3Ma41h6hUYF0Wqb`~2Djw~+y8EVKajKhBSew2d!mkCeI0@+ z1Ve5qG_XkZ%eXLThtdxx)yC<_R_qcd2Q}W2p<>(4^!fTS7`2J0I#O1}MORO}F5F`B zSQM5DjL0e}VFZ(HitR}+qpJHBdC==Ff$yCgy25v&?9VbfNZwcw2PzB z;7rO}_GjK2H?K-u=L-`}Zu+fPFuX`P{|z z*E@>nvB4A$4x-~=J*F`R;e#2fZ&x$RNqIImDqVOnUe}x4K zHV!M9e?MxLIq<7VsuMiBKP-9~ISdmM)1RLB7Rey2t~c855BYDGdZj{5x-~ORQ!u_B zmGo1>&ECm3E-7FM?q_QIdxYV8S^Am-J@+b(`1M0s3(`qRUO4G5kr2X4e8@*NYNFD6$H(HlBGNduS;#M%SYj4ossieQxX;V=WY6dxp%|qDV`y~LK z;v*OiQLy96-Fz@?4p2m0eCTX?QVv!ioVj&d|G2 zj6z@tfsW1`J?wK)9fKy5&>eO3HFl#X#78aj<>hj24lS6ts6(T&A!2;ga=ubxlXOIE zxKD#MGXfD~&Gkzc4sydXKlWluerEebW@gm93zz54VxzIHC>kN@L%LNuNdLBI_a zPrHvqcY!?}Iv}frS$ZRj8=Bt4A@v9n5&1Z_l*&2h5z)}t*jKbLDT@e*kfp+Dznf~o ziv@^Cfyuhd{M_sK1DFVCk*0(k@8diFvnQeV1R3F#1fcqY7>UtO>is0-iHcw1xa3Ic(bA zOnVSY47EI8$bkfH*DccCdx5`S|6k5MSxQLEcS&Yrb#@!tb+u6p=c_}{u@aAfQjCq& zv(Nx(D9CG+;C^p^hIhuVHQr~)zmu2|>)_;2u&mvBZJo{SxRuv-ZN;b?CEz?yDV6q8 z-F;8s(v6Cc*LLdqaWDpV@`IL02d)n@cPFHokI+vcrpMofvtP((QxUm~G003q7SMNR zJ-?H4I}fJ=0$x{!mET#eU8pQM(hvPFD)R#b6QIzel6v>POpg;*99IMf<209>0|~jB zt^0ZwiX2;PM-{`Ssog9hjPb-V$SYDeFHIBnnYyQA(sn#gP z?Uc$L|5~$lH(loR-Iod1Ua*g z^qrk9_>seWedl+mN&K1$chCg-Cr$2VLfjikp|46%?_9tdVSAVCc?u_nlRtw10a8E@ zAOkN6&vFHDfE6OtXrzJ3_?)gVgYZgkGHX{|20-og`+`HBU&3Ib2dR)D3cHp8jWcu< zA=qt@5gkVl3=7KbCi3ut8jbSupgGqwci?`^WR>c=+MyeccKbl@{4SQG0Crph5jB1@ z_-n9X$Yzb^cu}YMlCLudtF-F1sIi48Ag*RHP~~pdN1#G7Vnnd~*RkG5_Hf{MMkxI3 z>`q;Iu?9OnE^*{{_*^F=sw;md6QQZ~O8~c!uY^qY_^45Rqkd1WC~)<#bvt&k7p`HX z<3AP9vLJ;4lZ{-@Zx~|Y5;GNp_Rrlo0fMIC;#mG;SaD!daMIxJcgq~Q0(`SN@d!{V z7zm;uzjaf7xnb%{-}TuyupRfQy9}`3+Zk99`cOIe=lK^xx88fWrcQT|f}wR_2|>6_ zM(B$OGYz9yJv31yup54dgNd(%A7TSCaHGjUNb(6Q>ms$08awMFZ;y^qU})uU;kc}> z3?@I>_Z6;IS)E8Zz91A;|Ao7G9Z>^-T=SNBym{-{pyp$EB%uFJ8t=9a3LVUguGU}z zGwX6$T)0ZucnX~nw`+sTwn-0_Zyc8yT&R#}B>^GPhTIJP>m=-sX@dy!&fbDvHjO(v zw=Y@z2TcJsK9M+S1}QcHrW6oWREp^zACphRQ2{dFiYokDcKrONnoj^eH9DhuHpBf} zA9(k%ypY&O@d;r^V&$c_7VPe|65lA;&(TDh{3I9%!5koP(_E23V96N!f{|WNMO3*{4ZXpQDqM*ufmVdD*$;;|d;L>sB`_2yyXBqI+ z?p;qHc4ez{c4dFn+lCfq77^Xu-QBc(_qplO!?U3}#2`68gWbOEBowK@1W0jI zLr3fra0BmUg%H@AUWbyH$9)RYOgK3B0Jt`@?F|xQHB89!3@N*x5LqyRpv`KRpBE#M z7sqTuzf>0%L1EL$YNpwEDbsb`vUV`@(b1^FKyvR2lboQ0lo4*SGv9v0LUu;)-L?xu zw_P}TS6?)R7eYDPxXDN%Lf@n)X5Df`1X`S3@E&zP!5wG}Ukq*hYuqG&{*T+XzlHw! ze;#lb+<-+=@=q$E+w`%v%l3QQp^T%87)`~+o_3*mVWA0dAHn563x9{%daSbNLq>^B zC6dLP5r`ry=Qp0sz4r5ak9VXtyzDz+42;ub9;{O$r*b>+V+z8GK$OmA^rTBD#On3h z=$JU0^}|07k@#nwI*$ClFlO^X+dLQV#wF<-O;d6InVP z%#!~!$FS4QB4n>4{?u?y!HPvJ(2BhPFLV|mp%IHV9<-E~e=bv)K??gQ;>b`XBJ;gM zD2p6$YK971dC%9VAfoZtXLJ#fM%ij<&d>+3((-B3_5x&N$wclO9|{0ik+Zomp<#)}wqOjzF}X&GA)3ybBCjWh3i z#VcNL{!poXQN&ra-S;KS!7Y62Q`PA&L-*cRyVE)IQhxKbq=z?9*fb>CimOE4vv;=J>5%5|apdfeB2r(k*MwsYSGKttXTfMqS zvkgwx)aSD-8Jkq{{V3ZU*5>(+rcb;%5Igu1Vk8r4Pl0bViA`MeIN$E7jD{%r4stPJqh6C#J@fm`>}ChF$Bx0hP6t}*3*ni{ia?`S-kb~2L#q`gE8bm|?Qo|3vJ44q_92bMkB>paKW zjX{Rb;RB?)QG37AXgSX263cGtB-KhhUBR3F)4}d;=txbs`mml1wohjf@mn$Nr6HveV_*Q9(-B!5vtq2TKUQ%Hs#`zHJA ziV{^9!)I$${-qb;{E$=M&+>ePMDABVc3eK4y&3<39OxuJr+^5DfKH;|0&{4!8aA83 z0oUNTi!X3~bLRURi|YMTSEJLT#nemUCyh?~C1FV8`V1Y74wI&ZGJrlzq(CR>$<0LY zJ(O|aEw9qbCYuCfzYj z8t#9NQTLlKa?e*c&t={n#W5`QH|`@dHUBpIVQ7|ju{1liiOfz46|F2lV8q_?Y!_DD zroVZ6D02S*evQYq|3Ow=;dyYZHJgqo-3-~Gm7n)hc_;~ffM3X2%INpRK;K{lrROT7 z_1cYV`AcOI-B_T!O36Ilo~xM-IfrbLnOM50mL;=p5VIv@hD9@n*~%fghC|>$C)H-M z9EA?6M&^Y@{gU3)Z!T%PP{1m>r$lNw%n+hzBtkfR?XM5sW}Vr%*IM_iD7A-8=wdxS z-j8R0znD4EmU1>jJd9fqz6Ex;XnTJTy19dnfJM{ATEDnp^HO+dn$F^qLt>XR&g^kbpPmc7(~r}`n;(cmnT}LQFpDeZ zz^mnwL-aE}`PR&$U$%PMbvb<6ZThP1+=RXD-5*7oFe*JSFh#FwNMjTXBC@&2!42qT z{ERVtbbJf?=r8P@UwC+%@z!r0*ErYm?CsrY2NfkS2`rpxg`VCz&944uvmfk^3YScu zb`alm@9MYvhn>vVA=L^sY3l2BVgXAblmWXmE5iL${2$R1BEiacgh<2P2|1}a2q~nMplHA>uVKc_f$toAS^G$a&-$zU>GpS=XrPL&I zC&qWy>*NJ65_xlq6H*9TT-QxD?bWJ=(JsSqsg3*B>Iv6Z$x<_g`aRhD95SkA2tdrF zNJ-`xUU8bg_($Y~c#)O)VGeI^iX#G&=FjFFtsEV!&f2!=+LV}DbW)NU&GlhjMD(Tb zET*=&C@?v$?SmuK-|1@ z7=-}OW7ECXS81uAVNGbW9O*@8T60Hf%-(eSmyhOmIvNg zxKN&?U5)Ab+c710EHUI~$umOiMC;Z+UpOc)ca@r@%1nMJTCT#^AGruuht;on^g)J0 zCdkiHmRe>S*LeC__gnb0UHO4!B;P}p`8_TQthH&vec5S3X-bPLK@J8BJeY^dC?l~s zW|Dac*l9KIJ=P85-_zCagdpxR{nSM#f?WM5TaztfRs9no+@xu$zj`M;pTM%o*kj)g zz?xQUzTJ0|z>&yXzg({CKeE$7I1@a#nXIvd@N*U)G=w-IQ@tgDQlzW^q)%Au74!vn z$`qrLzJ(a*c_x30-X))`7L2OatZ!Gh{G&d{#GD=fbJSyAho0!iNkk*Gz6@AMyt%*$ zrQ1r;%DfJ+kR#1sr9_g^2vnn zNS=(9K&{P?x&B(Td_dL9%&eDS{XKQGvCwtUk^_+oEmGW8)jKcCSkz|mC*pLJ84uKM zbo7%T_N3)I9Q{&eJdpawQq7wkcONIPfEsG6^XmY+mpZKe5(8|vh<70siN{&Ze!$Jc z$8jG$dNq05&WK%Wuq_!1KhdZ&U$1CB&+B$GUv_)dcIBYCU(ZR2mfP{oqIbCtR(a&8 zPD-DrmZ?M;Z=iZ^Z&Ib(vf6>r`y~QiI;|)Zr^oXVl@IYceB?5`?ovlvEp+p0u@q$e zx(A9i4bsbWRl3NXjl0IXa!@;G^BYhX&8aM6fF$$T&8+TbicWMYl^cxYvP3<*-pOFL z{uUDUYhl?W*7=O9OzX~kyv0S|S7}C8{*N_Chj~<(>g7Dm@8rj*-M~h&n;|O|WIf-q z9wa(X{o`}4SQ~Jix!G-X8u~3`wlyz-1|57w@*^C99H!L}m})LJ_XYXDVcUdVlOzGYRYX^P`D(@`g?#lwNa3)#bypu^NSM)t76ttjLVzJe}+msE&a}lny;L ztb5qe@Vo?)L>4;5%#;|pmf;appP8#Ebu*adX=gkKYq~E_If``>Ed2=P?VxYu2Y$6W zuLe>bFSOpD(q3j-}F^HG;qsH{Y;pe%Ff$VZ6E=8n?t%!K4(j>mlj=S?? zz($_L|3~hG(w$)t13Qz5syj5~gk)a(y0qz~Doom!h}P`dwn*tqF9n0X zy@mx{f&wtHRwp~N^*34Y>d_HViF+O%z&22y}X$$5ie6A7(hhy&$Qv)2%XweK&$-!d z$|%EHHG<@CsSRRK_}nr0BvnejNHJ$X#nGh-mBo51V=Xz@dN{E40TqzZk6#B#ecCB- zwek7|>@*~?Fo(;bQA*ntZY7h_M6s?e^4OOUo^z2J#)j7vh=6MgUS7@&_6{1Q3QM05WBw08REb`bq}gu~c>ViLiXSvKp|dWnq`hOPdI8c9U+g9rq?N#KQ=m$1&*; zyj#<$`;+SwKxb7~KFd>T2>Y(L<68_{LKOT6{bnuJ6W$K7_I}WVpg%RvH9hRCEAuS0 z2z@Uk!sUa$tHsnGuGDE&-s!KQ1fzmlkegBFCeL{l_fME)xGjf9&c}YL?NhRvn$4>6 zOag9Wq0II|X$Kk>y}R;13-St!=wM*s5%JP_5ITAl5s&xh_k~_AZR&qt5LTZa$@Y6& zG~ug?+l-^5eXgNay>Fvs= z3N}q%MD%%Mro; zmM6EP#MiI!*z8Rv563kZ>C!GM%UqVb4tiT}hHTc3H)9*zi$2`ijZ3S4)Ndh_F5*Nx zB9ngcvxeVFBZFC*=w~#-@*L8IoqNQa>8k+U8LJTm3i&{ z#nYA2{RDz9XPB>#%M2z`55}g6d4{{gU2hC*^}cwP5-nzMm--s(s(%-Ls=XTFiNqo6_EE5dJ633Ta5W)bE!MG`=yTm=$UO&{mu0s_6f`G@RY^s3ETix z9LAm~%vy_rJzSZ-r$tNA6`hR?R5Qw-nscq(mmiI^{aTjr2z7sD zUe0HF7^R5GbwUAL7Z;cF3@v52zdQK3$Y@bJ-1^7N$dC5es)#tw(BuiRv zh+A=MET*s->vk$^dIJPzw2qJD1)ttrdwOzC`(HTSE-{Iwd0Z#W7mY@z@tv7zh1uw8 z`7v8LC96>XRH3tI-aWi=7HCd03XEGk|IUu+e+I5Q1!#*%f4=z05^gn~Sk$5tc(+p{b5S#0q}vMPlo>zPyy&r)WY zJwRNaAKlLmYLe}~RI71Tgi*@OS% zYGD?dn)swkI93SZm-s3-_sW(OM(+OrRK?1r{_pJ)w29f@scUDnC)qeHk-PZDS-EfFqc7$XcFx5KzWjP>oKCcd$Nye$W4K;v zvf0>LjSxN()k&L{NifYQGuJ!E(0rUTO?nkI?1!)W5(j~)(N^#wf$_+18;Eqj0DH`o?9f$}5XnXHB!suRif_C` zlUPT$>BS8_N-2{%W{su!6iW6gd-bVS)AS9$qWPf}DAu*!e7@M9w?+i}q4QUsUx?iE z_!PlmJR5uiS%abHOY>KYON(sdmqn@r-+Ru7ey+D?#+swn%S$N|5O}IsPTEf%j*(N4 z)P(lhP4nCSPJW7sM(X%cNE8~AWIkvA_#ZLpf-|FpVR3q0L=qlUMCuq;M22H~wb3|_ z2u4%&v>aR?mAYR?lC|DU+|qr~YG6Cw8lk$n(Y@{?-N$v$oI(tYPvhp+Vl&j*z>7vZ zBDeHBG|_^waSX8xWa2katb4z8t};!Q$FQ90VQcGbF;{dU(O#+rqD5AFy_#y9ffDVu z$ON(Y@aDs*&Z3EcU!{yFoVxZ#aU1cTCcmb_79nT?Da|qurPJzGdv-38C*lLr1Xu-I zzg)14t^Taz?+Vv$Y;T=8dw+hi&4}9m=giVWkl#iBM~}_K2$Qe!To`WZr{cs(eoCQi z@*K7=5z~TB%VA}XyA20MrZN5ozK(|0})rUCUmFx9IyHyL}(ye+LzqV>mbAB)V9G@(Cox< znkbihxWzeciFDSlgU(?wOH>kMP&Psp_M>FL(=s$Dc)o7Cd}sA!J&lMm3@<8dacw^@ zh+lfi_bd+aQ-HKk6MZRwt^hiZ=AO}Cw{-<$0Qki z0FH2vH^gNBar@}`+}?@OLNX$ROQ%l^a%E7i18U~NSHzBQPUUa7zCi3`H|8ph&wU0w z4QuN|*8Q0&Sp3L!5FKtW z;0}{mL)#x=jLV232-)l0SuNFZe}l)JZ+f|MbzQ^P?`ml4e6Y@B9PjbFS=I1|6Ahw` zm5hj1nZ1Kb1bM980l(6_m8(v=%9T#EF5mCAETk_9r|!{Is&_Uc^NA+>bA@W)$RqJkN()s=<1tJZ3&CZcbXt7vazNUrI~KybgvZ)_nKUL*sh2uiCsayTjqvk%K8InI?fIMThq6@H(6c2k@G#RD z)5Qn`FCv$gY?r(I4-L9~K~t9Rjcw-XHwh_88M+sYIt}!YFMdxkI~(E86j!0|oQ{L* zuv>OMIjrQX#1e7rd#fNmKnm=*O) zdct-|7-Hxx0oJpTl@q59xHkKpV1p)8sx%$jC|3`@S`*VcYsV3_Q?M_ZCH)DWYYVnh z`vM2bap<30_dh-G{sXQF#+_~p`2RV(2w5VHzK4A$7mJB5AuGUOAFP?5vT;~H;K8#q z*}{KJ%th_CHX!IE$>KD7+J3Miie|Vjcv;{2_)cB zqj@4%$|Qc*{*IwVe=borLeocWR5(pI9!FihB6$gL4OZJV2iF0qeKp?Fnsj;J(r;`- z7T6vf?Ovt^YCf_Ko7QPc@v1W!n_{-RX>*p1uxURw&6xJ~fViJDFte7F)ft?nI$!&# zi|F+hbCmF`SJ^DC{9k+D9o1CU^(_$#T|v4O2LS;Akt#LHjG$DJUPM4aN`TNp5d$g$ zB4D9ON0b&4P^7n!Dj-FvQiX^}3xpPG@|~NRah_S(n$WuSto4Cw_jA@yF86FJ7M(s@<;Mur z&#o*4bo3vy5}{XTdnPKN^jLK(l4Si{*i^mj`jxV?_S@I%s_d;;kF1vE{@Us>x@BG_ z?>+nt-)Ls@IDTjKdq8(6J6~*kNK#QnlBuU|hJnPFm)zyHwY9SzvaWHqAc)=vK{WaM z!T4KeLdR=^!k!4})8#fbHBBNJs=yZP{qy@%M2;QD<3PQl4cLi1)LCu3PA+$ z5@qKqAHstUzr-eszP#VG;H3MV7v*_wQ=1KCWHdGGtA~l4VM8e(#&0jbVh@rW$8sSs zcU{koBXmH~eQm4J?Aqhf*(Vi^UC)rml^0WG5xS#WBKjee!9$KWF~8(UKAs@OtTqgt z*#9OC@#$r%4bn@W2emiEl<1hzEgF%_3BEfton_n2KN-!G(uhTVP_Y@w)gmqPDq26) z3$(38dT;8FnuzkXUWShzYwcW0m)A%!R#%JBuw`q_=tWYxZCy%(4E;VygACdfWYFa{ zxl=zfX!+AU?sO5F2U*(dwDmD#FQpTA))(0Vn-B>*Z--nKJoU$>#aa=ym)GtGw;6w&f=X0-d+jPg_>zR9XmBtu(m7oo18Q?T9J!DMdRZ|1pdtj#tIa zbF)XKyIVbxrRuG2!%jQ8F6}gF()`dfWG7AKm0bS%c1N=-J=*S*@m|gWVfn5P?mWVC<)!z#sC4 zGx0q|{H8b+Hz^~7y!Cw?J96}Z-@;IUAU9IeT!4+Oynfwu=%_=?+NSC5FJkEN@yLf- zI~Nq>FV+M#NvYu!UCxcGS;D5Qh#dpy&9>}L;!1G^-)fO<5OQE+BqN#an)UE81Afj2 zQJ{$RWQDdSe_y=H(@n8Cw5CVfT@?Ns6e^FzpUZSN=Emv{I};CMEtIq0Icc7zU*Snv;6n1$?Nw!_1f z(;ICmW%cZJzTIpVY0QZsNr^~HYZ=GU<vCytsm6eeEtkecbMC|%uQc3a#fX#~7H_vFnM z%m8eX7XXh~uu^?4w5Pj=opAj?i0;;!^U2f9Do0dOJPD?(igs zwmHqh%YOT=LfS~Js2YJ;rFV52U6-(n9Qu#?uZ5+;TI>y)7%D0Dk zyO*M7dL1_IJSvJ=4|6Lh@-LUH^;>fVhS@ovAcDI+sYP;PY7<>KZN2VTvG{SuQeG+} z&x=&D+BiCxP#)OL0JgJ?ErIue+8d|z1+fuIYro%5nZq@5%Ju)^yf`8<98HzH@B1 zj)km@1q>&LB#9ghJ{J>Su6jpu0Ofx=X#A66LmIN78e}>xpv$CiQN!iH-!YxeSdNCc z>)p*+Er@HSdQdUWg-=cZ(93S?Be>76t zhOqe#Yd4S`>u9@8{%l4eSFjyt5nJXGEr<`<>{v?WZ(-q$6E1o6vP_6i;L%`o)F2{4 zHj6^UwK7*O^e)wl_(ZndUQH-`G}2VtlNyp#-=*Q{of@DliSwzjAIqr-Zn?TO>*)!z z=ed5l#H`n}-J{8sMcwG^xcrPkr{n7!(n>#XY+OhZ`bm)IxvhCNJ-BYY+Q}V zoYxO(i&K<0o4_GUH&txoxXj8`!7g>*a_YX&4G3vbUa@oZ)HOl958P*O8J67zEu(w* z`)PMRZ*+<=>l3}?S%`$l`9Uvgo|hn@G)`O_Exz8yYd4oPDPyWGjO*uD)tQNvs3IQ`GkN{8(aTn_-zl}I2FX#;+_?q?i#UsJL}B%rc8&#W|yD#iryC^ zR>i?duh0~WJC`J$8EIN$pP9D4+3{HKm-fxogCV5Io<-k^N zG_LJV`gi9})vkJrA&Cs-^8KqHh(e8e$lt~JoTr-;O$(Vp%Es(Ewb5Dcv$bWX?KTrB zB3O318tf8RnO%O7D(7{JOT`DyC1B>U@VV4gdCVncHd|Pbd{RWP3wW&OTfb%UL%ZOb z()mK6Wppo1z&jf4V=HXT2BmB?2XQtREG2VXcToYo4!6g5tGs)+x@@Kr%hE37ZXU4M zp5=1r)lXAyXFQIf0_Y{m{m%xf z=~%bT8QY!h6N7trPO`}9puP1ojt%#hQ^5P-p*@YMFXtb<=+H0_)R(C@N=ha6dpY0c-GguVnZMayobO6LBVOaW{dU27%g=M` z;k`p>`IPYgjTPCP^Y)K$8hzzn_F1{0u!h&~}A2KvlWbJ3U z^hS3?2R#QWPRucWP;5+?Iv|fPY?B+i<;;XApOn%-To-#sRCKR6$?WcX7}b?L(Joe` zRkfi*A;QbpOK6*3P73yL!4Br}WDAtug$F?un^rZ@Zr`?Qg4;Rn@7hS8s%tQNBTtYM z0Y~Cq`gJT3z6afwy9A{*rm(5?UW4wZG|&2;Djf`-*DPsxe;(QT9FyXg8eo4ubpf~! z$M>#XQ5YV5o@ce{APsuuq)We~6m0J|rZKVOZ_eB5wu&Dts#ap0pD=^jGf#m^%n@*s z4HNy5=F-x$&I?_W$>6|&U-ap?EUQ{C( zOnM;Bv?4V?mNLBMlM%q^o>%iomv1dDaTM+&qnG04(#$TrkTP&nD72#NDquc ztja>@N2h1lB2$X>NcH-6?u!`;!fSIAl>7d5TjjQlIvi4r*)7owl*JNCZRMkW39|=9 z;WDsd7N&@D`$j2<_AEeu`JCmWF zjtC}_JGvR3Jy67+d0ti@fxlq!!lt!i*jCxGMe?yz3-)m@@(o=?{-X}O;FaO+tuI1M z+S4T6rB3VOQy)?Xd=5MozZm;*gDY-G-D-oPDPhbUNuN#3o%wF#27Jh z&nI$3CI{bqQ|2|XEvM-sT?BWeEiKOl(2vmc$-a2xmRV@o?GqB?k~umq^5gL#=DHN| zFc6}Tf)E{BQhnssNg&Xjbw_MVbpUMY!F_Ep{N=(`P7r*EiIqX zU4O&oxS8=TSx65fnWMOhkWoOOC3YLrVij!BgnWkvl_{4;;W}Kpvep@BM1a3N`Ng;S z-e1XeC8|ELYa+GzU5DBdfpgY)DEu|_X+kOaVR6QekjXUQNe|j)^FzTM!$fpiW&5$_+6$LX<%BQOTj;u`yB;{fL`2W zS{8~#2$z$O_HZA0E%A~sAUz-ei6PGT5bs}o(8TB5#i&;0<4kr-HYS&xD{7KV(UOm? z9_K-2Sg@k9DivD#XY`Nrq1rzSl(l;G&P8xGM=m;BS6)qZ%MftIyPuQAo3F$pozm_g zoigMs_KMK{9!m21U1;0m-FjNX&Z5|+q*$|DnH7&#M5+~kz1MV@-G|3CNVhPWnDKm_6xQZ9`Ii?}ga$T84KcRRD0eVMdlJ48TXbH8<`d zt0$z8e$&#omo;U!ik&gx7uI5Z9R-T4|jdncE1fpe)uQKeLY z+4PlU79YUIkl&xHO_edgRapvP*Y)oU&X@ch03LfX3ALWbUrKu`o8MN=Rvm(0X}kiZ}%tbLBi8 zeB9kjL$$dkl>ru@IdLi%qo3>q|XNAFn=pH~}ehWTO2V4IIz%&xmjSOI=5VkF?&X5fP zY$%n1#`w@h+>f4upl1!#6de+CFY#<|inQwy6N)V-`=V-To2ur|vO~Mv5`YI*sRj(2 z2{sGy;LWtYK!t(;;3YQF-H;CED-5nM1S1Q;BkmfgqPI0@_Wcka`wXVN}_G@JBU&Nw;VeSK)%-vn~$Cf4UxW~)6J1g#)r^0nI4ZvpP+fY(n0_u3B61YO5T^aH*{d-NZ;Tsu`Pv~-_Zbd zkLXM9mx9H!feNO}v<-URum+6J|Ee(S4_knwh#-x!SNY5uJxm{}_ORXDP&0^of#tab zXkTPM1MkmM!`RS@ivn$@VxLk?*&pbJm~;7L&v!7si%WKkLO@3j0L99S(I};Y{-JUt zQ-Kyh2{*?^>IAk~xXgKZ*m2DpY1IuR{v?yh>Qm{E%*DlkG@e$qi}WM`Qq*M+NM!@P z@RmB2M!~0n;^Rw9&O*XH2C_TJapTAzHby1Cj@~lmIv4087HE$zTb$I2RW$>+We69{ zV*_!+exGWl^U*XKg3ViQzCrX3NwzfW%A}>LDk&b?z+2HDhdce^U{Z1gKvY+P zOsfwY>w`6Y&PtdH{3QbIOzFh~Q-w4EDHouTG{adKCU(c`6JChA2Y-KFypBzKbqjM5 z7+2;Mfbx-d>2~1^Z3ku{;e@#XJ$4Fm6E*p)baGXI%f}$|9YCtb9Mb%p0Tw!XK&76? z1R-ig9(1D@JM32a@=H$`Wmy)E7oQs?ejTNc$C*R4Zb<_dwJ5x(PRj$jt0U%n`SQ@O zH-K1#NVu|p>f9dEd7yaoU!xC!v*tz8HbqHQpWG#9kS}SH-UoxSR2Va;=))@?18%!{ z1T6ap*9I=ant_=_DVjhT!(ro#U;^A`uUP*fek3IR-bBkE%hXVX3OZ4$BTG-v3u(pT z_@2XD-ylaemb10eC5nIj4LY*}F9jPJCeYTxe-`nE2f+lm11)&ze(-|sh4A9`YVrSp z+NbN&g-!Lz=7eblLC}IBkI9jc|KAtk|(J;ektH3#6w)pyl@A)nUCaUx5%r zJ@RNF>E%I=0CFHeQ(*AJCBwe~n{R=2XiTuy&>w7=8O^aVU7x zJ_MOM2R`o@G>SjGkmLauaT*zug@Sn;g8-$^BOEtYRa)pYrZ!RH;gPh}@M3xHp}emd z3JOdBEDu2W%5S1kK-Vc?4hVf56+=G=1W4>pbCVEU(e_GaYoA6 zHuD?n5w^A=BEE5n{E-4Gsz>>CJ#>B78wVCALuYL1dCS~1LJfAHLk5TY-hc&eN#OGp zGSmQ5*q)V;7Y54s4D@|-9=RxN$PMV66g7)5 z088)7ABa`zXrLH25cq5G;l6TkRkvfX2-a~=1Q^-H1rr1$2I#gUc?Uw1_26!ivbWwp z_T1)nx}Wc)%Y+xzWenb4XR6&yO*$HD zAJ1HGdcU#Zr$H5lLnxDk+5J|JJyX7Nct6PWo`DB-Yq3~}2(+9ZWg7uY5dc%zQL1JD z68ujK`h#@oNr-ewQN8dZb^L$L_!^Yv7sArdByQvnv*6c8^RmYsu^?_YpBZmJo8p~Hh2 z;uL6JJ57)$3u1#`)CEy32A*kifPeR!S;Iyr?+A2w4m`>RvYGU})NUx6)BuB8*{Drm z%hLivQQJsX26mWP1%92|u2%U$8&3~t%lOW|64<`Qb;kY%egl_4^=o!8UQ^uR*okdy zL;F?eOxUm{uoeDx0>Bdg-MR<`TMVd<0sJtO1+#$yEWIMl;P1RdDFL3(b|l;&nKfr( zMW^-biaM3?;qGyAW3kJm&PgB!Lx49NtD2LFhZdy?5QNDz${R+j4-T9J-St$5=JkJ_ zwCiz)z0!v>@+se!xU-0djBxQF;UXkdLo{TB3@nt6LCvB1da`&?3rK7scqf587zmX2 z_6nHB#Z!p@Iv)fW56`p7gEa?d0WT}~4p}|3uBA=g_6Bk?Oms$Nr1yX-GzWCBKjEEYa)Cbm3-1@*sUR zRg(`wyuU!MLgqr_e5{rMceogVJD!cbFoHx)U9U{yf;6vxYu(^el}p_rkiymP9V}Ox7lU}j>0R%r zDxKU?@nA?9#EDt;mL`G}8G;h}A9CdfcMOA*V+f(R4!}(X41Ub_IXz^fzW{y@i^b#q z@PmNO??<7T==Nr5a;X#Fp0V3*w)^t_G8i$OwZ|LCdrYH7 zdSFrY0Xjyg`W7}pLw7*Fa>sU_E)Mb)$+!VS@ZfO(&sH;Uas`)vIUgZG8se$0v7NQf zr$-LOaPe(3a&uJqEpb=*Eb&+Q%pWaxA>58L2#kV;=3;VviJ)dj>MCy_@ToN5_(mEN z6wSidB@)Brlu8{szFA_+0-=@oAM-H*3)D1zq7&fgWWbQ3eIw=|YuX2{X(Ar}AyH^F zhQ**jxO<)*SQ0eFKZp0K|JAZ%@Oy!4aH7he^$Q# zE|7m0$p60H|6L&eMv(vAO7{I5LH>;(KM~pfO|kw>v3??L`u~$+eW4th?~w5<4w4bx Q2mUVorvEGM!u7lV2Vr+Y`~Uy| literal 0 HcmV?d00001 diff --git a/Svc/ComStub/docs/sdd.md b/Svc/ComStub/docs/sdd.md new file mode 100644 index 0000000000..d05fdfc46b --- /dev/null +++ b/Svc/ComStub/docs/sdd.md @@ -0,0 +1,96 @@ +\page SvcComStubComponent Svc::ComStub Component +# Svc::ComStub (Passive Component) + +## 1. Introduction + +`Svc::ComStub` is an example F´ component implementing the +[communication adapter interface](https://nasa.github.io/fprime/Design/communication-adapter-interface.html) required +to work with F´ communication components. Projects and users may choose to replace this with a complete communication +implementation (i.e. a component managing a specific radio) once ready. As long as any communication implementation +implements the communication adapter interface it can drop in and work with the standard F´ uplink and downlink setup. + +`Svc::ComStub` delegates to a `Drv.ByteStreamDriver` in order to send and receive data through the driver interface. + +## 2. Assumptions + +Using `Svc::ComStub` assumes that the driver layer (e.g. `Drv::TcpClient`) provides all capability needed to establish +communications. For example, a project can communicate over raw tcp rather than requiring additional protocol on top of +tcp. + + +## 3. Requirements + +| Requirement | Description | Rationale | Verification Method | +|-----------------|-----------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------|---------------------| +| SVC-COMSTUB-001 | `Svc::ComStub` shall accept `Fw::Buffer` for transmission and pass them to a `Drv::ByteStreamSend` port | The comm interface must send `Fw::Buffer`s through a driver | Unit Test | +| SVC-COMSTUB-002 | `Svc::ComStub` shall send a `Fw::Success:SUCCESS` signal via an `Fw.SuccessCondition` port on `Drv::ByteStreamSend` success | Successful sends must notify any attached `Svc::ComQueue` | Unit Test | +| SVC-COMSTUB-003 | `Svc::ComStub` shall send a `Fw::Success:FAILURE` signal via an `Fw.SuccessCondition` port on `Drv::ByteStreamSend` failure | Failed sends must notify any attached `Svc::ComQueue` | Unit Test | +| SVC-COMSTUB-004 | `Svc::ComStub` shall retry sending to `Drv::ByteStreamSend` on `Drv::ByteStreamSend` retry | Sends indicating `RETRY` should be retried. | Unit Test | +| SVC-COMSTUB-005 | `Svc::ComStub` shall pass-through `Fw::Buffer` from a `Drv::ByteStreamRead` on `Drv::ByteStreamSend` success | A Comm interface must receive `Fw::Buffer`s from a driver | Unit Test | + +## 4. Design + +The diagram below shows the `Svc::ComStub` port interface. `Svc::ComStub` is a basic *Communication Adapter* and can be +used alongside the other F´ communication components (`Svc::Framer`, `Svc::Deframer`, `Svc::ComQueue`). + +**Svc::ComStub Uplink and Downlink Interface** + +![`Svc::ComStub` as Communication Adapter](./img/com-adapter.png) + + +`Svc::ComStub` implements the +[communication adapter interface](https://nasa.github.io/fprime/Design/communication-adapter-interface.html) by +delegation to a `Drv::ByteStreamDriverModel` as a way to transmit data and receive data. Other communication +adapter implementations may follow-suite. + +![`Svc::ComStub` to `Drv::ByteStreamDriverModel`](./img/byte-stream.png) + +### 4.1. Ports + +`ComStub` has the following ports. The first three ports are required for the communication adapter interface, the +second three are because the implementation delegates to a `Drv.ByteStreamDriverModel`. Only the communication adapter +interfaces ports are required for replacements to `Svc::ComStub`, however; a `Drv.ByteStreamDriverModel` ports may still +be useful + +**Communication Adapter Interface Ports** + +| Kind | Name | Port Type | Usage | +|--------------|----------------|-----------------------|-----------------------------------------------------------------------------------| +| `sync input` | `comDataIn` | `Drv.ByteStreamSend` | Port receiving `Fw::Buffer`s for transmission out `drvDataOut` | +| `output` | `comStatus` | `Svc.ComStatus` | Port indicating success or failure to attached `Svc::ComQueue` | +| `output` | `comDataOut` | `Drv.ByteStreamRecv` | Port providing received `Fw::Buffers` to a potential `Svc::Deframer` | + +**Byte Stream Driver Model Ports** + +| Kind | Name | Port Type | Usage | +|--------------|----------------|-----------------------|-----------------------------------------------------------------------------------| +| `sync input` | `drvConnected` | `Drv.ByteStreamReady` | Port called when the underlying driver has connected | +| `sync input` | `drvDataIn` | `Drv.ByteStreamRecv` | Port receiving `Fw::Buffers` from underlying communications bus driver | +| `output` | `drvDataOut` | `Drv.ByteStreamSend` | Port providing received `Fw::Buffers` to the underlying communications bus driver | + + +### 4.2. State, Configuration, and Runtime Setup + +`Svc::ComStub` has only stores a boolean `m_reinitialize` indicating when it should send `Fw::Success::SUCCESS` in +response to a driver reconnection event. This is to implement the Communication Adapter Protocol of a +[communication adapter interface](https://nasa.github.io/fprime/Design/communication-adapter-interface.html#Communication_Adapter_Protocol). + +### 4.3. Port Handlers + +#### 4.3.1 comDataIn + +The `comDataIn` port handler receives an `Fw::Buffer` from the F´ system for transmission to the ground. Typically, it +is connected to the output of the `Svc::Framer` component. In this `Svc::ComStub` implementation, it passes this +`Fw::Buffer` directly to the `drvDataOut` port. It will retry when that port responds with a `RETRY` request. Otherwise, + the `comStatus` port will be invoked to indicate success or failure. Retries attempts are limited before the port +asserts. + +#### 4.3.1 drvConnected + +This port receives the connected signal from the driver and responds with exactly one `READY` invocation to the +`comStatus` port. This starts downlink. This occurs each time the driver reconnects. + +#### 4.3.1 drvDataIn + +The `drvDataIn` handler receives data read from the driver and supplies it out the `comDataOut` port. It is usually +connected to the `Svc::Deframer` component diff --git a/Svc/ComStub/test/ut/TestMain.cpp b/Svc/ComStub/test/ut/TestMain.cpp new file mode 100644 index 0000000000..c156b08acb --- /dev/null +++ b/Svc/ComStub/test/ut/TestMain.cpp @@ -0,0 +1,31 @@ +// ---------------------------------------------------------------------- +// TestMain.cpp +// ---------------------------------------------------------------------- + +#include "Tester.hpp" + +TEST(Nominal, Initial) { + Svc::Tester tester; + tester.test_initial(); +} + +TEST(Nominal, BasicIo) { + Svc::Tester tester; + tester.test_basic(); +} + + +TEST(Nominal, Fail) { + Svc::Tester tester; + tester.test_fail(); +} + +TEST(OffNominal, Retry) { + Svc::Tester tester; + tester.test_retry(); +} + +int main(int argc, char **argv) { + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/Svc/ComStub/test/ut/Tester.cpp b/Svc/ComStub/test/ut/Tester.cpp new file mode 100644 index 0000000000..59788e8585 --- /dev/null +++ b/Svc/ComStub/test/ut/Tester.cpp @@ -0,0 +1,172 @@ +// ====================================================================== +// \title ComStub.hpp +// \author mstarch +// \brief cpp file for ComStub test harness implementation class +// ====================================================================== + +#include "Tester.hpp" +#include + +#define INSTANCE 0 +#define MAX_HISTORY_SIZE 100 +#define RETRIES 3 + +U8 storage[RETRIES][10240]; + +namespace Svc { + +// ---------------------------------------------------------------------- +// Construction and destruction +// ---------------------------------------------------------------------- + +Tester ::Tester() + : ComStubGTestBase("Tester", MAX_HISTORY_SIZE), + m_component("ComStub"), + m_send_mode(Drv::SendStatus::SEND_OK), + m_retries(0) { + this->initComponents(); + this->connectPorts(); +} + +Tester ::~Tester() {} + +// ---------------------------------------------------------------------- +// Helpers +// ---------------------------------------------------------------------- +void Tester ::fill(Fw::Buffer& buffer_to_fill) { + U8 size = STest::Pick::lowerUpper(1, sizeof(buffer_to_fill.getSize())); + for (U32 i = 0; i < size; i++) { + buffer_to_fill.getData()[i] = STest::Pick::any(); + } + buffer_to_fill.setSize(size); +} + +// ---------------------------------------------------------------------- +// Tests +// ---------------------------------------------------------------------- +void Tester ::test_initial() { + Fw::Success condition = Fw::Success::SUCCESS; + invoke_to_drvConnected(0); + ASSERT_from_comStatus_SIZE(1); + ASSERT_from_comStatus(0, condition); + this->fromPortHistory_comStatus->clear(); +} + +void Tester ::test_basic() { + this->test_initial(); + Fw::Buffer buffer(storage[0], sizeof(storage[0])); + Fw::Success condition = Fw::Success::SUCCESS; + this->fill(buffer); + + // Downlink + ASSERT_EQ(invoke_to_comDataIn(0, buffer), Drv::SendStatus::SEND_OK); + ASSERT_from_drvDataOut_SIZE(1); + ASSERT_from_drvDataOut(0, buffer); + ASSERT_from_comStatus(0, condition); + + // Uplink + Drv::RecvStatus status = Drv::RecvStatus::RECV_OK; + invoke_to_drvDataIn(0, buffer, status); + ASSERT_from_comDataOut_SIZE(1); + ASSERT_from_comDataOut(0, buffer, status); +} + +void Tester ::test_fail() { + this->test_initial(); + Fw::Buffer buffer(storage[0], sizeof(storage[0])); + this->fill(buffer); + Fw::Success condition = Fw::Success::FAILURE; + m_send_mode = Drv::SendStatus::SEND_ERROR; + + // Downlink + ASSERT_EQ(invoke_to_comDataIn(0, buffer), Drv::SendStatus::SEND_OK); + ASSERT_from_drvDataOut_SIZE(1); + ASSERT_from_drvDataOut(0, buffer); + ASSERT_from_drvDataOut_SIZE(1); + ASSERT_from_comStatus(0, condition); + + // Uplink + Drv::RecvStatus status = Drv::RecvStatus::RECV_ERROR; + invoke_to_drvDataIn(0, buffer, status); + ASSERT_from_comDataOut_SIZE(1); + ASSERT_from_comDataOut(0, buffer, status); +} + +void Tester ::test_retry() { + this->test_initial(); + Fw::Buffer buffers[RETRIES]; + Fw::Success condition = Fw::Success::SUCCESS; + m_send_mode = Drv::SendStatus::SEND_RETRY; + + for (U32 i = 0; i < RETRIES; i++) { + buffers[i].setData(storage[i]); + buffers[i].setSize(sizeof(storage[i])); + buffers[i].setContext(i); + this->fill(buffers[i]); + invoke_to_comDataIn(0, buffers[i]); + ASSERT_from_drvDataOut_SIZE((i + 1) * RETRIES); + m_retries = 0; + } + ASSERT_from_drvDataOut_SIZE(RETRIES * RETRIES); + ASSERT_from_comStatus_SIZE(3); + for (U32 i = 0; i < RETRIES; i++) { + for (U32 j = 0; j < RETRIES; j++) { + ASSERT_from_drvDataOut((i * RETRIES) + j, buffers[i]); + } + ASSERT_from_comStatus(i, condition); + } +} + +// ---------------------------------------------------------------------- +// Handlers for typed from ports +// ---------------------------------------------------------------------- + +void Tester ::from_comDataOut_handler(const NATIVE_INT_TYPE portNum, + Fw::Buffer& recvBuffer, + const Drv::RecvStatus& recvStatus) { + this->pushFromPortEntry_comDataOut(recvBuffer, recvStatus); +} + +void Tester ::from_comStatus_handler(const NATIVE_INT_TYPE portNum, Fw::Success& condition) { + this->pushFromPortEntry_comStatus(condition); +} + +Drv::SendStatus Tester ::from_drvDataOut_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& sendBuffer) { + this->pushFromPortEntry_drvDataOut(sendBuffer); + m_retries = (m_send_mode == Drv::SendStatus::SEND_RETRY) ? (m_retries + 1) : m_retries; + if (m_retries < RETRIES) { + return m_send_mode; + } + return Drv::SendStatus::SEND_OK; +} + +// ---------------------------------------------------------------------- +// Helper methods +// ---------------------------------------------------------------------- + +void Tester ::connectPorts() { + // comDataIn + this->connect_to_comDataIn(0, this->m_component.get_comDataIn_InputPort(0)); + + // drvConnected + this->connect_to_drvConnected(0, this->m_component.get_drvConnected_InputPort(0)); + + // drvDataIn + this->connect_to_drvDataIn(0, this->m_component.get_drvDataIn_InputPort(0)); + + // comDataOut + this->m_component.set_comDataOut_OutputPort(0, this->get_from_comDataOut(0)); + + // comStatus + this->m_component.set_comStatus_OutputPort(0, this->get_from_comStatus(0)); + + // drvDataOut + this->m_component.set_drvDataOut_OutputPort(0, this->get_from_drvDataOut(0)); +} + +void Tester ::initComponents() { + this->init(); + this->m_component.init(INSTANCE); +} + +} // end namespace Svc diff --git a/Svc/ComStub/test/ut/Tester.hpp b/Svc/ComStub/test/ut/Tester.hpp new file mode 100644 index 0000000000..6f794d6354 --- /dev/null +++ b/Svc/ComStub/test/ut/Tester.hpp @@ -0,0 +1,104 @@ +// ====================================================================== +// \title ComStub/test/ut/Tester.hpp +// \author mstarch +// \brief hpp file for ComStub test harness implementation class +// ====================================================================== + +#ifndef TESTER_HPP +#define TESTER_HPP + +#include "GTestBase.hpp" +#include "Svc/ComStub/ComStub.hpp" + +namespace Svc { + +class Tester : public ComStubGTestBase { + // ---------------------------------------------------------------------- + // Construction and destruction + // ---------------------------------------------------------------------- + + public: + //! Construct object Tester + //! + Tester(); + + //! Destroy object Tester + //! + ~Tester(); + + public: + //! Buffer to fill with data + //! + void fill(Fw::Buffer& buffer_to_fill); + // ---------------------------------------------------------------------- + // Tests + // ---------------------------------------------------------------------- + + //! Test initial READY setup + //! + void test_initial(); + + //! Tests the basic input and output of the component + //! + void test_basic(); + + //! Tests the basic failure case for the component + //! + void test_fail(); + + //! Tests the basic failure retry component + //! + void test_retry(); + + private: + // ---------------------------------------------------------------------- + // Handlers for typed from ports + // ---------------------------------------------------------------------- + + //! Handler for from_comDataOut + //! + void from_comDataOut_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& recvBuffer, + const Drv::RecvStatus& recvStatus); + + //! Handler for from_comStatus + //! + void from_comStatus_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Success& condition /*!< + Status of communication state + */ + ); + + //! Handler for from_drvDataOut + //! + Drv::SendStatus from_drvDataOut_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& sendBuffer); + + private: + // ---------------------------------------------------------------------- + // Helper methods + // ---------------------------------------------------------------------- + + //! Connect ports + //! + void connectPorts(); + + //! Initialize components + //! + void initComponents(); + + private: + // ---------------------------------------------------------------------- + // Variables + // ---------------------------------------------------------------------- + + //! The component under test + //! + ComStub m_component; + Drv::SendStatus m_send_mode; //! Send mode + U32 m_retries; //! Number of retries to test +}; + +} // end namespace Svc + +#endif diff --git a/docs/Design/communications-adapter-interface.md b/docs/Design/communications-adapter-interface.md new file mode 100644 index 0000000000..72e45864e0 --- /dev/null +++ b/docs/Design/communications-adapter-interface.md @@ -0,0 +1,63 @@ +# Communication Adapter Interface + +Any communication component (e.g. a radio component) that is intended for use with the standard F´ uplink and downlink +stack should implement the *Communication Adapter Interface*. This interface specifies both the ports and protocols used +to operate with the standard F´ uplink and downlink components. + +Implementors of this interface are referred to as *Communication Adapters*. + +![Communication Adapter Interface](./img/com-adapter.png) + +## Ports + +The communication adapter interface is composed of three ports. These ports are used to transmit outgoing data through +some communication hardware and receive incoming data from that same hardware. These ports share types with the byte +stream driver model for backwards compatibility. + +| Kind | Suggested Name | Port Type | Usage | +|----------|----------------|-----------------------|----------------------------------------------------------------| +| `input` | `comDataIn` | `Drv.ByteStreamSend` | Port receiving `Fw::Buffer` objects for outgoing transmission. | +| `output` | `comDataOut` | `Drv.ByteStreamRecv` | Port producing incoming `Fw::Buffer` objects. | +| `output` | `comStatus` | `Fw.SuccessCondition` | Port indicating status of outgoing transmission. See protocol. | + + +> Note: components implementing the *Communication Adapter Interface* must deallocate any `Fw::Buffer` received on the +> `comDataIn` port or must delegate the deallocation to another component (e.g. a driver). +> See [Memory Management in F´](./memory.md) + +### comDataIn Description + +This port receives data from an F´ application in the form of an argument of `Fw::Buffer` type. This data is intended to +be sent out the communications interface managed by this component. From the perspective of the application this is +the outgoing data port. + +### comDataOut Description + +This port receives data from the communication interface managed by this component and provides it to the F´ application +in the form of an argument of `Fw::Buffer` type. From the perspective of the application this is the incoming data port. + +### comStatus Description + +This port carries a status of `Fw::Success::SUCCESS` or `Fw::Success::FAILURE` typically in response to a call to the +`comDataIn` port described above. + +> Note: it is critical to obey the protocol as described in the protocol section below. + +## Communication Adapter Protocol + +The `comStatus` port must obey a specific protocol to indicate to F´ applications the status of outgoing transmissions. +A communication status is one of two possibilities: + +| Status | Description | +|----------------------|-----------------------------------------------------------------------------------| +| Fw::Success::SUCCESS | *Communication adapter* transmission succeeded* and is ready for more data. | +| Fw::Success::FAILURE | Last transmission failed; *communication adapter* is unable to receive more data. | + +> * Fw::Success::SUCCESS may also indicate a connection/reconnection success when a retransmission is often desired. + +A *Communication Adapter* shall emit either Fw::Success::SUCCESS or Fw::Success::FAILURE via the `comStatus` port once +for each call received on `comDataIn`. Additionally, a *Communication Adapter* shall emit Fw::Success::SUCCESS once at +startup to indicate communication is initially ready and once after each Fw::Success::FAILURE event to indicate that +communication has been restored. + +> It is imperative that *Communication Adapters* implement the `comStatus` protocol correctly. diff --git a/docs/Design/img/com-adapter.png b/docs/Design/img/com-adapter.png new file mode 100644 index 0000000000000000000000000000000000000000..ebe740facee434a38ece96e58900a6d61893e4a1 GIT binary patch literal 92476 zcmeFZbySsI*EdQjp$G_qfRr=}NOy@yHDU#os|uDNDze>oXZbTk4qI5;?Taj`cFaByfeaB%Pe zDEGmgq(hB5IJk%W#=^pK;=;nDa@H0G#-{pkaAN+^D#)seJ-8_v3S?Dq2nw$)K8vA~ zQhvb|bjEr^Ndf=bp9%BLuD*O*b>KbI%>qB2+-WSHzz_R@_wMOyzWf=@L7TSIa@c&) zQh&7QF?hAnU(a&3055n=q4IK2gbl76`-zy2Fv3&aNX4gFxt<7{p7*;2ef#?GDl;<4 z;a+<0E%r4M!i86>5b3Gk?%tM)L^5`7zzb5to3vKWJPg-O<{;W7t8M<T~KHK@|;mNpE*@Gdia3>X5%{E z58AF}|9h4~bjJq|t%Piwp35|GCKBQn`yp%Je-1~8gm6EsJ>e0Rmno^~PVv5vLqN)h zZ}%RDp(1?~>UkI<7IEgc#P$fsTY&7b=T*8D{Gk>+&6lewGG!|}IQ+wf*B5@ze&a0j zVm`9|)vUxX!MaM1#p@OHn`EKB?C?WVeOd42EuTQQyP;~BzZ~T+;tSA3293+oqmdZeXGhGofWE=`xGOdd&5zsO~1 z{kP(@971AGsGwb5(9ZJxZ}1L2?y7Yp$Gi8{YM9N{l%EP1-h%At@Kyeb zmR%rJsZ!B~P$7Knvg?XQN1CLU!zFLS@OGD^V#wF*d?@DU>s?a&M?5~7-$HawJiU^? z5tJ$K#y!L+E}=f0VB4fuCYF6Pj&<{WaVaudpLsF=M}F5V$dfU?n5i` z+)eNz7a`S^Z62IuOE`5j4jt!vd$Mn}U%2OtFTXvFLnP!RFH5DodzZN66 zMyvO?+f#1l2DD@uaU`n8@ecAi+ z{R@jFqaD@)mj4^g47L$ONT;3-yA^>IlNF*B;{ipv_j%k;+2`TM;-?fO3ON3fbfnQ? zli~J}GGQfQ4PqqSbb8noEL?F(uW`dSBKmq7ySsW+x`(<`X$f#71MnyV+H<9{UuK(T zvdS|kHqfNzCn%W|V6demNGA(xN)~6Qq%UN)$ji$!DFT|yV-@r(s})wrt~K=vM~4=u z7uXk=PAI+0-+nwnR6zaCqOc`>#7LRdLmjQyv*wGkG>^24AT;f*ijC4r-ob=H{=2-1 zd`)?md>Q##CBuAKIYwnh6@ff=wPqFXjE~uElS`la$Mc4b#_RG&O2wz1W#ebZ=hmy* z#ID~PFsF}*iB=B7)i!CFR4yJ<58Zk?pEQ_rw0X2SyJ@(oIrGNM#4N6DEu1qtn2?)_T$?(|*Km*lB?7baU3 zOAuR5ZPnr%f)2hMED*4j#lJZuonghC(l^=Xmw%FR(={>+SguVC%wj&UPnniZyV(?Qjq!eWjdrSZO7-#Yd>Xig%ZBUl zk~T)F?`0ob%*M+_4K)o)HTtrG+U=Uj%5_ydjVaZ|%Jk{;X{nn0ih2XdD*c)DpXOy| zwZeOIyA`{1y9~3Lr;yXvQ1nwGaujl2QNOoJ!F5|{+uy8dZ1b!fH}iI${^Fb}UpQD3 z3k;_vj}7JJI82O8R4f@|&uz@Cdg~LMz*As6Zeqw|m}28|#D$>y@1x82}N^_Rl0T|T849ylNI$o!26yhBh4E3NyR#rnkL z_1tj$mfsWyHISGQ@o`;>J!GQd&UwCWyqouPt9)a5(+YdVzOy+H!%v&QgQJZ~C}B7$ zFC{KPHTj&M_LZ@S!p6^VUBjT}DATZ)Qs!c0*%UdZvRfp0tmY?mB}%p95#xj_#a(#8 zt*_cXyoP+y#h#$HrY4pm&!WuUlYq7dFDqL?$GEnlx7>KyEztMxEvB{xERz4mD#GOL z``x1&K9al@SYAUL&QNqv&|Cqsz-z6gu9Yb!8Abjn zUXM55NWu4~*8As>q+K?rlU084Iz1Qu2m$`qbV0(K?pg`6tX44++)G?#9QU{g&b1HW z2H|;mb_Mg}B8sU`knwKW(NljUPV&y%UM6i}7?v5B#{2h6rB3tqxlUfGX;umw>?a8) zN3v|3)yvqZ^t(wOW<=NUehV zRwr|A#bE_wpi>~@4fpm`b?c*-J*uNM<8E6&^gHx3^f_Xn^o#YcZA186%ied8=5*tsC_y;mf9pW`>j`{~Wr za{I`UoC@hw_6Hn`Gmk5>OL_|mTwhq3{F=<2eO#Li4ZhGgvG?B7pKXO;?rqNDH&$lP zWHva*{wm34GYYQCF?865obq|O5PTx~RJ%JduTg`s8wqh~5iq+AM*M}GfWeG0NnF9J zhD%@Irg0iT616R=e0u7uujDu7%#D zb@ldkAf&d$A`zMiC28t&IlFM%LcYe}5nvWbfkqu~O>fX@i)l}~S6|N@(_hUtdo_8% zGpV#k-=cje%fQEnYg&MZqsNEi=1rCFq8;=&{7f@gWQ}x#t(=6l)=A{4ett_l_Tbjs z9HGpDkk?(v?L-MK!x*l^1!25XKkre>#Oj8G8d^p4KwnkdKw27(4qT(aA;A;C-2+$f;KdJ5_^<1?@HB9UclQzC z;CzkYkp6l`27JQ)!oUmG=FcZ$#8)_E@ZV$ba!f<``)M?qG{nEJ;RC>Ta6*d0;^N>_ zQP)~u-`vK?!q(i1W*6K*wG>mcfrG=PguUR!6)1j#{-=zURBctIrMPu1%oslES?K69 zIGS0)`hnwhl7E5?8I4Vv=8?sCf+JL;RNy)iZen1M0)S-4nv@1Fl3-~88z z|JG9VzgjZ0zk2oWP5#xTD{^ef{c^P3#|2HW9;Cy!% z0L_oa%lI#%@uQWP%cKK3J~MtJs{}p)m)-q!f_Gs2!ofblE3dX2uVVuaP7qG~jgXQf z{O&w*63*Jiw*%h=mnU0dj0*RJ?!76m{mB;dbWB$~!(ZHVMD=knL1Zh{r`=|Ua?(6f z5kYRT{Sz7ohUaR1Mv_>X9Xgh?tCZt{Ol+drN2;*koC*eE>m`-j+5 z&{(7YGnV)C+(4k9ahBrx3Kbz~nNtOR>u78P^|D0U^O``wj;+84l)dNYz_+&g0q9DCq)2`ah$9bi5a5vzo(nb+hJ8(Y3hsOQB6Kto z>sZr(UYp?#%r_Im&|o@Ry5QRntM(aU)L$)w*iPYKqu0U)j#VvcqlT4x3DpGGYW$#W`eoj-SyMr5< z$Eh~ipGpfog#>><&wq@7qL&GJVXxt~dkb)R`~Y*G%Kjrg0?HQ+Pe+cqJ<%y8{d*f<(zyb8{t+!Ips@9B?J9#h^OHQjXpVx4%F zQ(-k03*{euui;_yU<4pG%dNtI6SM`_nPV~INbpFHP%!tcDeqLbIxyHgLDO3}FB)+3 zZTgdZM4&D$B@3#q%ooYXjWZs#P^YfVzxx*cXIzYuInY&Me} z0MquW0R8tpUbX>*@dk^0s_xGW)05+|NEZfzcnn40;4NSaJ6Sb?%_a(|9e3Zr?6ZzH zu5Zr>-h0}2g)G)OQ8&n03@|FIAh-ks=#Li4Nsz?;{{+SkZ*>9h&1e@wN7$;7W;vmB#Mc{!MECkTQ z*836{ENuBl?l#I7O+dX}da(=G?JATnvbn${s9*oAOt2eSWg(+(@p@Nq^D!- z19+IsBvtb&>u6MqPjfuJry>@~z87I8Sp!1_vs=fDzECA0KP9zC2fiQ#4&fsX=>ocL zp}YaC84K7u@m3o}D5P>spx=Otat<&?m^8ROJw7x3#A_4A1G)71s4yO=6;uTqK~k|;d+c;WX3L-hgX)7B)6_E9!Pa>NnChe}I`jFz4<|_43x<|A*WCUpcno9q zshn{XfXQzS(uW7;law^4&zvG`HwAv~*KC}FA>a_O9;@=}2J{o2S$+BR<{bd&UmbuM zpOXtV?S#G%1;~4V-mb0I@?i6V(J6DTVI19S6BU3}DxHt@2dt-eVDWCxNoF}g$*;^^ z{sorwiw(+Ism)_kMx|P%xqpg{(SWIxe|H7XE+3Tz?{L>I|>|t z?B7U$Wb=5>Mfcy<^lwCaBMWHbY$g#5+Yznz+A;SHG(Rt+3fvZt7b#Bt8(K8o^9-p1 z2bTZ$&{}H{5RWc+cl~c@HM^X4i{3Wz{9hw`%1xujwYkGzYyR{NUG7*Ue^bUYA zjOn}WFEDyD0(!SH83GI}0KJ>7R%u}Lt^rgw&fUGK{fM-< zoXFs1}D zW6D8C1~erGBRC`Ve1wUwm)I!IO_HB=Vl=~)@W5k&q-D!U3a-hCRCvrq|8vmDbfrL1Qp|Pu%W~6BV#gF7cc{RqHSUHqHPr{0H9u!22KW z{f}^f$(H{JhyU-$UZi(vqz;X%>!wu!Duw25#y^+K(r}}#eWZZU*F%46h1IPCQxQ3C zV%T2j&wi~|2&>inG-W}t=Zq2diLF58>f1AzE{aknIJ~0y7zfeyfI_26^Wvi7V-G^l zVhlO-bT_;qI8prCU?5v9@sUEl^_m_A_RqajT)e)9&K!3Q_MQ@=3o1V&(v!rRusHXL_Pl1Xg2|G(iMswJKri$f7WBXxmu0`5fidum=@W^Oqt{~oB_J73VcPq z>Hd6cRbV9AoNo$7)3>|=23qvQgLT!y7w;Y$k2TBoo>AdSJ)>4!aBkyP?z$0Pt&=PX z5g^*f5)%jTP_o;D@gAap@#ynCYTxe7tZR7)=TFrc_m;mlmR4wL6l-zcqgCTSN{kyA zyggc!?w{f`AhLiR@Oh|6Fgum0LuD={<9Yn)FTx7T_Mcy>jpiDXAM)=!Hy%m1X&?Gt zW<9dXsQ)9bHfxxI>IWm+&SYffV3Qd4Dao^2tbN!?J9H16-w-Dsn0xyRNDU-XmCSLY z$JTOZ&Sy88Elhppu~r%}6LY82AxQvrkbe5BEYK%Z5#;?G%tlN%7pr#&I$BAtcFd=n ztmEHRWe&EeIzMBfEAE_YwMgA%LwvNEfwA03@`G`vT2iZNjUboT@V!SME7SG0kmjU2 zhb+I_l~ArD_4V@G7v-aB@*#LaVsbBw&3fgZu%pKTE#w=)mt~-6_`?S5+g>c5PYbst zv~RK{VecIaN6&Tp{k5OyY=o=^Z{gH)yg=nP?4$@LBr+&4j~!!?I>WTgW`qv5uraua zXtLkw9uK)w7jru>nnen_pAJAv`V37@I}DdGeDY4X9%9W={ir?i>|>ZC(hCl-Oo| zSMTe7;cjdoYieF9aj}1M4PA>T^jO|q%rVq9!P%ZUAyBna!ZAp(rR#bC(*?c$>@{pw z^{2|x?$GSGaO@LQZ+o}SpZR1!KNe;Uw8kpE_0*Qs)~pMP;IM-Z+3?n<<_I3_qCb#g3Y0=DHEuzd7RU zAz(ORt;Xb%pm^XctPE(R`0CXLALHHjd+=xbeNp+a zupWH4zId}6bskJKhjsD2`@sWv z9_WT{%#6pp(0*1NI|4R-y`$z%7rm~U0fk0)@_gmWb+Xjhs@J))j(a5nVnPshlgJoR z+emqV2C5uWk$d+Jw{D58--eCnz8Jim-=idA&OQNRGCH|lBU@tP(~q2w5?x{jxwgsF z@fBt02q;l6F^?IKBP0i@0mNnq@;l!O#FBE86{6|hNj&Y_qi0|*{}cjDH0@90`H{!^ z8Rgr9dm7TF>Mwq|b3c~(6~dc8R^|`{r07Md}46 zt_CrEjR>5V6bx1%J4;C1e&oNm;YRx?w7{OPn}hjMwus21WO=?(TKh!#s4+u)lw$84>`DCXTJEI%Ug$F#at5fAlo_4}i@ZVT^(zC4c5oEN>vdsg&yJ9H zTvHa!%DAr4n%t5P*!Iq(v+M`T_76?yv&yyHhMx%DDo#AY zROcq9+El$>iT`SfZ_oe;V#)UFNycj#e)nU3!^TRBCPji8&fhp44?J$FBa@uk=+C<5 zqO>Y4LtIZg1d6X8?N3U|G+jDxJiW{yWmGY6zY2MoaF|`$q8^+uTH@e={Z#YmnA$5y zyl7Fbsoi(1*z4CbBwXL7MG*<0J@WIn8M7n-_2QZ-N1VuO_kduKf{9st?_V9jF~jL) zy7^7w%guH&2RBAtP{X!*yw2Nai{*Be)%o-I*<-Go!Bl&svkeB>Hcx}|T}V6%Y>AlL zJL)HrPO!Dz-r~w$_d1uBFQ{XSZjUvevYK4l?tdE_inVXP>f2Z6IY_%C30!s z+c8G-v&0>C^_-jBB=TU5>T>&dwo}B5)6CjshuVdmgQ4avh8;U&w>g+|^K^rx`*SJ3 zjeF{*jP#6c7<}%Hpt>Ezoap`eOl=_C3?hlDyjVd2%70Yu2Q9IaT4jAhqGTZFh{pVE1-Sw#Muj4yZzGX1~+>Siqyjip(N5S$S!a_@COp1G{a|?k@tT5nKGeUJ16ACHAC^0 z&OZH5k7A0T<|)m+9TmY@J0stv-DLco>b~6Q`ugFa=vDtYErlJO+z-#a2l2w~2_CW% zq4~!Q7&xv*+vI4FY>f|Hu6i}srNUKB)!%OC`B2}Sb4SWKEZsK~mlbL_8=0Eg0Tbv-DLOO!vD?OeRNT)w#NJ&a%Mu(0oj4tj@# zcP>hC>NS^$*(#cE9rqkgNKy*4%{m;%XWULps@YZ6t}p^8ksKDx0@y4E*I9}%dMaHy zTyL_-WVf<)@wy)02s^|$;eXQkncsSo$#NOoNHpix$lboMF?5w$r1q+@L-&+#>*dZz zHy1=Vnw!9l8^Xvu0}q4S34Bjmq;!jc?+2AqB#s#(&{W2TYoVRYIDSatK1(JOd&Q*5 z;VRIks9qQlB@r;)sJh8;YF?(g)>JyTi0dU?4)zT~BeXj9RYvVkFU<%idwI?l4Vot^ zQlVWgYZE-~8=Of;zKvNzmAI$tgW5z{OJiNcwly~VelEXmg4Z`J8b$=5$lSEVBLI-L@x+Afy33qMi#)6uK`7Kg zT<+no>WfpiT5j^nhZk)a*|Wn~YXzMFYGe9WHlf_m&29#IZhLlek`k-8ej^xrj3#bG zw`&FD^xJtsBKLR(q-XPeUAaE#{Q9-tBjBb!er+oxaFn$fo+&dX98*`9s{G5VSa?aTHHDb0 zL+oe#kvM2Xe}4JiVUNe{$L2{7)|#TJs(L#ctJzDo!Al!=k6czG_sz|v)BBKy>7Dby zJ4*mqhR>aM!Sxo7-|HsA=o?Le%OJ%q3+bq|JbyF0{;JM|jt%1KIikeasIiPX>eqV|nE-SuhB;@;pwh8|t~{$NQgVVT`t(PA&3eVr}o=4?c3(>&E7b;Y-L^ z5aYkt;P4CiS~+o*Gd$w7yZD?NQNEV!`vA@;Te9zx?q!`OYCzP+@n;7crAYk3SDRRoRaw`K}LXYQx zkegJ;tmLsUMwM!NXyHl|TNIB?$6dzj4W6%gd(6`(sxa6n@3g!toC+8z z>H-CY&lwBeM#gX7^FkuL5g9mXnm|C>aq3To7(dL+mZlPtznHT+kT=wR$rpmJpC6Np zQ7!X5#{e!{+#sf7kNGIlAz2y!lYzsyh@s>7?K0H)geADSV4{e!>vnTWq0*kn=^Eml zDPZ!<+Hp#&Vmb(CFNE+i-d8Y$6~lXTS(LX(k)`!)m`Fw{9g)F!dHp_1#>$M3P4UsT zz;}kLa9d*5erIjv#kxvtpw^R){=HY$Hf}zTF!sF}6OU3Z=73yRj?rccBq7IT3Aw28 z>VKAU-7|(3zqi~$oP5;@VN|&ualN#w<@}Df5f~gxBD#DO@k`(;-sb8J zQKI=q#t~2RW1pb^Gi(vw*%Y9;@RI{Mjvtd zEdNjaD9`Q#ZP~(4@v16zA{Jq(u4o3xQ?*n3>p3RlD`{p2(KwmuIg<|Y zNv3(QC0re^p0wJgNK6beIQYi$z4L?QktZ}c_Eir`w`2||S#zI!Wq=S`ouc#ZARdLf za5pj-G;F1BTn}I76*Wvlk6_`0JU?KEiyZ$1*Q2zUK8{mFi$3)pQ=$ATN|zcd*f^qE z2QQ4L8dL4mwpp7P=be+W6L*5Q8H7VB`6Z*$RGVBJ`cXW&ueCSYx;SIcMMD=hc*88t zG#jBICsef|&y9wjS6QDv#6R05AH0dZ-D@4RKs$RW3VFlpvI3;}J~qySL+j$h>DeTs zw}T^I2(}}OWI*LpXC)KFlWrK3C$zJorul?F^r|QNq?KfPSkry})HG6Qs;tw?H~ZL4 zJdoe-c3a!R(mZ9B9HUsfLXQ7t=z7vT0VV%>_jHrL!MeG={-)fj3eRCQFC^l;NB4}U zC(t}L;3j7*KT1^7DLDF7-bToNF3I)SqB=&_mSJ{v@L@K}GWk#XPCF{ko2 zTb<427NI1gREq@<&GldsUAOV{#Sbh4hq6Uef0(}^)!Ej;_2-7&VqFc7yTaBh$u(Yk ze3-v6Impdd+;ej-xMzNp!m*M6IjC8RmWbZ9(vBc4#br#e$IX-EKtEY@lp zxL%!-Wx8+PhseBeh)8$G^}yagbQuW#QGlE?K0HL-bd_bJJDfsgCM#dgdz-7h*)_RL zOewEYl*FU>gU>B(rJsl+SD_Zsa7i2H9dQEM%4+e?#~@YW#sALh^QZv{n1-_9rrP=1 zE$3hG-x*e%)a-Avh}@1*%74xXNjqCO8xx_HDA8c^h>>!GepBj!Am zhlIBNu0hUHZoZt1fe`llUuFWi-YP5i{x3_@t?F^4YBvIyLzH(A5kDvSX)_WgfH42oDkdoxCh*pMmxW=s|UX72kP~cd(_rQ z+6LEQKiysY47fLT{)mKHepHi03km|3JEe@GAfsU)3Ano&ju7WCq&r^JL*@2->lOEe z>199bsBxh{tha^nO>hUIhf=R%tJSgLhFT6D?NpN-l<}zOY+k5{#kO^EchYwEv0xNF z3rc2a-ns3k31d^(CUkhz3mj8^L4Rx7`Smf__%p<-)SN%49KNeup|ee z+t))uXdvUnixllmF`{I!9bMI%KpCHjDJlG%K%Te!J6~H>$2hw7Gc&D<;<(<$#L)^I z+OTsemeto*^0eD(8lwhqPy8_PXdan9>4m0RYVABYQ!+fwTT4`-kHsKv>6;!TV%h2C z6A{soJ=%5e<%nS7ih zhB{>2;j_p^XL($itM}UKJsI}xdDZP#it3*;Vq3S4T_LOQ&MewSALGoU#yAI^FWOyd zl#@Cnx>KA6DL{}!&Mf#$$Zy19A?2AoF5nPUl7pE66@UhMyilPCC8%6qWSY_9PN)T) z+quvYZA;>nk10z%Ja8(ma4?ZeQ^%&|@x*ZWz9u<#JjFmZ%miwi&v+1_mD5qLzD)dJ z%dbZ-a@($<8Cfk>hSb3SD5&=*uKu)La$oZZX+!ylBA3B?uu0CD*gSzEEKJbH7NEc8FTXcB+CXvekA@oAefQh~BXFZLR= zZ}yZfmVLS;W;-s6G5~^Ef@gjn5bV~op+>#F?X^idmj;tkY#fKRjYN4okCh~4Q5)0Y zqUqq>?{Lrh zgeU0u83Z*`0aEumb_raxr|w5DSj{ z!1!b)e6dE1i9n=IaSL9?MQH-0ztxEZZ2ZjPcuW!pWe5O$JO8?&U zW(_=K+$45I4;z;PzErC+*(CH6KwD1KzJtuJ-y}CL4QA?a4Laf#-K{Lg@t~yIt*1r! zLI;vNdrLM9(U9+N6Bw5n^+pMY)OO|s#`oNM6R$1yV>kCdqw4DS&N8Zzs3}s+xq9^5 zI-T-gR%Jc?=%{6`lqjwi#h*2{S^RWZ-a8CQalnn+ujxrtUxA=-(u+d=vyp9}7Lfw@Zk>-{3vY!7*~2 zGrl|YsAIsLie}r^@>Gdb{Zy+fb-Cnq|Bgg7o#ZWuI!Hvnpl0LN>mO`_MWPfiL1q|y zuqHT%$YBAG%+bGhy%rTsgQ%Po>$PP@U<(MjHJzL#CcA&ytF#y^EM+yD*D6phrea)h zF0Rx7JAQr)`HZa_t zJctg=F9*2DfmKfhQ)uFmM2Otf_Y-IPjHeRR2xjf0z`lNwkXCov=ybTXf-%z>ev^A8 znBc(qnxNK{K2e$8&LHTRMab%GF!^xQY>G>tQ)fvoU#->ai2p_eSU%b2D>=s`UEhBb zd%b+}m(P?@>I|;|ck%i-y^$M2va1n|l8+zYSlncDYc^@X9sTWIEkEhRCnX2_ z*;bF%ric7?VW+}Nj9RmjEq5cn9fmErQjynQHzF&);tdkH;7*sp`7K?S3PL$MO zksR3_5{SYlX}P#=z_lI>b`V>mdslP@J&iNIH0S1&)`oG_y060yCAF4Y*{zyvUQa~n zf|IwM`E?hueD@9z^TOwYJrYhMS<=W{D-DRPK6CoUe?<^=PNkyKHoGji`SPL8gpQXN zqrg5$2fhPy=VmTKSi}vp+OakZ z3#W_!#6peFBIn+_S}PW=vrq@gY>8-!3I6c_DjN60pNNykgX(Dv!f(5WkK8v|moKvy zd%8jw44Y-ygqT_w>$0Aqo#jO!%J8T-hrYZZb7=HDCYgPFB|_Tx_j$3y!f(^!mg)t9 zbOQDfM^zF#xC40CkE>(DV{a8^PPQ0<&sF+xaX&df2%73#a%>emx9t8}>8v{PW{!wN zKR7LJH?~l-=8ea^Z0~mH70gA%)*jrvm-9rjANwH&7f1Xak`&bD%r68I;&Tl>?TKZ) z9*Te6o}9J`u^nFdDH}V}HCJvH=z4M($-ES0^F~y4Tz{01F>ZviORZGHVV|7(>U?Re z%$#NZn~a>)8t)|PImjqwrh~)lEgel*=s;xoDUQ*6KO(hozc+P*BVXrHOS8*bwnnLqj%skBU6jq9V`Z$9wmaSI zWHCF@2NljtzgT4s7l9jCF76YMKwF$g3I+bc2AD$lHrr!r{&wr#opu7`)V77M%KmvW zb|psZvEll!9HGIry_A%n#BG)!5}k}SJ@4<>Fb3l1{fIlEJkT9a`0Aah+J#2!gU5W` z5O^T;>L&-TZ)7gvwp?ez8-7-aYue0{Dt$3jydiC{;OqRY_G zJM-hFE7_9sGPm^!5nn}CXL3jWY|;^wC)+&Jz}GaT(aB9pZ3sllGEmV7V;N&YZ}u$) zPa*E-K=GP%L*Kid>LhL+4qUWNc*wO}k;>DPc@P6x^v|xAzH%3Kx6HRC5?Exc3@YjOJhe|&eoCn^0OmH=2g-&5CVhQbW?mw3a+0sezZp}xDLkey)_PLKL51E z`oS+d>J!N)uzv*3r{*i1)|d+)HV^FbBw(inuH#8LABm{3IyIfNXpP}oL!=$lO0WHV zyZDa$Kest(ibp|oKrf6UPZo4F_!;9pt@dfh9ds=;cb$eT`ww8 z3a7)Eb3BiEP-V*yYA!gGhH4g|2W#6&G;I&u9-j=j+~ORGn;fwg@Q0Vp2O-oOw3%*H z{xGoZQ1oz8l=__Gl7KT`wlhMWC6oChLzu;aReR=iSw?P7{*s%bVknE+O267b^G1t8j~f=$+D5jCztJa?9GI{ z3__TCcky_9p!_XWIM_i}kHFqd#$q zST;sAOesayuX5!cli9mOANVGBlobAC&szK7tgEQ5E!2^7sK5Ov#{`#n;N7OxE=}YE z`R@{G?|DyN6h2KLu^vP>ScMe4i(8&He|qygZ0#?X+}6E<_{&SZ^=B+@Z;S)oKW^dt zs3v5!Wv_gT#VTvYka`hZ$#5gGA=K49{Gi10tj7hI2w_nV}H}xqGIzw@^My-zX#{^@zs8qYprvC$OYzZcmmuFO5;CaG8`sDROT~= z|5o`REgu|sEwob?n{FHW2|bqDuE=G1g)ftBV@^h>4Jhn*ep#Mp3$T$>66+UFA@>V7 zEvLsJ&+q9@dxSD)mYluHEZxbd#C1FGZuXrst*y1Yorn($dFohIP3O*S;L`YFU*NZ( zqBv^6J*RpD`*h@F3QiY+v&D~iH)7lv1nWhIbVBlGwli(Z^FF{-OttZkl-o+`Khc4l zhw9HjOVvzRxrB0ArV=+3l^LQjZtX%%`Z^eaw)Es$I`;e_^5phI8IWn?z)o9eX1kgj zO5%|=&OW8rjU{kZuT=W3?_ook%tFhp^3M6T<(B5H{a|O{F-Qf;8A@Ow^Azm7^E6=N zNRAC-<%hCj7;m~coJC07iBUVa>@(t~@BTJ(YyKYB-ieTyOXYT!|m*~C@`9PO%e#&$gLdl{7=~4yHpn$3kcfw-;=F3n?wQ_=L%qu=Jk#YlR z2KD~>GsqTk@!tFulUqjKm#GXhhGwB3O8oWqppU91cLcbrm)^5PECYY1|Hbw2Tu@LR zIb97Kd1+(p=O*6xgI_yLyH};!c8XQqC9egCr_C?WW&xP&u938cS*#Ez7=Z zCT~n5h1Gu9#c;};&{j*)mde(UtV}oPDUSas@&hRnC=SbYB?EWn=qnaZFBhk?be?3r z#&bQsGkZvjyC#V?!&%LxI`mAt6-s4T?Q&^Er2o56CB=HMkkDA$V~UJiZ>};_6; zE|XbW>qk58EppLhb4uOq8huKsP4<^JpuFqSq8}eb3<+ToL&%M0Z2-TNLa8_lSCa{& zNtT}U;R`cbS(1W5+>6OYi}FXYn_ixp~OKmKC|pW)h!^^+Q9^?B~XWH3>)_ zOxj}FJ=rer+f}J!Sw!L)2$n>LW@g=N2OB0s(p#ogQg>gPjpR}}nD&KpqbEL#c&Rqy zeyQd(s5n`E4iu{^EMRdr2vo0wsu|3;upG{dEn-5F8XA?kUD5heoF{5yp2k5t#3ys1 zHdazVpr)|`fjVk?{t%R3QD9Cua%^8W=D!zy0s?kxu9SP37zuc*W-OVjRj(9x-Z2`p zn7AF72k&!8va#Gtm1%sRuaK=!JB4AV)b476=_Qe4(VEXCx(tsj!5ubXkpgm8<7rV$ zCJIx>xg@!jsU~->QTJ3zrzq+d4c9KDV~vztuRWxjcUX;Jet+8P-kzFZt-^a3v)Lu} z9CF150}7!%zVXI5ERQDqP}5Upih0hJGliBp4hh^XwK7Ym9O82cEvO;?;p3} zyKM@K#uv@j8E@(|2RyJu0ySvLe@ZZVYA9y!$&lWl{y5KlkErqi4Ma@SabfO>JS$pW z5M`hfM2^W#dIoU7>?Q!16d8Y_3lQ7{1sKAMUz9+F87hT@oYZU&m;4f_Q$d`fzyVcG z62SjJ5C3)IE;BD1?T!=5$JbZBr#&#$tW^ivln3+gs-xB4=FOkA-uL>#A&}jT>1RyK z4aR&4#_URa_6RoSV=(4RW1|9pK_t*W`LLf7yca9@$&om!&9J1ejvN%|B1~97xyGi?n+D|?g9-Z~%?LSD;Hbq1Ib;Kl*m7{NQ$6ah17=NMB>ir*QF_>7Y+Wq*fq_;63R>FC2qi!( z6eL(hTX(VWG}zztz|lUr1S{C{6s!OyeUC&r5m0{B!4qTj-|p%HE&tGjDQW6SHmvv) zQ>+pu;m7*hw!pC85Nto(tFxjZ09{~y0IP@NcqAhHZ{>_&KnhTqlSqM+2*CRRn1N*h z2?y2>O7>rlI43oEka+_%J=+H$g_CcdI0*x6r5A$8%9gWVBVg5bLLdzo-Fiok9SPGC z2&ccYVoAe_02UPrrhqBp!4m_v4=mkbSS0<0#fF_o{vRyv5)xT$EI~aiN*TZc-uzj> z9Tuu!rQd>uM?fo3jKuNP8>m}gKyi>XL513B0CX=au&6(pC@9{f{gdJ=r=^TT0G1#~ zIuCQ&%hn=qfHg0{s+{I(()D0yhJlrO&v8cqR+t08nxo%kcA-$fDo=}WW&svCFf8T~ zl1N}!FiclEllJ1a{Zlt@ryHh%bl$7o+>F#DoX#}LZOF9NY`mEXe`_B8GKj$CH%v#Ug z*K-$zY26O#C(G?DSbIfrz(-JkLw#w)EP^h=8U;MJt^=z(VBuDPeM&Uwmtg~sG0I^m z@lPECJ|IG-RHj0O$8T4f<oeMNc z9sO4OrJFjD{B_(GEXY0t_!}e8FRoPR{)#3 z-fKZ-0vl7yw%Kj z^^KMk>Q$3~v#7|~0q9Jd76>*W(F(}`GWqXmUS49S;MIpo_(F;CjQDcH%k|Ey^}?lk zDo4x0BXQsquLA9`NrhRA7y%*tI}Gy*<|D$%Mz3+a4iOgu^Zc2tM0`M+1PAD$wh*RJ6$jo62Hv}ynf8tx4KMIn z5;b53Rw=D?_`03=5N&o#>U`V}hmkAMh@<%VJa0lWoHr2T7H4S;jxz-%_b z9d+?n1Tl%tYWVX+1K*e^IbRHQv$grttKQwVZ-OQO-~z-P4lH(iuVp&*AHnmyb;mtR z3E8k1LM?Ke`JCF>QNR=J#*>*1XmlPS@Q%G66II~YqyfOsukElR0Eq_zj7L^;QThN? zVJPm{qc(*H&}N(vB!zMJ5;te;*U}7VId#yNg3tX_;anP8>i}l5OQ74$Mzt@4rUKQS zL}LJYfXQnk-3bltCQmQw$hc+~NA2q>tldi4l{;>ro-QT|m^uEb6eI9@5MbsFEvIEX z0MdglhRDLyg^E!a$k`*?j43ez0>I^V-<4|H+W$OQ6SMnJx51QTe(XZ7%|!>y#UPkP z0vqFA+gkJ1!u-3e0*$t$XL+xJ%JN6C^BMNUIAnn_^^|@;tltE1ECi5?20L4_7%2vf=F1hX^I+S7SU!`vy2-><6RVf7 z`+F3Xl()IiR(s=r6s01fbS&L?LyfWBJbg~0@=-`` z>)GrbmE+J0F7U}7K-_SZPQQEJX$2_}LUknz2GW&I1-d!;_z%^JTTI%YcOYMIa#R2t z9t0lDCNcR9>I4;mp9PF}NdaGL44epoi%A`D!Ii)*Zal)GH~~RSWHWuiFeNk^UlPi3 za(~V5V15T3?aWI+KmNgjP(9xP(Bc0&IG(o_iaBHtx99&d{H4pc-r`Dfi-8}wZUja_ z-A7ao&?ycqf&^IW-8U=@5YPwk9^FB&9Ki6}WPmMp9`p;K5&zGn)NglY(P;iWf5C>Ii zoA->seB*0dv!L zO=4*{C;%j41KSbn{;d-Lir@}JrWpl;d&I*Yy0tJxfV99oDB8Zp$@c+%{ofd!4zLwn zmd`i9TYf|BqdU3`8n>ZKdzMdSPtn2?fKw{l$R9zSCxCxo2LhT{{`A3bd3%)%Eo7A9c;@L9ER9EDQ8KNr(9b6#oAhvp8p!j>C;M^9pBWi=fRfaM7&evR+1`0}XN}$^JV3Y>mhHG8Mh0V&dvJ zf!V=4VVO#2=&bcGDWKzzHq7meOua&L%MHz^ zUrben^>?qelo}v&i7bph}IkY}rC#I-$GRZPd`1K^^9~H`NFb zi%83X$0*xtAB6~gdHZ$UkwCAlpNe8#{-jR_P`4bRb_}dk#(M<=pGTG@eJ$Fmm8L`v zdX4ZAg(T&YY$gf?K`Q%C=|FpYe?KIafYd&Nv+;<}eCiz@7o?+cPC%dLeh=?QkwI0) z)!D9gz0n-pl=sWywJA{Srn}n98esLE8g<1EfdCc^`wv7ZnEuy-12O;J?0A?#MyXi; zp2&)0zV6h+@e?r67|(Vfs#gf2WLn(wnKXUi1^<>8Sx-rRfXpZv?@(mMLRNRn|E zas*UtG;5eh6f$WVQma^Qi7UpMETbFCZe7JX-{(A+4BI3&xL@HF)`t6{)#N`Comk=eru9J?>EkOG*(QxT81n$L777 zxzN>VW&Wyo-p|;06(-VLQ8W5^uC7M(Pv63in@{6VEf_q?xocIC4i~!G@T8r( z!Gh*>b{lOgcRy=zDQWMi#+=Z@s{t9huB2p`w+Kl)xg@D!3}lKItNPtbI%X)Zb7`rc zavPO$^m*DRhHJIDgyEU{Mni`M|Kus|+05+$BM1ri7GeWxDT>4oVNENg71fYG`=Z+B z6zhz#;XsHWU4bH*r+0bJ2!)EIbABs$rt8i3)xaoQ7dsEwz746eAXL%o;jQ(r?Jsyf z^WuB!pMUcKz`HYqmIMZ25yoTHIdS$ATVK=R{EwfW`;)K8{U2uJ6LK@@gJO6jCffh1 zJj`C5CXHMTHcV>0X?%RH?kF+{nk5-_MbR0Il%uB2S?un3&z)a&!igHw#baDtxtgXb zVg2Kd1u4(UB&THgN_JB}Df+cyMXx4I?P z>7NHqn_tvHHyC`Nmq*j(^sQ&ezHDmp8|L|(bU&`sZ-<$}wZd7Q=(z4RLU$HE=4W2q zU5%%D4Q9+Vzap5_Iga6QZ{pAK=G!+b0!zF8XiXaTeHcDRsZ?Mj7`+r&(b^+nvu&%K zSVC7#t&q4$pi8D78O`FqGfR09txC-M@MDqyxJ-%w(FT!{QSc=!0b%r8v68PRAJg^0wZEXKafW!IsrnbFcj9R*ec<` z<}=3GbOXOCGQ_<;PdWQh0^ktB*TCFZQ9`;yoA!$PbiFUUqNS^Dn_U_IbL>Nv%i~q? zXXy$~_%r##cb%x-Lyk46CTtb`P6dhyQ*VwJBd zpAFMC{Qf#WGKSOBGcmN@c}BxByR%EaVX)rbGSF^0#nPVOCH8?E`Diww82M=AsC9?k zQEel`PdhfgyW-O`+5~8=+v1N+z2&*!QUWdrb!zGN18(%ue6xZ5in7s@Jg4xKzQLOE zv3{qHx^`xRK=IkU@EuT;Mf+<2jl=ryfXrN_Fs;HS>Nd(+hJ9pmPn}0;a?04 z99B0uLQwRprZ8{MH*g!O9d@Xl`vVHhms(WKN4N~XDcJe|ivncTF?XqST<@E{)d)~@ zTs8B|px8R^JR;_1>?|Y^4-LkYrvW33cZqS?fRUnaU^~M84qJQq`fQ?w*qd&r#fYgs^P6yR}FK)lR<=7&eS; zIMrDEdCZ0|k5g>6rlEFmh}qd+mV63vVz`_If)}q2RgQ&?6b-@X3M9?W%ufpNGJPEFY6kKxNNW1 zC+vBq-G-$`v>QY;GRt;>_(ew)Lue&!-IrUvQE!ue!byS7$y?cky})I=Fcop>O2Ma5 zsZr4E`kQY!;x!kOA*H(QJgbw7rM11uf6)F^ z6lBT6{wyf)w$o~tnooOPIo%Hg`XkC^1Rz4* z4}xz{@j|`;P0;n;y>=sPzG>~h-R(iw*uWp77>ML<0Y5c29djjwV17;wI_FXiariW(&EZ(Q>$t`+XFHqVZBcj$T^(Tx=^#x+x^$ra!vk!mNsdJAldnAwx=DC;<6<9AiM3m7l4r{_6`wuNH&E|Z zkFnEbl)zhH%tD*JML}wyxo3FwmcL68cd1cel9CBW>R^7ns65^JJj7{Z_-I_W$p4^u zy2g|s(N0T~&NsGhg_5m$BY~boF_+n0Ws`~mPI_fO+I(-{-oks&X8NaH&6t5puJ^!T z6|3(h9gnG$W10Ht=F{&vYV?bc$r2y`**E^YO*Tv=?@!3wZ0EnspVKj=NF$|;&4$2R zn$DnhwAgsox`bwm+iLP1EW9m-XjTY6AvT*zzp2>B>0pfHs38GMl9cb&!)YMd>Gt(tQpM6 z^kXYJxJZJ?=NPN431Cv5d-&8*EVg^;YH1vPlV2?J zvlA=?1D#WuF_7+ivGRp#8VbL^sog8L=f$_01C$^3_v{iz90fgwlL#V96q5GX zXh@v(1SGqsEP04*&uESPS&bK&f0h_)Zax zN7FwZ6{OB?M}e-+tX+wR+Vm)|r!Hezux$$~AY{@?;BH`S&ode=bO^H{|16_1kz-?T zHWYG0{G=!_=|u`E^OCYWyrr)UrXX%juYq(PTR|e*3f&m%oe{bstFm=}0QZj|ni- z$8l5%X=FB){7x&A9O|b-XS-O18=Hf37t<0c^BEM}*blVH(ch?Fu(5EYi4wU>&)t@? zIz*puF9Xke$0U$hD9}>;BhJbqHHHt^x*K8^3f7FB2R8*3$af7OojL;?54j*+d4*Z~ z(|RrV@P`s$jSC86=4i+ea`=*IE}rs?FZj|0cWn1=%%ph>T6BY^6RLqaE;MfifNJ-z z`8aZkd#+f*L=t+rje0WlnH@or+l|ufj`X0a8|5D zRNf8OnI4ACqi%ib3$jyZ`g=#E>G$gu^}bIwQv{W3VZ@GWh2tAG2{@m9ejL>vdS6S~ z1`7)adtqRm67(&2x%_yAo!(7f3H-N)PaF^<-undD>&zv*yFQOEs^x@kN}h(m6unW&?kgqm)6EV*XG zb3TIXG!uNLrHqN&kpZvoS}0Cbw34Hv?P%pL;2r#pY-MB+JJNjpZ!AMUrk_tIHhl^W zC!->`4QPSVHj#_N#f={&O_$i z-T5ng7kFJJT1?j)=TUhf{^qL_ms zCMKfGWFE^lxWD&6&t|Uo#_E6W8}q!UV*qSawp_kD840U=IuSJSZE%?KVN0BpoGw+@ z#dE#Cn?FeZ8|KM{d6b0-ZE%oE%CjPo1XeG59NMfMG%O_Fo*OzoW@F)CNr|%kSVi`D z{u8(M+4D&~o!ud;>3Ohwoe>!y7!Dy|)-(f}@s7VF;H4``it2T6Xy!be^lUQ!@Fv=# zq{TU`^tMnNz$R!OmSB6^5aYSnU{C*%{nj9tfNw6tM!Q5@@OJTex>}oJ$uZ_`Gt;!{ zFb?R`ljYhS4)&5Q{GMKXw;L#s-9NlX&@vp{Cj0a9X4t$ShV@Ol8e0Lo16u(Hv8U&@ zrseyVV*hz`%#Ey1Gx)uA(ogNq&vj2f>ue&a8J;1hFP7*0Jv+SBAb*5_->-zxULgj& zLahC2bgpi~Mir4D#UWE~r(I_{Gy!VPVm=*{-KLxzc}U=PH_>%JS#;hl)r^oQA6N&y zMo2KC!IuvB-3iHNi_|t?c^|aABVM7WtO$Cj`PU`hL%C1&M3aYVBF|jLY8Vs#iSKRC%DpgNyZ zmE_L4@sr7Aj}+DXEGBO0@|!=5EIy9RTSV?kI^okS#(e+A+lUP<)_4yCJb zFWm#=?rwH3*l4*ZbxrqN`eIqGiuWE5{_g@!UhwjPJeDg=t;d@uf`I1-`qz>j+V^Gl z3YU4@kUGl~{Z#Sg8AH2G{ij}b^CeRokM1rniv=8W7mJ3}UbP!mt43@~!Ar2fsxAm= zWv{zsX-`$N@_S)?GtsexV#qR+`v9lg!1^rl2<9}a_5EmxE3UV|{^`;vSvh18@>4CN z)+&9Bpd3a#4*}G&P=n?W@CrdI_|=JiMNt;iWF+5DsD%Yih?Ruf^xWDGlt{ zWy@Q?-aDq!aUN}?)Md!X$Nu)_zun{UoAHuv9cH$;6?%S9T9lIa8lfu@5zl$C|eE$0YidbxR5;$F|7uSCo zynP8~9gOOviREKX)6Q!>{wdBoy{E2x&kyo}iJM=~zidmiHt}Yi=keoDo7nSWwAt#bl zryiw2mlJI#ERYsMO;yQ;L!DRn?A{In4CyNvG}??4z5qmqL}Y{vQ(hRIJZ{rDojvo( z#h%BYj?y@RvTL{Ani6sKA=_+lrrE=B^ICR;XP_FmWtCYyb={0P;JlP!ySJ!m$qO}N z!8vB8hyq0G{RJl4JoeMzY_EjP#0~P%^t5Kz(AF;8a_6t#AzIlREd31(%MK5x-4!d_ zfh;x`XxZvSNDu{OuPyA+G~U#~p9a594M4U8>ZxmaN7DpqZVhSW4p__Qkp~%VC)mpF z3rEsS>0e}t6U`?nXw#C5t z$Jg-`?ez~{U^IFw9!^jBVol}{SXO(_uUD@tDEM{7bROsx zO*P;s?>8=?(cZuu5!8Bs$b!ZI(P)sp0xi%{gt&hVfWTf4UgVG;4f~WK9EtRaoI)BB zQw4fmlGeoWix!wFhFQHuTbvXcYuu~r;3p4IYynrBnQnu%a^~%pkyE8v}k{W(FLp>|WbmN9MJ2?CM&)orORcequwKOb#86H%cM zxGNHS7<{S_QWoKU`5N+-oRhs+su{Vs?gI-MXN1WTqP(6Ow|Gd%QUmuptO42W2T;t) zd5y)CF-|0E^j6;9e!|BctBKZlu)<ge#XWisHx=DWghP8idO-Z}pZG=%vlNrYnj9 z5H14kKYAbe|LFZoTg}IG&VE5irXUm%KbTwS^u4}@onIi% z5&91Pw9)rn>Dh9!lPrfMGe@{As9-K;XXEUr3+R^UZAAN5jc2Ct$iEXY3WDy7u|$t; zi8UUzt(tzzZENKENvluxT1-I;`B8ywP+pEX>>^3OW-&tN)zQsySs$}+h`VbE3 z7$0ZkmjrnjG>3$gtIu(`LNq>Rb0-(<+ja_~m7>8i$dOW0XXJaWF?}WS4!&B}q~*iI z8z%D-6&3A>@o{(|%)c6bLNjL}733fAl7S`$y~xY1yHNr|m?s}uG6kqo)V^pP5;fOOJI^TR zwK{8X%8#^mixPRA{T?`;opAX8X<*%>cq*jtZ@mBY=XkCpMFrL$HyfMw*<^>foDG58 zZ3Tc=Dg!(S0Rhyn0`sYj6DX)_a`yczc!!;v zDqBJ>%TH0@UIgZx30sj>hx?FL3G8+Uvv;;C78F`Moi)dNv8%~;>IcC+x;zOZ`5tI2 za4v&v$;@6SiZK_gF6u@luXja@Oq`Klaq2!R*T}8L{I0~MW2fy&pvcG%ogg8>A~$L# z(Pa=E12ce`>o0;Wz91EL$+=%e`*AyNk>qcu(B&A?5Co+naCVRx-SMQ0YxgE&seqP+ zx_;q7!orv5Tt06xwO$X{Q|NkpL{Qol=>K=|ms`?gJpuz#k9o_OJ|oT@U^rkoz;IFn z3wY5kFkWlIM%4dpd&o9arC|<`_5`-B6wvbeA%qb|&>$Xaq27OQM{@1?C`r2nlOg@M+WB%5qW#v)I)!sXLl^ zT<0y4@M#8zR!^+RfV?qiZO%8RbCR4A7c-6Di4UUWZw4BJ@tziLkpEtRD`3Qjyc|D@ zmfV-Wi)mFA+Z%Z6+R=k!p(2(UIq#=$Ke})S_PTBqnzFe$qdDf9I@G&$48Gk@%V$FS z0v{L`hZaFXD9JK4g+)LhsvIAWMMO04c?t`A;DA9YYHKpy2WV@56-hiZWO=z!f0ii) zvOTZyyJlANdEym!CV83ce*B$dNAh@koCJFGthqh+%FD&Aq*Qv`H$}2W@F!Vb`Y!3G z{1H1zUBz7g&A@=z6efdS(k`vi&rSo8T%yj0^Qs0IamIH^thc-R?L+kWdZ}t^8sgd% z3D$>ZnW+c2w>f#XE$uaBZAZW!jb4o(`j?cj5g7huPkvH0pxzk!jVa2aw_Gs`jbWl)mKPiT%SQVIzRX>yNtGI)6= z&!L-;YF1*aZ3diaLmHiCwvz`$mdFB41>$1*A=JgU5m#V?pL6TFyBP`?bZyO7oK*D} z%KU3t_a<-Fy8Oz9;wJC$^uulp(i(g*lMOnJP+O`XBX!N&oNG*AnJFhxE2}}PRM-gK zs1^n@MZ>$KI<0A9S~r6Bwd-woMMa~kjCkRXPMshrAE#c=2ow@2xACg$^*|(t^R@z^ zOZd-^me0hYt}DH`Z7vq^77GF1{9J@f9Th3cLgy3A9Ie-v;Kz&H2WSVhjKGQ zsP4BNO7`d4wX?g`#p<2R&-tSXFfH$}^y}pH>$uF(?=RXtk`{26O4-~75(T`G;>7Li z%Epjtltk`nGoF9r&zWm(KuyNV4WxOp%6%h87O4>gH&C9tnD!yU92Fn6-ZJw}pr-PK zGg(uOt~X!4bvW{d!9)z^HCipo>&1?FJo-i~*et3q;Q}PU_?*~~{LFUImlt?PC6F!> zqu*idY$(>q!pv$@Gg~50)@5N)?3#yy+T@zxu&SrwzJ1Xo;As?Myz3$Uer23!JQIw^ z(VVDPdB1_UBi8qkxoZM)^wH)`2XUB2Ori5d0as~LTfFy`RW-!x{(}{yBSd^)R3VvX zJ@Cz)BoTbMN2V%|rPWw-_C?yBdE*ggmI44Cg%tBHFy>B>#YwIZc33%WXr_)A&5{L` z0-mg_VEV*3vn6|?1QQp@)s3B-H^D%UH4^S3c`_zjJ%=Y(ms@@-!7artbe|pF+y+&J&=0^9QEU_R)8|{fW2O z^$m^+S#=>gUy@PDZgZ^wUeHH$%_HkW`xj3V>|Nrb!YC*9KeDkE{5&gM^|Tk{(dm#+ z=5py})g1G4SA`Sj>b}cC`K#Owwn%GWR}IE@1h^_xj}5aQ*X{OM4KMSwJa4e}NEW51 z7p!9|4>_$V&87JieYzAvT<6_V^@a-?K+WZGR7i$@;YMU*3sL-x6T~gIa+{3sip&)| z&&{$5;KeCQLYN=FFAvb~HP>2pimocAgReXSO+@Tq1vqRQT{GQt81v~{+L<-{d`HA^ z;861Di{={H&d+X@1U5qr1rV{;lqzS$hZV%q5fChU^AT|WwB_)}4H%^hh4199C&;}| z(o`!A*>JwmD45*xt>ZFjMS(e^0cAEf(Q#`XSGb|P(a z?Cn~Tlue#p=lzbbKPvD1_`O{5;vt0cvNq@G7lr$ZX7$K}B=O2XOLbOi>>58~`+ZkF z;O3C#%8i(xudcsVeO~F<+A?NP!>S{HsU1Srew2~>kna~tO||BM<(QnJtn7pcq^76l zj^BRj9eIXv!0bZ3{fBxi_yGcab@&iH7KDuwEpAzZQ>0Y-Bz*rGwaKP@m`!2(VPJD3gBseJsxxw=eU@!cVrR0$})q0#cC+C^AN{?hAT;kBPbPFofMzM%hgqAyGb?2Z~8RhK&0P9RWI{zza!2Nohw4+ywLq@xsek_J||Rxv)n;vl}Yjx4%Y9&`z*Ywu;zCLj1-Gb$zdMM$xH6SzSBfF?)9(2S|P7B0lFP%SR#uYBB zX{xWw=W%<_i;QMjtbC+!I}((72(yUUshxDYxxjWdM8ewBLqZoPt6xZYjVJ1)kKb`<~n>MLpr zJCz~xibpQy>=N&NOb#oAajzpP12B>2#t64$VE$}D=Mh5p>}8_0&=<6|)-M|JdLzF6 zxU@1Pxw)TXOejRkz86KWFXb|)s>ytd%~zjcEo*?FbT*yyH(eCwbR^aQx2|hTrOI*B zXs035ECv_|Y%s&S+oXO-zFb$bQ+Q`)i%eM>ZeYdIF*!8QJ^+E%jYKvH7RG`c2(-!| zxod9HzwLb&PEf0?jWCK3dKvf?{Xu>2^Ht`VS-+|OAA4&)7ULrJ2Xf6VDD?d zs9mYiPW8RI@qcdhB^fylqa}zpz)~5Uczu_{iLTLSR{Okw^scPBYrSIQjT#&b=`TJY z6n8fC5~0=7z25tH3FK?{tMv zqF-vr4=2N|_AOc&BvDUK^?RGq`S8R4nT4Oy`>-R#1}rO-_2Ipu{P!fY=i9Wm;pAdi zis1r9%e)399s1Q`z`rZar>Y6X(`avhW@Mq$hKh@+EVo`_VdE~8I6Ure_{+UbWuCc+ zr#M{ke@?w&m2q6n%YB(aRmZC8erm~8qLrMua;*ns$PI3{Kooc7akSp+b~@1v7Ww+M zgUn{<*wKzpF4k%I;Mr3tNrYs-b{sNjS$f5H=BgrqgkGSXM;kvuxu-{8Jh>E@kTYs~O&)P!3!}4|+GNC|zolQX z&7xR>o@hCvb)!a0X6`m^obbm|`x7CT2MhLoj?#ADp5aRu#_Y&b=lP?CeCr2+glkv% zR4P6xAQdh;aNu%H^`Lx&H;PHWU8IzNvPO2m7>(?D1yNMfLc3#-#=)cVf9@q(gNbF~<< zp!$$B$%{OhA!B;LU)UdXpCMPRzv?FT=hZ7(TWK+2H345aFZz{X6HeZ}J zMmq*4NEVC1y!epO!bDHSsHmpX#rS%25n0%Hl>luefO0e7d8RME*_Lbeu zwxs%RdkS0A&UN0~LD&?}WG`olV(+?Pdb$#dR0oycJw`fw9)uy6m#)3`yzX}?n(cb7 zUm7%zoII$uJE^@El`s@JMt&q%E&lp$!=fdU&RyKz?oGFy{exVCVKV|N4YpEqVcXA^MX&i_-Ew?G-iF+kthgDf9Il=Gnf6Iz?xu z$QhFg2~^^3&qzHl!;f3?JeIe1%I1_;9Y5GnKAuLxf)*ZT&0V4qa3o`-4szLL6bbwk zDa2|$JM+T*-yI$`!64wAlLaG@ZVCWJh|VE=j=%se#NqwKReOTc{hKvllhT`WW&8t4!@38(F3F?hXKyw&i*6wmva=3hATo`cpEir8?kJ zaePW}RW!~DFJOHr)9!Q!gPp@eooaPRzoG8S-Qoy88JVlGFvu2kePYct4${1o$jPcY z?ifFpHEy3+Wa2YW-`q0<4)vaJE--)qVHoUZBg0x$N9y$VLQUo%_xJBokW7k~@3%rq z;-kHi#!5LJy0}tV4Y^xP+EE>A6CHeHqWJH9_cu-c+v1m&3}SYBO>IND{(% z=f~XV_;Q~1H8$pMxtaZ+$F`SD0td2z+X-br)^jo5wX-r|eZ~GElRHs>oGF(#hi=Js z%ink2H-?^#Cq5^Q?;H7|>UV|hx-Xy!@r)FntWcK^R?_G7@ISn?@z_~E<|ybf<=NAm z^HOQ^&}SB#y)QW~!ag~?Xk`io{#ucIBy|+|(5F#nU%}KO0rt^1r(k9BnoVl^LkyZD z5z6zgl|LQw`}0@Sv4}b2FiZ=qpSB2j4Lu`8?p~@ib9M4ZSJOf9G5dz5EJcjLO$cQE z?GCt2`14~p3izT(ZL2Fyf3ELS-n8>V(}Y4o=s-j_GlZ2hO1BgGMW~7ySBp+we{AJg zkk$(O?r`9#Jvg+~QZdY9u|jV)ulGip)Wc07I54_tPHi%@weX7pe?-bnt%uMhj;GBr z+=GIeY4-TZR(@GmXeYVE%7FLa!=THOvaX^2cQB!Z*pSkDkS!J}fdG}ZQZo3Bm!$$g z4)VLRE{dVQQJ#tMBPHHB+(;G_JfWQn!FXb!gJ5T-Q>)5~{g4Ix>d)bQ`2`;m)MW*VL1L@}+nUZM5W`l};|Pf>{Eo?D4ShWE6jX7~rcF zNgC=WUH6;o-MC!sTXB7qDQg%%^$@IhhXp!rWq3p(u)$;~E-5NsOBVQsBVI^Lc2n)- z**T_Jqe|bcMGn-PxFvzCj7wG=5-dz$faf0^J|`nB?ty-qWiAx!2Z66#D?p~^%xF8p zei;{}8XWg$Zf{mkb8H=PJDFDbB&CqgPvwz;v)>c4Yn0Jsi`QhtN*H$g~N^v&d3 z%}YJk;Eb6$?J`K6feYe4L=QF08P#j86iW(w>nJP07zRt((hGQ)c-4J8xOI8cw506w zRAhNG7&{-iJzpg!X{ySLCSGz*K=r!k6sRn_@=ZTuha*-#U;daOHIjhAxDpZjDlr*j zVMnvPOAND~(KB6zyoDPURmfd#V^w^mbKcGWH&aO2Wp0Rc-JCX&z#9BJlaoKhKQuA; z8)q?!A09IUL$PdX&94D^&9cgq=6_#C2t{MBzQzJVA~j+GeC0To(Xs`0Z@#BC7HT9q zLuec&!GoD;GzNXnSV?GThcd#?1(a%yjd^X<1>A%^MVbyc`32{FMs0iPFd;4vG5dCn!O2z%` zSDE9(-js44?Qz@>2@9p|3-;Jb>1K$x<5cehmP8TtrV$@BF}in?Of55*7%C`a7AKW^p)&NQNLd=4Z}S1vzk->k2DJ2Xhi3hTO`>?F@C1>a%r;BEk~Y$1 z0VxuINZP!){_z`WLv zU#lW}9!Wb8aE4-t2TTUukN*519UuDXa9jVfZ(z)o_u#$08EWKn7to0qim87A14MFz zfG9d4sKx~WT<}J#hL1qm68BhAWAmDZZ7SuerQh|Gl!V{g&n|is7Tf!#6~47#xCh`8 zSM3l+D+!NO}nMcmcYeZ5fjFkK#)}6`z}K zqDi{{8|GlFdJeYaN^HS{qJ9MvtE+0VcD}&OH*zqg?tPmY9eA(61xuxB@mRgtpbHw z4-P~^;T{mInSw8VBnFLqmXXIR(icY@Y}^_17!}vMQI2*e2+m7)#4Ywt>EpHK=i)8X zK@};hw9ER99MQbrEuxVzfEmCdyhgy1=lqq{!@3lZ#{(s0ll(ORkr94QHb@4Cson%% zvb$Z0$sE-F;!RFjE1qey{H>;tgTZuk%>7k}6fK~W0HGjC@arptzifayJhQZKzxBC^ zI%Eg!vqzk~d#$0ZEglw2T#|V5)X~&5_n9}sARqu0nkjwls)h)7jCU~0KfdE&mtTzN z8z)g^)uU7}NOmgsC5JXd#k~#nkm4662niuK!I%u=L=E?N`z@iH8S%!!uyhL#?Mrq5 zI84q`Ip0%OPDZX4my|41@se+3334~Px@yuLlL$hr+(6eNHY8I5-|_{}|05_WXl>Q5 z@l&9A{cB;De^gf-CauRAUF(&3ECH6Rs#Ynt`LvkK2aFo;_4V~?emY{KSPpgdxz}QE z^pVW~F~9M;p7H=}$e$E2b`pt82NE%E(oF09$!z&=h@!K|+OYgibYU@sd@Dk~hE>l_rGjfc9z>8Q1Au}%9BNEK2xOl&_8S>tj@I<))w@w1mlS7b zNNF+7IqAf7u+WsY$}l|Cut|;Jpfnp}y|?dyO?eHc@K1#J3Jb8HR~RCksH&RaMdpby zp2nGeP5E=l<<9kDm<2^wc{>Q_yA0X|F(B4;)98$UScM6-@~`DQql5x`G28*d(*fFYJy+#5w!!}S@1XGyw6(YAc*L&7rH53ddvPiTb@!-;d za9@Nn1}$+ZE65kC3me+4q(89;Xvt`GKN<@FrZ$QOg=%L7h<(W50u@JaQ|iZ$KMZ-9 zCWT|jI;=K&p8L%BAYl3aAZh~C4zS$o=vS~2zB~JMC7%NKSQ=?RzyfCli@d_rGUz?w zN|r+Sz0^=Vv#QPZk&aH~k1TA&11jgD_g+^-hPt5v0^#8=H zU1CAJPx-9rNeqIIZIQuoois4Kjq5NurBhqE^mO!xn_H%Iu#Iwm$pZtr0jV4_Q+)FS zxCToH2sV)Is*Z)F(dY1oOerl=B!-Rs!-POmrU#SJx)+RPf{nUgWiB!}CmG9rpSS#mUtSQ~LE zV6AyE{P(8{Fc=(G_p>AH{u2xlu_TodDW4|l4-Z`@@N9;BT6DkoH=45{6LSAzG*9nD zLmz%|7!z*b!aRKg4OeKbsDPh3e=~&J0*Dyts1y?_;#JAble(;cOSD6*e^Yl9e$`kjA|5r zPe;p;|0XPEIz%?LZfa!QFlod8ns@*?#>1s-pP@Ql;Gw&7r<8{vOals10NgDO1gerx zUd))(wP5Ha6bfBv5O#AX3Q~%36tV2vSywWS4(H1RifvQ7*=aeb(s9OfWwm#P=(bFB zbqP+F{KIKnVoFCW{SRsG(LDkCg zvaI@dsSG*DcRGssqHg1geIGL~kAXXORKZuy^y~mnxg_~p)?7y7Cov&k!58vVfiK|> z>vS9-2;)kZVb>*ZQSlNXkybON0w*{_G|0d8pfIs59vLcSp`NIJ+9XSj{%w;4m=X{W z3Cpy%uWBk96sf4q2C~)XNY3Fg8XwdxopTB@u@(&T%jqR!F>@|yZx6-&>hX&wXHyvF zH9erqwgbwdnNVBWWCFKul6U+>cpdUO3}`4N=fmB z9-D~S-#s+5Zgo%op46CnT{pTOBuf{|z|wdoRdOgy~g;jpaI9%|Fak!(0oXpF;ng=O#q^#v=> zc%TFp2@sX^!p%fB+f3Ud;O)IB()POuCBWFOS{y8YG08I;R0Ek&4kM9wSp|84st12p@_|~~1Wb_4SMYZB|Cp?Hj-xW=Lv&;-D-j_gyg4Eqf<;^kv zOOi~Xq3ylocJhhtvx%FXa`a8Htxd6beoE0!FL28 zj9L&f`oAOeRfK9;9WTh^!Ecq9slW*2US&7^J- zXo6C<;o!bygW$6e?O!2EFOaHPrZ0~3dk#Mc2!K|r8)Yu%UgGW5FJMlgE?}`z zy#Hz4I#5(bho^l_JAYa%+a^UtMKumYV2X+*spJZMG#11yRzwcKX0C{@1YdY-n;}3T z9=zk^m~^>LV2&v4Yf-H)DvqGQUxVd8dY#l^CBxASIwG3y0h_6(I65jc!X^|n#}&TG zGh-@_b2*y7Myc`a=P53!xa@z>Em9Np+ArYZVeVH@a%(8d)2OZahbeU4go=*w7)I$rVR;FKiDwE=^7($#!VEdLz%Gp}6ETcWRl*zDpG8|l4 zS3Za{0eOqLMF8CX{jadFC(MTn-RJj&Z)d{0f~lC+PKR@)CR#gtl!q;v9U}l@M+#6> z%9uL8GuL*1N__lTAwnQ0LqQ9YHvV(DMo8<~7+Zd(3m4`trT&K;O>ia$!WmtqKSqu& zn21?9_BA`608R+nyd!&@?TCUE9uonXh^xru%z2|xQc_%OwQ8ZaeKKK#zZ2re>w56( z`b_Kb=G#%73C(49 z+}>|5HSd54=NY*^In^+&Vw;dXiM``fLDDi6Bt6K7=E&7{$Tt0C_Xai%ZNxpj*0RlMT}b@1AMl zAKAW{MI6}1;H%Mjf0n=-4@XkrrVS(olFZ`9uW9bF?zQ$*SS$brBmy81cPHpO8q~Cg z{Qwc&4h=6U{>kJpoXMlsW@$1|c4)bMp)oan<6S=@iYXRu;e&9aB<9Uk5bS6Xz~GsKn`Tf zAa=xHpcT=+@pA$?0v@NG z`7{=VrO5HwrEjb)8K0oOG7Qj5HgmOxj&JK5NcI()0Qk!yCN44Me6f)xXPnat(KO(f zJkJYhEhaw~kT-_$me8&-CTI2ZfSiPa4b&tle3~;O747+SV5fvSYD74QSAu#cftGmCxe-RNoJHx4P! zwHwoWa{=dzbgdm3I?81f;61+L3r()GQlTsyrb8h+`VnYN5)9R0oyJ&nC&I`6TeeQP zBs)KPdESK@WOuT~g=Mf1#!~>9(~CnW@*o>5?7oDjV{qQ?_znQ%DaR9GTUDf>e21E&Zt1z&>Kw0lSMTh4O z=UZdXNS3}Qa%%|-=zY!(MA0hBYnXA5*^>Qh7jv%u@tC$2cofDbQI4Cv5umY8_q6K+ zmuEIBZBJgm)^?}sZc#%+w}qWVcYqQ!UdM@gVE~~g3)rfg&7Y0cS`Y}N52wE{I=*;% zsLnPAaGO7?k%418`OrRiF3IEeP&g|SlVo?v^O=JMFkGm+Fq!oTm64}$L!TOi%BN~1 z0V3?J=b}C1`G?_fWV{4M+W}bAtX-C55OsTaCY==D3=@u%%_88ZXBs z4wEoGUfl0Es4f5B_BJ`=(pZS*1n+39+O@jI)Yf(}SOjVp{{G28YPe;#j8Tk^qm4lw zeEYPODzK!mko@A%J_UPKnl@t{s@ic))rATeL8V~f;^I;Gr5~vU z5FBnUjz8A~`o{7X)S?cB%GmQEylA5aq*@V*lTnHF8BvJ6<%p&GcNa)} zrGP{R&!ar4qhPjZo4<@7rZO!giCsNoZ|!qkw?e@lS!J^g*M+qXLYUZEwkM+rw=S` z>Xj@{rIL9Qg6$7%9jfnZYE^AMu+~m$B!uG#>XvOEkEGp|YHF#fQny^qtJQrTx@*yE z+jbVnNVBN5|K5TRtyrwQ4BvoSt3Q-D5qQDqUoF&yV%DE5Qi`~@=CL^u$ODq36MlrLNh$->sVIXstbG2RAUB-5NV$) z)R-_ipok_nz_|qb8>e05>@Ybg>09j4>x@g${JC|^FdbJRZ=1`{T~etWAF0ih2C}0E zRB+#blCnQ!GcpN;c8#_0stL~NmD$;ikIoK?+Nlp3Vk?&HY~c%DTH4y5o2!8d{zt#K zc*n;sjPASoYa2Dm;3CV9CG4R$0E{l9Gj>b<^Fn|nfA69_;HB06Sc%pA^hmL9k8*nU zP`$mDgpL{yVa$mjtoD!dCMxN$C-B7#NW=@idWwlN61O`l+d~a#UGxKNss2_jvOt3F z^&WB#3pFB{0RMDH6Xe2Yx+Qo~bQ|2qGZf;U*#09(lG)~6*i9i^L^EaV6HGLRy6=IU zRUt_CH^*g!XyfXrt1x# zml&jN32Cz>FHEQJTUiIHs_*s}(Ps1@_(VG#eeQg-!PrDqSKyPP+av2O7Tq;~2Kj*q zU^#puP!zA41izx31=2o?pI-g`yi%13A`+ZF)sN+FhvDT!buDsn!~bjy1K2eu7`^$n zv54{icVRZQG;cn@mHC>ZNy|uqKd9lfTn{3sJFVu|3It5*#`=r0PwU!q3>!l)_X899 z@x&|ysn)oRnS5U*Nq8JgFf85mK`(T~+kN0ljSsDWAo``j=tB_ zZk1Fh6jG+sGb1K~eVfW6n@7Dz_Li-OY`V}x5_-@`(l3f>{SH7XT@lu7KP%%GH$D$a zchdz7yPl2wh07PJN*$$F{^(o;LVvdDEF|3Zb@1TidHw-4Tx32uIoE&wzyc*Tlj46E z3Yt#sX&L&&hN3CGXU8Qw8z~^!-fQsLb%kTCLw&)_GOhcHo){UrX)gfKTmFcCv6nKo zef*VK9RY(vSUJmX;h-%;dI&bqpLc&@F*wv|flxswIFyGo+r|*htlfps%+&=GU%-n; z3bgKj6`7L&T!|d&vLuaFN~t-_RC$EY*H*1hJIY31dz~&|6qc8hyNG>%2N!Db4pJ0X zelS+;f%vo-N)Dv-#j4E6p^a~irvOds;TLM%y(J_oU`-T)vRRcgsE#@tpsdnGDp-NU&_` zEFR`(giLC+S^W)~T|yQguhgt{V zJDV$MrI|v_ymy5W8&Nynf4YfA16clJDyNHY51sg!g4?I0~u9^5%C8mm0*dQ%> z^uWq5W%M{(Of0tu6uT)ZE|*Z6lc!ip1hB!}tA*N4N|HG zn5E_HS2Y(GV+3(p>ehYSvbD}qY&=}%%}*zItdV(3jh0%Qcd;f7v@^gpmC;3k_Wd;+^o;zrP$1F68M z&787vPq`^DHSMr5DEqqqGq{f3@7fcnJ&LokmYt>XF6LHM&22dF=~@!OQgcNkVrY?6 z{rdH5q5%=D^VcuXmyj@Ov2h8hxlOsRQz__m_4Or}1t+et=2Zy>tT|t{5@hNz!kHEizZ>c*L&*5FipEhd}3PNu_Y?Y9AbxDmW4v8u<_I4)TpFZ?t zjjl6m`A(3IllVUcCHa2x9OH}7xM#`@29}J}WMv?BsPM`*HqZFZ4+aM2@$qD(v-^J@ zL9~~F;G^H;dVn$F?Ldo+&G9h`5&JA18Q+dVEOfkvS zwL}q@P8HYt5DiXV9lPbyz~u;-u+XH>^}cf2$^DY#-rw8(V7}qaV?cQKj6>@iHhZ60 zypwFFxyw(>($(GS&m!NGUQWom4{K?Z5T)dx4Y>NL?X}i%3j)qE>gwulm$@$$d>K8V zn#;z9E0=~jbgz&`n0k&fp)~%NO`Y+_dpF~WNN2SbJ}EvvK3l7Q^|q!X)G~!l$o>v4 zEoDgr1~KySg-b{TGJ-(i5|R?*BUK{bc7qx+G&gs5Z6;U*1Ogda-`tzM%?JfD+vw%B zU*=xe+S*aXdpDBiL;obHbG_8P;Xshn zDO{v|y*VMrv+qR#M$)dsZW&(vX>W(|I$CV9bTWT+es(cBIaEIe$?0kN3}7dG*sFFo zmNQ3o=>K@Izi3`MU#vB%+7f6y&nFqb9ojVV3F%{IY9R-VTcR~zDwG}qxSWuX*d2Mh{rz!sTN+ne8=4P#f_}#~Q34I-Yg1(`LbkTH#2SwW zlZ1!v3wGTcPY84v0rZ6ysd^>Uy8kiZKTG;C5K2wa^k2m3W>zS21@+NdQ?8fK&3bG6E%pz z3wmlu0jGj|2X16Mnhq^ z{yd+Omu4U+=t7Q;e?4-a5@xogaew0A-> zNJz)(U~Q?2=Ht4tN4F{lba@@tUlQ`&1jK#Y@$34dwAF>+iIlj}--#kKLqm-i$EK@b zy{sUUCO(qBWO~q=a}f@Mr0bfOYle}#W1pGDqpuQAroJ}c``J%GAM&4)|FDU4zVxPK-leU%)E-NC6PkZlhQAJF#KPJUM>jsk7;n$a1s z>KT!?kR=!KM6w&3Y{J&?AI5|j1=B))3hJ_~T|XA!;`hYHa8Hf|6E^%%0FGIpHnTm@ z(|M~djrWVKeo=Y3N}5}j2`M}@l>O(+cn`QMQbEbHr@%+KECH+KRSx#GV@1I!DGJJ9 zny+-JB}xR3XdCp!61N=i!AH*o!1?(4ZYPldb2z5{YQ5w4yg{|QIdjhSaiesWb!8ot zBC(&9b6<4FP?D2(9sfW&>wx1Y#xBv_{DpX@qfHClEatgqaRw?6o{zpF4m*i&*9mEI za0t5Z0wtQz$ET*kGEn(LUZbE%+fEP7fcZ(QRw23C=JAki!h!dayZU+EoJQ#=Xw*FF zv7s`rf8?}=V@TUVCH7v*)6O{A_wL?o3f@iC0uv;F#6|uR>Rpwo0S!qITjlJ;#uQ%> zcAr&b4Kcg=oh|g#S9Y`AA|Bg8uuU>+{Fq8S7 z2~^uZTv{*9!1ghhOzvWGvOTLK3AFI@k_)57>^@ba#_b&0+KzkJ;ql6X?uf*?n3}Z4 zlP)l0+EbAOoK?ob8G!g;h?QuMD|pNHt|oU)dOUAU0Y1p$dgxDMnJHY!e7dTA%UGH3e zQr9LVxufFT4iwE#9>>BtcW>WH^K0|d5!J}v_~W3(Dg*pDDct~@#l z8ib_6=-tSO%J}fKlyov%^%zxw=7vq`stKsRvd+cb{gR(JwJSu%&6J0qR5u*0wowF& zx+`>Y^nB0_6Xdno_+b)QK&Cv*vB8kOmixD_ad8-Bh7Hk^<+}1BBCCZ}#i@%Px5CzI zmu;Z`TPzIh1p{zGS)fWMMEb|^geo*C1dUv$=RhWOJTSS*`=tn5?4Cj*JH)yCrc z)*ut?r%#`1yt-fOHuxa*HrTd$ZnngM+J5{gz6D^_^Nl<$*$qg%W(U#TpJ|ex;bP9h z1w>8X4zmjcH!HdMWeZy>fAeE>s?8^fd3X>m_}-Rr@xL+n3u(v;5xG8dZv33KS?7FG z6Tq(B{Q1+><3s;g{)B@_78$>6UM<@F&JobV4Bdr$sO>&-C)9jQRfJ#@R!tAHaN%~C zEZG26j30cYRm0$U%reFmWlK{|$PD1ei0evl`|R}Dvn7FyrAe2eqN&V<+Xsr|HlkU+ zo*Xm~7@8y88rp=0@K7#;fi(!=vI{&_{|Ye0e5M$`9b=-vR-3;qNaHCl2tRVvNHYRU zQP|GD1u|#+GRG%^>wl~nI#fm=lI7;9M1tu^7;xuI&^x?06A*NfFHp?y{>KD$q|yTG zPpUwOee1DTWNf55PCq*+_Z?8|xbX`At=}^Gcpdear{lcQ=tYR``^nRn#!e)0f7s%? z^RvnH0Oun=n*Ofhml~xDi;SWwkW1p~U2!DDCoWcHNGrE0N(chNSNop~-5N_fZjiW% zpkPDzj~^M*AuFbZ5g6;1T;E91xkpSaEDEGCE=19gk#j9FALv7>Bv%38WO=#x^1=_% z3obwf8~B{W_F+<}&|TyJLnmX43`3V67Y}h89UgwNE|>=Pn-R#JeU*1QQ=9IXI*ves1rHdVF&` z6qEzt>W3|&`dI}^D#rLszk3Zm2ltZO#d*&}-8q4I>j6R*s8913^MhTa1>?F)d}PFp zhvdG+hd`19basAeM>D*aOhAl}%aO}sIc(w*hm1_yi)gv}#)hWCs2C80N#c|5T;I=* zGp3xahaFg4b}^sbir%Lb+gRT|9xdY`@}&SKp!_Pf=cxtke@wt$4))>U0U9QBTTQX9 zZ*ElG-Ff!~9lu@di53oqH6wlfZy$$F1NgYk;p`938zzfsSy)!E(o8MuQr0B0>-6qR zWu3nJ>M#E@CCW$xT!)tJSE)Q^Rm7HR&To8wHw8Km8jWAJ3p=`$OqS&wKK6@xE)TqV zXLZ|)qOSd-@|W@J!Y9;vNwr)KD~*Nq3gP3<+GonI$~uGH6T^wR{MrTy>V5e4zDU%7GOhDqjhH}Dbj@NnzR0S_!_x{cMd0ti95^F24_&6Jm+ zVk2*+@TviT{Xc=M$vXe#7{Ad#f5G1@--D6EDT8j}p=bSmirhBPc1c#on&%$EVfcWm zZ0zE)(#dXZQsMBV6Kd<`#MP~y?|v9`9Q<#B?Az95oM$(GW%r-;TId1Od=@1wO53b_ z@3#xKF1!yXm)c1=va6-dT(+9s!+Xg5F$|uZ5gX!9h3_EyP-^mVsojW@8o8-&EC#N$YFK6!4f6Vk7`lefAM;EJ&(f9$SXbP-I+mY zEC?VkJBu(uXbcm>03zK)CzHn{AvX33|3gExx$+P-1qH><&QA8iE&Av~P*`C>!BjPU z)XcLmps)UEfX^6FB0%p1&RW2{aG-NMc0sSLZi?Vd1QMZQfu<#r{78O*Z(^oWa0@=G z=Ug;4#nKmD*SoSB-Ac&8OS{1!yFpfJR4AYsl0|Mxbo@?@Y>e z!hmEizhAt_!VNrky+>GYfaeO|bKdx*{uzKjR@p=e{`af}XAF)9TUI*<2M0#mkc!5+ zxx$q$bc_tL{B>kl01sMqSJ81f%iv$1*uQ67$NQ>K=)txL+oAENwd5q(eJQ(ei}2R1 zcx+L3I%TIUqsK)+02Spa>KV`TQMh3f$%^=p_Q-zJxiFdf_3`eLm_EjOqu&81K9Ti7 zXh(4j_gYtmRB-SY9-UZfKJ`ufioe?lw{Q_;WEqn#F+2ja#wk13r|fRUm+=Cm^r372 z055%Z1poUCP&1)Sn3X2-wl4IH?|ih8YT2eS@!AE6fNv`t{Y6wm8$% z7vO4yFOFXB2(MN=9ti;*ke(Y-oXiV=o~qO<1_eBMc@0347Xu0LHj#ZkvUyqY?;rj!wa^{N+8=5-IE+=P%M0js`bH7dAt4 zet&+-0Yc!)F|U7kL-_o|t08V8u^DI@8GPhbe~yYzA-(YNbm5w4jh71S2HPzXPJ7$& zr-mYJzcz)fJL7UU_Sc<@5}f6aqg`4wA<{JTN9`@{qoqV+MO&(zEoVC<#;~x;bU<`c z`?zWX4OzzSK(aDRRwU~VN-IfbGn9)WVC8VADK9F^k(7-c=^eAE9GT70qDXjl?tsD{ z(EBf_e|xC-u%WJuO9UFAg?g7ksy2=HNXiR5yP%17j^}) zP@ic?NF;PZHmp5r2WdIR^)VtA01&G66XL{eie>VSy@{Zz^B*1^Q=(VV8zfZjP00o} zwy+#L65TgR0d@cxAO}|=OU>bTK-vfd@_q8M zyFjGc6}a&7bMnzI#ikofjhE)+9I^gc6>;;{4IOH#0Gv4&fse*`@*Gb=M9i2FkQMsN zR};@j<%V{74@Og8ibIKnLejO&&IK}X{fi~nV{&r{!W+#*OB=lLH$}SILb+fKY4xvK zd0}a`Ek3h?@sFa08U46~4!Cq+%uQig-sy}5BNb=F>*^}GF0MhA%*+*j0hZuKerapP zxry=3e;wj$J=;1Yx-o-NPjOOPep$CXwDs=MzHJxS@|{u**b~vpR5eI%t)qXtBjE^D zeU;PMpu?+x?9&wQUpN$gXC?|+iNDiyoVI{&i;G}J6LfnqAnD=NrbWequCH7i=6J!T z{rHz+JQfz0RySoeh?A=0?f25=U(F`7mQwTGsIM5F7yYEM`Ov&?csno+jd-W9 z@n?9d4O1bcN(VT(47C z#$H?AB@(R>EFX?C5~rmVZjEC_M!(BW+^#m@!MA|_k*^eguLh+8qjYYw#IhvzEisdeF4bc{n*eY`-QloMrw|eO zaJ6k{{kmqxb&!`eRoNQg~7#{F(>n=KAw z4h4Uu>4JJY^Zw70qg4?jkTYiF1B23XyGpXV02;OSSi0&b7Y|RvCLE{rfBEMCDgc=B z(c-HE0CFop4B*z@*?K;vN~TnqqA8_1XN(zSm-B;2*myKGhAZDK&EQXQfrB15{} zh2K(P#Y-Bx%j88L|B-b7t8TcYR{z7d5OVrs!AIjyS03TcHlY5%pB77?s*w;cq5a+C zakL0`c~h|mrDRJ=<^1z%wL2X^9MDHT{8kVP40Yzaug=wth-|)bQ1$jkz{5Alp1*^o z)3vp-BHPWGe|Ru@+#pDN?Mi%obIotdhUV&e*6;TS!JZJh4f4y;UbI>q47@aYyb>*J zsEjA~xwGN&{wEP8yj1l;3kkP-<|wVcR8`W`WcO3CUDeW%p{XT@u~_(drkZK^c2FtX1Ln5Hp|6Sko5_SU9ZY^+;gCk1yR$L(x|mwQc?{S_n&F|^&txd; zos2V>ua$#CU+Saz>cFvVC#{Q?AoG&Y($>698<3Dp*rkfXxE+*sDYVd%EZMLtkO5ME zq+9~GYU^v&Mw3q6_450YrTYk4Gzw%yzAu2Ujm?c}6>ooo_$R;5Zs^gct9QWAk2xkQ zo%?;$KjNBNuG7$i99&{NB^(QO!t$B$^M#BI7q?9db!UFR={l2lxEBnJ&MFr+2 zCPNYLbn7UT@$pcdf;7PE5iz%tnoQ6linGt$zUPbDQbAgu;weDFtkMid#LAuENnUB{lst0})+ zF}DwLe^WbRe`dZ5YE+7E<}n$I2aXV92BO_by6}U`zYJ3?JZimKLhTCo-7X3d(v0)e6W$2!TL* z6cpOuNcG(`h=m*%3qsFvhQ&$MM2uc~dd`W2=6jV|D=ih|$X%0^oi_$)w%we&C(WyYnFy#0rnVJAhMQ0H&lBUcxqgL=9tVCC&u44%fo$Td zVSaw`YmMXvM|d+fZR@eO-TOyJVHIko?_aYvoKmITY^^DU_K13C=~^>S+!IZ)Y7x0g zXopYRTdtQ%P^{W{O>X+#q%=Bo;tcV*yjhnEat;;4I$ns^ z?5LbFJDusOQBO^$%I-o{Uhp}$(B%1wmz>DBY1cbIO{5F{U%UW(Ba{WGac0}^Z&Zjs z$pYAvRe-rin;OGrD|;bau1E!TYZyW-QE(~9aTM8sI0)+JqfKpZv5q5>l;$^@A;syj zpU(1$4`*c`L)D_-&PlwT4baHE4)HYVcNCX65XNt~oqnM>V1dl(rAKa3iXyj?#-!C% z=awRNBV4PsgSlhbrg+9S3)ltIh2SF5Wup?swO*OV1bn;)5xQeRbcEBeuuG#RlaGU!N<~b^UViX3|oZCnu;qt5N5h z-qif#W%%Tv6Y9r!6I>!<3HbF1u5_`Hs+M$y9_gY7MeChfwvTWx<`5kx1^>2y;euDR z`8e#VHUKh%IC2;Ag+ceSnF@$V-b&jE-G9LkErBHvR}k3(GOV;L&c)tC0z-5GLzc(e zhJ*)z*DI_;Z_5($?gk2Ih`0v*6z>pTxKkQ4f)mk}s*dNX^#5H#8e}iV*5AmgpZA5e z+N*64dn4kW#!;;C)ieHXSu2+Xy{77QD%_c$9&b;vTU1S(US&|uzuwEWR6NEHpk8UJ zyK|ZT6xY@A{zJC>B1Yd7+_i!NZCfj0)S14~lGt^KbYilRTu3sTnwD1bK1Nr@{{ayg zSbHdWTd&W9N({HB_`QlUS%Ez>PX@p5`uawN59OZzuZ~=0uhl)dx^u&4g~2R{x!ZXH z_5P^&K+aVJ(T1B6w}#918CGQGXBn)INa};i;k9(h+Ctx?W;$IBDwE2SZ#ZZZ-_z%w=ys1FDNF8e zGiDxY{}B|Rk(>xyXW#o%*Ofg;VVEKf33wRq&Q3^n&meJGSi}QDSQ_ZY89$)#52Av+ zeE#?vQsS3^p2U(zw_ZX4ZLWN{C_FrMJv~|Oof6FnL7V891St_mBs>IYb4djB6g9akdF6q-Wiz~%R!&@^S? zL&lj<-<(53JiY;MmV!e6)^)Ps#3`7QhZkD=Nn@uBJ&cD-wJDK*-xz~O*BoD*R*l#N z-Z|svGTDj#R1{42MtP*Sa}QZtIfKj&mmFuPa+WcX$2qeh1Hb%l|_ULxX*P*TSeSguLjj^+@yAv%Z zN^k+(q>AOM6&tAvZgS~jD)PO}*N$Iw_O#QTQ;U(Eiy+P4x@I^sS9^QM%u9Y&ol&K= z*eEu{tw`(`CwFZfGvc!PILGe+8boulUtOoo?7_Dxv0RjL0A>76=`}L|I_hiK4ho1x{ZHU9P8Mi zr>xKxjL+KzG}}b3RwN?fSpK?_Ql9bQMyGzqzHu3pcha5qRdJfN5=g;521yM4KdwX^ z>PocfQL*7jWtUeVEgKox*mB$ZjXSSvmXmG=B1{ByD-DfTiOhk?(Hk z*7B96loD+^Huls;4>@{~xhD9WYmo?tow?6lk8VJEPnRrc4BMN`K0={3 z4}Axk6@T8SzR0+_>lDAYzVv7mJ06)BWBjx9u0gehD;P!v#S!WIW_=b}SMUGYJKhUX z{4Uz#gKb=Vmi#<==8^1hLWHEGB+d1oYHE5VQcN!1i_Z27uTR3@@1PHO z$yGI_+qhpj+@_X{?&dIx%JWkLwK*=?A8i!IOnW79I21Av3C(1iXrjpBB4_WUYBp`C z8XMI$WF7WJ^4UaNKN8W&NDrqdnw@ROmq?s#{lL80U@cKk)2gS)*I+?TPb4gHl^?Z; zs?5lq-X5-U`60Q*zPO~kQs*Jq#A=-=U9)cU55|}F5__M|%nRdeI5p({Ch36-vI>Un zu5~UL8MR7ap(qJ9{-UYH>^Ji%oN4Fnp+$`V=|Zx9l88<^sxHI5m&F)vGoqX>SQ&@gC$#d7rdJN2f+- znVe1gdiBQQ(2cy4u`0UE=2EwjPSdE5H;SZow>cFv_BK}RD1vl3E6@R&|;L-bv1vdsrOxL59+8hO)Py2BF=s;T|QGW?Il2Bx;4=s z*Xs?;HiZvy{08vviS13ibTI0UE8mgJgL~+QtGp@J4YD;{wt}W`*_3KP;^ZG`g&Nj< zHQKgf!^Y9U{bFkR)~_ORjA0HDTO5rUCiMH%?C8Q18;pq#d1CUKX>JQ?H)#)9{(gt& zT`DX0J05jV_qRGYcmF}MjH|&r&x<5Oc7Mg{dVRx?sUhefO9K|F+P15$)`Ha@ORmrg zfFyb0vwphCL?%|!t5fDj?RzOh10D|qV|S(cts3C=qX!G`eRtU&;G{cCym5^ak#0@j z_#PI5CM)v544i)|_WV=(GtnjTpF!=)21qcXcA>5Kh2Jh$-AHCz>vul0GVLM3FPp`R z6D*h$Qc;S0!+5=H$uEPv04G`MHeN@ft6`0aWihDhje}5Yelb@o_;FIA_R~t0T56gS z!9~hEM4zbni@bn<|M}Hy${y{GB$s;B7OhVnQI!^4Ge z(XQ#l`Q@#KzC@_>9e3c%pH=ptfNUOeEKvU2jQmd+maaL%4_Ak6vio~m1l{&sOOGRQ z2n(&(3-#N}gBisShkkcPxI|>ag)zd+XOv)EmE}pC&F!})j1e>|FH0(NJe0Fo*8eW_ zY&&VN>M(;@R?mjV#=dL~=H)L{ih6pN?8uHXKQ0K9j9<@rzXO{{#|S)P2tCcN7G*=-qUzASD3Oq^Z?zD+FY$0#vzOr|i$28JHG2p$Lo*)YI zP*DR*x_}D5a34%vMx$7dGkZzpa#|~*b|bMhP%%orcvr$A(Is*W;UkZgK(ch>9uE#x zaGBn8vP@CXNym^52Ksy+FyP@{K?}o_Sj}}I?RzP2wxE4?ZiDJar$+aNWOmyKm;UXw zK!M(aRp93<*g?ACzvzdz4>uNcscBs9NIgEu#eYNa;0d;b9GH@;4l3JJ4t+0M%&d7m zN0`><84klVc2<-Q3;As69W;m1+j5Oq)Vh4eJZS2EVkqDfvEn&_wP^u`O!|fWN)hG zd()i9Wp<1_p&3;X)$Y`rfl(xIo!=eL8WQw-gI=KhmnKty)t!fp*CvJ4w^JE7v%A$@;N@FcvT3h=X1rk_>Bg zoRg8$WLlXPUrR$n^6SI|i&UvUK>8{>Tq^Rnh#dpK}H()HUV@tq`2G!f8?DB z#>VOBdFdyR`~9Hf(oASy~=x_^d$Fc5Tb%ZRJ-2-hmXkgcYT7hbAWl z#)@nca9X80K>Oi){hU%m4DZj*jgk+KTjk=EXVHI4`EiY?yr$m$ECP?DFf$}d=7G1i zrNw}3PJ19PLr~Dzi!~s7K>8CwzEhut{JpK>_0-{AjFV`T;@eyczaxjB#_76kn%Ne! zsN%=jYCpwowS08z4?|Eek5R4oZ%`yzB4sXdO{&qoTZsE_3qO2~sNfP6YC^o#*^l?rZm8F>bS2}kaU5jph8l>^XWEL|&osIW!@Dd9hR6f1m{|J(K*H1rs=6S;^56`=kEj~) zW$eKQ_&hvTk;df>@80RrTpm#jx~`ISzCEPaPHUo%EFZ>D9Q?p`D@h{Ks12*^`9F`F zW877K<-R=!DO!lL+S`%u| zN{6?^x9Es}ohYV~>AQ0pmlDGMcfnCnl>UpG&Pv;xnHQWXV@5Va9xS|vC9z@GNiE*Y z1cP2Y{ z>!8BgwCaCu_yy+#yq1hYT#$5na5Qn2LX?AF``e<1@=)|+bd{Nf#+!c?X}hd1m8%pr zM11a7hT7Dp2tL9nxb+y8aA|7%Kv^a!j@bLWZ);&8&a5UxkRc)iq{h_=A4rwf{S(Z# zP5wWst^%qGWorw9f^@fp#G$*pyBh)N66qEMq@<<08>G8YKm?>gx&;IzrSqSI|GV$q zwOD7t;l!Sq-Lv<%bAE0!3u$QrXT(6Ma@Bt6vJ}3h?(DI;fV_(BJW{7hQm;R2d!)PS4PJvpLUw=G_}XB<$JG zRv!K)gh<$mCb`N=*ea3%J{e%ZkISYqR_2Bh9HnMT!I?>o}qB1kCLdYRl><60{0c->S((#u+yTqlS5`S>-wQVnt8W$7mE?tG~3 zm%`}{mAR)wbw2EF6j#*p@5{hS5|rf+g(|1X$i|IJXS}}*8S$2GKBSHyRbIYLB1KNU z+9LIpdE1bxf1i0dO{(UtHlEFO_GvUgUHS4ng_8z1JINbv2GgaEAjmH{_`c`~fxUp)wbHy)O3C=Rm z#ui64(>+_Y^^q@^;c7>#4wjKhlF%5Y#%h#$KK!5~2zf_mBWm;=2puuIn9Ha%St^M~ z$Mq!lwtPKCIWCSa_0P9-ZL#b`o+pE}5tlAfX)n>uX z4n|3GlId(d&qJ$*Yg`;G{D9{wsu?Pya`$8Dbmw5|b$_yHimudPTWuKk*QX(AT`=ZH^#K;vr!c45w05v(EmUUl^BDy!o>@Gx;ehwxT(71gh5l z*Lwc9K(i|nK_~2&*24XiCZ&_j4pBC8u@dhvGjv|0;P!r0t~`pE^Vq&|}4 z4?~xeKwWE~e6=WG7dI*=p|vRIF=b8OpeFXIV>%;U?d!MgFDS$acB@9%&k&l}VGvK` z_y{o=q$C2>AxMPgeIEFoTGDs!0t_61?olDXoKn|vlfT-9!Du~WG{?OE<9i>PN<_rl z>x^9FaW^9R=jx);emq9-ZT#Vp@Vh^)sz_u{U3tWUK%~oTyQo~RczZ8+eMa({mI3mS zDPD6dW#x|;wzIS5+oo%H1>J7dQqi%tePDZyiBam&+$D^P5m7cClhs~0V3)*kj_N%# zr;@-W&$(GjSnj`}BK00Pc-2H`Q|I7f31ZQfKRes@zh7%H7NNWb2)=JfZa2|JcJ2M} zV_rh1O_V301)Q_M#-24*u_Ht`iB-DuH^_qZ>&an3ce8f=bG&|ca`L#D7uQD z<@C1GBROq;LQd1<>GJ#Jbcxnl36rXz7e^KE9|$ zwqR)AQVshc|7%(a3jr16QY<@XckS33Ng_p#e*TEocm!cJr5kF$b8{x03q^qKHeH+A z*Hu(WO6N?o04=bJ{<(?AVptGEfvPknOVYewh}Il2?w6?AYiiUbmeybT{ZYdbF7dX% zM=3+tSW^-gF42oL?6%0}4m8}^c^5-`SEeS%5=Ri$3_38Xj|Naw-PVUq497yT7}AnQ zIH`}YXeMrm4mb{;B`)@}3f$#{F&`vGWPG$yI{FkU!#Ix$*ju!>M1FcSpBITSP0c_T zv8d^9j_g!dqYBy-?o!-5E&xVsMO_@sV?WjS5X>K z`P0KyNkyV_HzC4cu$H=Tw{;8n_0A`@j@BD&!`QgD{FXRp-;>$O*nY=gh)Y9uiP^_F zn6Wp9>VYAx+xpUnj0r=fz+7=_xj*zVGs@*v^Zl(oUAs%Dn1|5)&GJ2e@z6Z;ZOSk) zKiBV5QSOLpF*MlT^RtZnwqu(=3SvA4W9|nW%^t*q^o7hynWS3TJp6(wb_N{si~M^2 zYc0(aR{eFdJ4=hRo|9(ybJp4UE&h5JKJUw6d-?7fJ;^MU(IGZsVvY>hjbf+w_^sio z5Xz%rWq7tmCi4QF_Vi-TfY^a>31HTi1C|D2aCYfI#e* z(CZDR7q_Ubkgt8c;|+VQRsa`ipUpO60tNctC*gtQUMMh(gM%v767mRow(Q_GPA-je zF!5ftJw_FQhD(D|=2nG%U1y#K?*PIi>caR>{Od)- z`3_Ob!BSFjW@EhVdwCe}VXqOVCW z3!iz*@XJn+zvmfrTJ2IoElpp^sHEfAsMe-p=H>kWlsUKG9IGH^)}=B!kW z-CzQ+`#kj+{c40G)qsLnfxcONT#;bL&&8&e@Y+ zM-OtbUh&L{9{t!Iw-%c`L=AnV7t^bxe>XY4Bx}FdX?320h7Gw}krrOf>Q>EvWV|Y6 zM5g99<6}HZjxZzAm5M!*xOi1vC15@PfHS!Z9yhdcOSTW&K?XmN^{{4lQ@Se)<>@XYF; zI?b0Lxd@!IS<}WaYfewRY>l!}lyzo`4;y=iy=7iFt~fpP>zugUlwdjO2csHcqjGd+ zUhaTiG!6tcNk~^Mgr*Jkn;~0)_*&!2O{;IH@u@Q^QETrYUnDL;Izq(A z3R>AT1Yh5PC8H=?XfJRFX>D_#sC;)$V`F32(9XVq2#X61cKrO+(H&S}90}XJHz6oE z^4O{-2A-@#t*fY|^zEPKtkWtPLku*NrHeW*k~#V$7>OeC;KN)u+6b=W8mCln7rcaf zsfto+ANAL23!S(guWPjE(F%A5g0PiDHCxANpCe=W9v%rxk!Yy?dZQSTg7c{)>r?*%hN6J?R?TI5~J3T84JyanyMvh3e!2!<0xpN0~& zt7aGXT~v5FI{XDa_)oWxp&Ur_GaGm)5WxkC+#LmIc-%ZfB9FCN-9t-N7sSrs6Z4cl zi`@)Mb~h8o0l9QI4hS8g}{hW(B7dIh>{J59G+0{Idff)`< z2}FedmCuq|YK=#b7p-W<9`n7{o{E9f^b72ikNG={lF_Lm zW1}k4*UO%|2BZ+aHV-T2r$bR-tR4qy?qcB_NMm4y!#Z0J#B#<9P5)%F`bpC9bm=zS zD|0g&5;?NJAco_)^#neV^0ro>Hc5S#sr{UFBU{INpVDBaQyhMEbJ-)wNl*jr_cisp zz}@Uqx`NuX-!H2>;;+_?bp31=yGd_kvdcpA3x-)B;3SeICYul0gtvAd_trTy)mCawH@wdO{==7=8L^=9aqjX zm1FpZ$W$uC;_i7JoEmB?PGPgz*<{Zw+gItQ;ftNtK?B!Xo6S$|AzymRyWFPFL%YMnNpeh8;(_SQmE(gTOM%W^|6FKHSGCXUJlp(($`J?W_Wsew+CTfr@Ww>nQLlqT^cI`T( zGq^Pp$HtyCYvdPDL*a8 z7|x;WeO2LA0?=%N@&klAE=e?*34$ytI>v7FOMdU|=h#L)*2YcdTG#zr&B>ZyV5K@o zx^YJ-#9$8bUlVy(nuFEJ>-D&$vCloDDc%G7U%`itBG`>G)f{pJkLNHO@fSa`5`HQ4 zd_c4&0DQq%x6%t791DMgC$9C46Lw0q8Ir&M6i)9xiv&8?w0$@a`2gB&&@XGTeF6F-?3f<>tRuZp*yX8hsVapRH!fLrGrpUQ&myIP}3&WDv$R*=AXQTQ#$yZ zm8FiuPx=gxHW5~Gkb{u*cRc=xKhvs5sJe&D+d+{;xV0!JKlybg{wVRwlr=6ht5WU# zuyJ2d6{Y9#r=4!G&RfU#S2y?6zMgTMz?(vwS26CHdMV0QW(;5y7)JfzImlT(E%Zp- zvf}p)%F5>^*xD7}z#A!fl&*j7@>DWqJz%g%Rl?yB0bk3nNFTg>xdcSk9GBf2rh%AKmRs%~jW1Xbz9 zb#)PhX)F0`lnfdzf-tY)!u&sz$MZ$14@yhUax8E89xumy5(jNY6jl zrOIMhLoYF*;%dkENS~g6FSr`amtcmTYKTJ^_6VaQxS{H+AhcBw zl!3jcyFx}p%(3ho62pGSe7re-FmV~)><0^L3Ti6Xk}+~0Lz4xAI-hz3=Jg1tsO>$! z_3(yU&5cj(cSJ(EEEzn7v`Ca-nGaFQAw1NS5o;T7l*2BaTi6}FA zF--@sQH@W6QsClZH7(DHeA#+GW5rDsdV;)wCbm9DpI^Wi3eVabxnW3r!CE{2tILcX zB{pO#^6=SR@Yml9pdK)VQH|mWGWHxmYyCZ#h--+R$+^97BnhBPnKo zFMTsnX1x2rch-DqI-jX}!xwl8Z0AWVHa5WXQm3jkjdx z;^#RiRvBNMm23`iSKq#zxZT+ZiePmd$KFtbRMulpI4v1-97ZjiUq@=bXBxlz;=i|v zJuSOy3iS;PmHC{J7CCvphTxh3zpwd=S-4V6#^P4rb(=4TY zF?vS`TDnSm1WHqDAK4S*Xill=i6LK}A^z_1Jb)Cr{^$vv3$)V}2)9s{<3hrhR7v(J zNvEW8$<88eZ`vc%r} z6k@-zUdRc83VDPy%OU`AY?4K(5vyF=lk$5*I2(+ zI}MnK7y2s#Ew5dL9EVL(zZ@x$3dixNm_*^7*%yU*$6;mv(2;l_JI6!Grl)B@pIE{R z38T;J?3HQ@IA||5`7FPG$7Wxp{4;Vx+iLy~Kwlg?fH-c9e#4LQ8Oi=h%ibT&ov52Q z7c1`)#=dQpE7DAj8Z@D8w{me|QQxmWC_p*wbY{18aZ1Zuzz|hZG?cC!^gB0sgefdh zvL}_oMgZiK6Jo5!7pRC|7+TwncUh;@y8A9E>lYhfPdo}83YP4%(cClz0Z>cT$jN!B z#=uP>qk(*{WmMVF{j~7WCr^|C53H-^#g~)qN5u45BMSzqpoJRVRp2k$_J3kGeW+V8 zecU%8D#8s%=~@%Bh<*zjkWe+0B7~ixM7Y`dNRp%fii6E=M!9J3CQf6 zPLW&tlaL^1uU)te8LP1#Z@SMM*1IFt3F0&DDrzLC+Ss*)PwbXOI_~b|vI(rn*@!)| zBD%k|M$9MI=4&DUTx?w>&Yu_$MYd(Glr)yr&S2+3XUiw^u>gyO>f#i8^DKk4{`f1 z;>2MpzVEG@G)rX>vX%jbDA@8kpLATd**5SDbCs0T!(n0frHpv|P0;zp@)fgWKl`Af zm}Y3dc4lwC*nOquDjDSTC2m>pn13fKq@!o8r@(Y?Y3JGic(ptt80cT6gJQBONi`j= zHiwNR(8rlr`NR+HWuc}hk9+1rcT_=1lr%|xXw9q|J`V&YU%fuo~|1%1GLok6R6uc;!Bc~bNmNWhMlCkqcVH5seABT+nxCpm`dEnHxt4&|SS9yUn{ z$op2Zs9rg00zsS=CHm6D%eG#4Ge+|4RlOQ1#LI5 z1B{UTogKo#L4duwh=~tTiCjgAfkFqTiN^tr}5p1y4nafEaj8|QGaa!Q8c(pXx2Y+}+&{Gs*O0CWfo z;L_t_pI?$T#1)qu_!ejqlDVxwfIn1C>yv!k6`o2fVTrN$|+HVay@PEz_{L%p33S66}2RJ&BE_2YZ=0xC?B&Y)y zu1;e){`0%bfJ~MIIj;41ufdUtolpj!PomSTadpzGJU>4}gbyNPNfWnGV2=6BQNI^K zV)xe^BL6j(ir`o_g}|USn_uhQOd&q7;*Jd(N+D+Aa;zPacZ=J57&P7F#K??0KbPsP z>1i8RY<^Xdin{;=Y!>L4peUH ziJVgnCT_n`q|^%loRfo9G^}E-S$x?h+o(tG9=QT!pxQYE+w- z;0y@$pXz2px||#YMBXJkRUy40dUPA2CK64AUcDn+)QGT4V&MDjb*-m|)rrSR z-(JA%{QjN)>TW-pa{m`FbN^I;LEC~mK*L&D?U&lng%SM5WAOtuK=0&!y2FsQsfGeD}ZiHQ(q0 z2PDeWT`U1JMKVwbINkK9!RgeVI@;Zil(dPnHV!A|_<*GXa;SyO$a9-fD}wX3BKX1g z3q%3ddES`ck}>-Dd`T9H?~snveDZ_;VAm}jKlvS~(JEf9|NQNNR6@`usV9#3=HCmb zg(gsScS9dqp#A!=L>>*UC(UdkN=ZtM>f_Q4X9$L`nV4z_FD@<)s5;)~ya00#telsd zFyL&-SKh$(a-XN0sOBJ`>v|L;Vr+bKrBJCWkfAe^*A|b914Zs{j6>f-zt9NUav3Fo zFuf;9M#+<$c{|()fv|jBy4Zc|Le4#6Xpl$BOb&Ea5(7seP+=?8pr7@0rl7ayU(_1u zfKNdUe}eb-*%O&ZFbskfpg$>Iz*wM_Zn$uFbA()2SeUcRnHTR@*J_@InqFZijH$$P z*{*rGu&nfNr0+;{vt}kHx=Uhp9llw|yxo|YpK$+)J>XLj+`jNN-H@Onxcg5J4)luM z;SspVBzc5mfGThFxsBIldan`0=&?JxYC=G)>Y>^t5qs{T{ZGO*`H1(@|4j^unZ?0U*Xp}IVozS7=!r?AHfDOb! z8!RbDJ&^wu?Em@z7=}*|8Tl`glaU#$C2EF>(#sc(F88<;C$xemDc8ypPuUMoPtB!! zb?Z!KF`cirK+h-?x?2v0ao7$*W@Hb0U^lA(z$DK0wUTa64?DG)?Rc{XtBqCu%JC2A ztW-WFD|2C3Rn?f2?-R=t-Z`FP`?$OKpu zYB-pAV=^Jp8QI;^QE}DfD9IvSOmIH~&hYN9o=8ec&ld={yPN#}l|S7`I(E&%D)jKB z{;z?0JtA~)=r@MbD%X+X{`5+`-u3ike#kf!7XEw7Q9yz}~F8 zU&l6gHvIT9$&~X9#t#0_d51&cp-^Pyj&5FgN zcY*&UVad+#ca_Oy^fUxG1fqkyr+-}kY!cK zp==5hQ8R({+1-7m8ST3tlvGkvI;ScA*?I9_EzigR>R{2hEBo(T|6^GMlA&6$ttpxC zfqn}AwHx_K74@x9bs`P`2S+=#mGxXB`dJ@30uoX|8n<2cEW2g#Q~efwg)HwgUNFvr zZ`1$Rlm%>TDL+tA?|YkBAm2`Um4ep{@p~%8FCbeKJn_4Qd=sw1!kwzZjYUNv5ns7% z*0EQf{243Wp=4~zM{N9*jAq1 z9Qc1L2Obtrtn>gi_Kb=5hS$qO#AnHxZ8Cnx7-Gm79BN(Svh{{rUEdb@v<7LZ8mq{v zucDn&j05``3;k*LC=95-YEr?%J>~@N*r>`lZ8!uBs5PZ6FMooIoeCFBJ(d&G8?slb zWZ3A`vUcV+@fw3PY-TjEW)&cnE&5(`FgCU<3bqdaR5PSqh+42)W%-K*4t$?nc;s}x z48MG@cUS#15OSfYv*$b#^9=`1SNMk_=TNPG{Rv0v0fI;zL&V!1LRb86(Hep3J&59^C}#qV4?zPrHjTHTl~uKTpW`S`QCt1{s2MP`gA2vD^)P3d>B&v~>$ z@vjs0poEIBlP)VQR5u;k!g^XVeH=47{3Ywwz@auZd;1)W6iwFm(7|8y`XiMZ!>NhV zSkaNm^=3&9v}m<B*|i>8``eyNPprNMuo;4+KJQSE4IZ;ijd-K(_PIoaN4(@*=V3-Aa@Nd-(N+JU1A zl}{02VACc?KoV8vN2P877a|mg*goqmOi5<@WymU_bI5}#eRwgzCs=F!FFwIPOdAT= z-VHX??ys>-m(H%P@Mqe>i30dv4`S3ZHiZAxzp+Z%>F>c^@_%>fU;F z)9w03C6;8OkpPr;yV=5fQPV&rX!p-V%(_4HwErJ>f|d^e<~>+|zmEn`ES2fOfX{!i zRFEZC1`_C9jwX3yUC1(ZTIP^7Je`tgl!nT;e(vtdmuWNQX$~gEW@VAehOL6K#y}^g zpM0){00-c=9)5m@nD}h-C<6vJIgRb_s~_00*-oS86R;|P}OZ|~*oIER$f7JSaz+>nh6jf%>>-fzhOz_wF$!)9Bf zh02YP&$;z~ur0+lYycwC8USlt1oM&@7~)^&#F||0yapgRuSv%$4MGr5bVujEnux{C ze2iug;3!Z?%q!{0ko>Ub0TB}~i8Epym_by?;*5KDQ+sc0T=r&{`wWApFyy&g=grSU z-BLRTG#b@D6%pw4HnJ67z`G~u^(TQT33P^S({ z#^nL{kqK((!|@(PKR|Q*bH+5#)L3ZM5#;YP*O}}s08ZJWW zO<;Ns|NL*bXv7Q{cP^arsv6I~Qs9`(+#-KsV-3^mD1p1m^Q)neU^XexEk+ou@KDl! zz3{tWdWZd22><`Fiys;eknBe2J~)wmn8lS9dE;LO?e2{ecxZm$nZ;EXPMS^+kWg=S zn~2xGB@ai^Of|#B3O;T|K$?0jo3Y^joDfq^RMekKQBe&vMdW-yR74G?o(5w&%m7NR zH>6VWOLv26GsheUWZ|a@>@K%meo^KvDm>iW8Tm+P|K!OC`g zg4*o8LD+t>Xa6pe`zCO7Sn%2kOhQ_E3d8;!+Mh3OBKlw-n;3ytx#+gd;_%O@L4T=A z1+M{xe&Tc*^^!9yAgiM@GYo5N1TaL(G=Ac-%oJz zE9tq)V~^9JMq1|1QP+UaajxP}qrm|GU{$Mka!Y&@CoDr3zZ8R3K|&7{qd= zW{Td$J-`sushSl>iaOIz!UbWHO$~E4iYt0R-k?007@7YMBrMQYoLrm}M7};rbY&|n zMUK5kbTG0Q9f9hB%eP&(@tn?^Q%HP5WnftRM3A{lbE#5aUeD-X9{UP{?%wLr?)E6k zD&svHy;>XI`bPKBgZmT9Q^Wa~5%J|KsFuB(MtJd{Sks`GW>{Pc|A8Ba3Npwjh=5&j z*P)7dz)uk|(tzXRb*;$h6$#$7u;H##byr3^b#YZkBdv7E9!!x`<34wDPw8mkE18&4 z$Y6}5TUM?zI3$Sf2B`n&|efhQnc!b|uB;5uBefDLd$ zM?zIJk-#9EQ%ilR$D`;(RPVH7#w#~q=EyeL6C#Cys|Uuex6p@ob_xqRjAU@U*)ijc z$m>%cw|v>DBBrYyg*0;Z917(8_6H&R1H|52%&u#Lx8oA8&ZyCQd`$&ze_~Kbogi z0GA7*LyXL8;3VVlQPu@Q8-Km?UdO}AO(@>Wjvd!h{4sz6HY)B3enY_(&(W`DiAic> z(!=G(iA^Kn&Pbocn6o=wNe+S~y2|38@goN@9~f0dy2juR{mUOPUx1VyD!^vmyqjj% z{(fyiWw)X1b6WZq01x+W@kW0dmm{Vq%PvHN?GR zDmxlGKZVG1KO5zP|GXsKXgD{|SI&RB-!5N`%T?KN#Fdbs-L&V;;&4vphh_^Jm|5hY zEHp|4ow}m-d=(5{RSrh=yAUzJCsPm0`w;_!#sHqEzr^r zklCGPS*-q7$Dl#|^biKh!oMN;iVo~Bs!>o-5S?lo0*ZKVze?yc#jU~?A>f2e^n7T* zL_f;@uqA~_*r1Dmwm3UGs-@JhL{n1Lc~fvr3kJJ-d3pU>MB^T7PDg5R3%M3Cl7OPm zKiq^u1)K#A#2~Z{`zRx}WLX1Cx701Mve?%`J5YZbj?{phZ7aEQ z2J854u>wT|_$N=0d4prvP;l3Wfn{J`W#zB|~ z@dG%+K6~`93c+}R$(c!ok@mwHO!~PZ_meeLfDJ!QqJ?Psp!#m1e05unDD}U(Z$%Jr z(n)6hR|P20+9SBHA|gmeDIh?b219j&PoNHxeq3F@Xu1%uKs*V09~l?$4yADM2AZ1! z@FVvM^SlaWHT+Pu>av6kN(NuYFo6I#CGxmp+HhaRKOrHzoS5z?Fq7lDvp@+(G zc_LE4gB&lSk1ieTScu>wAm|79-7KE|#EMo`P~ZS)9bP_J`|+?{d-uDD@Zl;-8BG}b8gX} zP2=rEACbWW&Pz=WaDz)($W&f{ugs) z=ro4Rs<7n8P^x*dz>4^?crzd3Ht2^u{15`8%ZbSY^^`yd9F@N#0}C(=%t&A)8>Gag zuX+?vds)BXS`x=~ylf?J<6PY$sYdbg8H%J%u|8@7LiK@uD0*dP^qH>J!6jU7F2#1t z(}TR8K#vW-OK7bGaNS0-cr1QlLr(#U;0u+xq-})RYHBy|QCq6opczkUW@H zIZMB}w-?uQZD4;^WJ{yR_nBev>sYFVtdRYPpry}na}|KCL zbl7_LJ4=@k)c^wP&0)sQwCLm%e)oOBt+y83_vx3*_o9zr;K1Dsc#sKxgc#PZ@{<^h zpm+o;i!(|oUT!-hkk^uG?5f#~oMtq$K=~q7SW&{(tR{!6p{7)=l&;J+C~~0mn`y$V zw)L52N-5EB$3WP#>zl|d-z@X^IKF{&1z(BwbyM!a(a!32F7g4MLK9gr*7%fdAf`v$l3*is3gv}7J$FS*4%51(YKBZPVh~QM zk=0##p!l_Z97YD5#Gm9}U*WWJO^8V=yAmdtlXSIT8Poe#yzCS;^!D_RPdi{Gf{nyk zc{=}f;D{G&7uf=APwVP)-_G-QJ%>3?TYa0e$$DiF8&1iFm1pP&Puy*{31AV(KFYzY zEo$sIfxCu>9fm$IF^Rli>-F)#gKm2lg4JAhxrI)KRdHyD5@$EzNLiBBkAdLS_?ej@ zYW%O1#5SDbiXxw!o`ZpKk_9EU#Z#z6F}5?wZmj-O_?$vmm0c^MkAI_;rlh1et*nq= zuCtE}q_9&Ry-Qz5FDCCoYvAPZ@P7nIK`(lAWS6c&ys7KokJZ3MH}#rkqcq zK`ozZm{Rm_-$^+ei1EgLn3>s>Oj6~N4aC7|$v+M%h~unQIj72NF*cn~`nHwaB_|PX zO7!C6M1A;z^Yq?$voj5^>rS1(pM_WE%Xa~hyf|5i%}{>0K@vH~5P9S;1$LARGb-9s z4q!gYvTdcNoNaQI=U?0fD`wh|M#@G3!kvhDk)VWgK?#rKxt07c;jvJ{2~puZe#jWH=YD={B6<~Ki@~=WdKM1}hLQlWz zqo(a>SwUIbUO|3SN7K`)`YaPFR0x!0B5i4pa6>4de>^-x_R$Om6FUxhU>o`gUlGi# zPQ~KPtdgX-WP|bO2)+tMGo*b2fGFmO=CzO-S&j&X6tLwn`Qk;fIn-o)BZ|j4B~Cge z31~yUUpiR*an9`h-rm|<(4`u>_HMAP4{R6aTC>mAnU~$T-VLf58txmuXo{@_!uMmk zTY4S3zjcV{2ZfQDNJSz>13gDhw+pZLQt;Z25*c1r^TBJc#&2ViEh#1mOhfndhEb$# z_uwe+^#6$m%eccmba`)*luk?_xzmkCC^0P`RY~;j zfQ0l<@uQ;(>8HUKvCAn`k*zeoY@&Y0zkB=xy$QyFBZd<@cC~N~CQb!X*?4<*<(? zKp?OmJA3`F2BKI=f$L3Vd^zx`xz>DXk2LOi`!Vyl*+GZvu|lY##zMnEvWAr=I~N@K zVT7L+?W9dm^&rF&%9kGavLc_9_-svbb0&<-Ev$f;M=Ry#fJO0DDpGaNgoO-md7M;$ z0a{BWY1xemWmSg4TZAb*?>_DAw44%sM=L|pJ)RADtlYNSEt=Q=psnFPxQlblknip! z4@wP`b1xgkVY}}w(JKpI;P}5^ z`#xK{arac1CdGn4T-bht`qFCqD@n~>m#VOPK*Ng_YZyf?TZ>XWK6%LN_r}5HhQ&ba z`&rZ$RpK!65>Sb1BWiR#XSG;3G?DW915?d(G!15}t~`TEyo>ukv@Fz6zpyzKZ&*QO z@yBUnJ$)G+j6%TBxagE;W?>;GYMgUveCo;Tb&|Z?g0XXkc@XS%u`K{dT=9fiGZ;a` zK(T$__3`uLjf#1@7+glZ8J(+sVWAf^O1Rvs5#Dt|;E=8~W}+3sG24(u*(-uVmm!-X0vPV)#;C3qFZGd18Hp4os^V0) z6eUq=-Dep|@z#jrAPKRTi!2t_8*=KiA0@iuQR*v|zr!U~hA^{4jtuWZvYP&Iwf?MS zLh1aq=l(NegI>|ZMbqdCe=-V~GFP*0JU|vYF`#iJf=aODRkrlGz-4Re0TA#xfLj%M zbCj}WcJCi>O8R{%5dMQZ7WMk$2lc=N)L{$q@Wy|QANmIjnYZsv?)@Kc2$Nn`*V!!c z73$vk>RDiB8tPYzJ_{SU=wv^6deX;&Zfco(hl(STMwK?aL z9@>;nZy&YcURiXRa6d(kwkrJ^rZU^OXTY4Zm)q$WOsQne1NXx!npK{jre-!!yj))= zLtjVNU~H5r!?yH2FHnQjFQ}c~MM;toz$zF~iN`oosv8|=_fM1 zqLNQ6uNsN-BpIG^0Vh>R~B*xA+hJ8p3ac(Oa+jHcG_{;Z!~ zj;*O-v*#EMDJNSxUCkad1MeXV1ilS9u}e$DKPGC0z`u?f5|zdw+Hpj>{0CWzj_`PA zXQ<}hLzPZxh!?{u-j5pJf`c2J1vnPl;!0CGVlJ*RmWEPemrygB)lmVy1Qbrh>e6uy z5e^)*j4cgr+ewvU@+A0VP#u##*h@9q;ltkyhL?ShF1!7G)LW#~FJH+Jk0vySJH5pV zIRzAzaBn_);HrKMaB@*EERUkQP@F3hfHyP$1P>RtzqXL>(mx>NW&$Rhyd3hhyW{;+2fT=(L+i!1_-R)7FRN9OG#U_t3UhPHU33gKMuoU#Lu?V? z4Ezv3Wk*+aUURz~k~P~6bB@!t=IwnuBjMjDm^Q?_%}HQv2aDN0-P(Cr%n>-AulBt$ zpE2;+tg;vQ4xaSeOnm+Bs?k4xz>q*CuRY@#y>h}l z!+VclL!ad{in4N7rU@KPl48E8WRCXr8YATOIZJ1rSIS$&alm}W88ceqF!Pj+P4%|I!f+LyLLuRPj$suBjFaNndad0vvoyM}7X1vZ zfU!L@$LhA0L&e#eQ*rLJ&-D?Hj+kCOexO4b2>O+Eoz-hPIBG?F8t2LkYx}b?B5y<8 z!{AQ_jY2p{&%X19x<6)*cY%XOGC|;MAi*h0|8?*@G|1i{hTUJ+o)0QEF7Bu%{^WYS zUh%lbX}98MW_)ck(+cqN#f;5p%@sK!Zp@RV(>#Ee&;I>*VAHj2z91H5uV!G(Ok90= zRD;h<{1MDKRA`pd>A4h*fH&$iaq65qD0Hw;FKy`M>QBrJv7HOObb-bvj_QtNP!{of z3QVjZ3jzoE9;^YMdm_Jm8qMO+0CUUUV&ihpDALAZOrEuU8XggF?Rr&n6dxE91+1Hk zvisdXhXDhp#{97XuGju<>)h;j4`Rtd&eMvj1D%+*28-IKdSY0_Ff_9)ZnWm*7WlKv z3)J{?REdggxzx|Ura2T3zL?*L1$ugb&c}`pKULb2*IbdyB~iU%bR%At%OyBa8cu*2 zOh(=c`S9e&i;u>!o38y^WreTo=s#6R;%^~*Li)g)G z7OvH*W-Ts`xPercV%g9myRks=I2kLfXJtt$Zi#9YDGoXq2iCl(FmT=wuqd>rk<`-g zd~UzUriYrPg3(Bb7aPGCb=?+|1S@mNhDih<1z!_tA2=po3P=HGMfy}HtmmTBh8LFj z`QF65+uF_LpBl4SIo%GY`uL=z>qb*qTizo(OjceT=n0Dq0JE#E^d0^`k^?x=N(IVx z%0lN6X6`!+M&0jEzJgo6c+81oYkXD zCAM@jl9_3AAuW~T8hjkrHcUm|)dr5{oQPqK(T!l~k@JXegm%T^oxiVX6Wn_4^I`V4;I z#_ca;d>Jsi3g;#H->@j(0PMk@xX9!Gu11Uj%6eOdZ*}z=YzdxuDMnoHy&e=Fo4(>B zkmdMPVO1;}QaG1W8(#yg&lGAIJu%nx`FG#7S(n+LVOA!_uJ3aeiv}UmiCS)$sP&i> zL{J5V4MSa(n%igDPCeRTz@H*u-KK!gEmbpDS3N{e$45S>z?po$v@9Z-Oo@VjWEV@u zi}D~%^gy&KSe!Akp8Z<*@iTONV~4&-Htk3G8|E`o9td-Li^@rGR+U{(t1*e^RV2`C z7wW)g&svu%1CGQ0E4TOL(Dhu}Ga&~XrMG*mB@{S5-`?w{2n`xim?}VS)prV(WwO=E z(8n)#vx-G_CD@RNMX8@w3KFN;t}6XeGmwB2vlHT0V*ckjbSW!^K&jc;I5RfFfiX5Po7Wwicns7H2WAqh&*(8wPLghszd$Ezuy z{TdQX&F8WH;!%4n{qxB@h~QGqv!=hDWwge6Q2C~Zc}$b8OVB^8fdXuSH`afT2VEu$ z1ldfpZ+S&kYDqEl-OD&z2piF(cp>D zPFx4>h5>ME3gk0)Tc}vf4n@+6XFBak-}WCLJL$IC1$TdTe9)B zWrQ#&SpM;LeeeP_s<@UBKYrnE}DT67HlRLD(us^&DGlUv6b)K zGd>w!XQm7J6k=GOj!1uSzh&2|!-g`ANT5fOJq(lq!E&Gv+gJ#S?@h*z)@xiRr26*~ zX&wio)(>K~_AkxA^;+a=BB#kC8OY5lxbQ`%n&G#C0EUul!e>+X$QF-|IMpV2vtoas zlO`iUk3vnO(l~2e<*^a+4nZv4I28P~m<&pNZ{wHO%;s_$4Xf*U8 zVD$c9Q6toetYBfgzdOmf8Nup|buK6vFHJ_2&q7*kYYf<$$MdmM>4FnB$7F>j`@W42SiCB5PfXdKrFvOG zBCK#+!#|0Sq?o+$?pHFyY?ESCmVm*!pm2MW<)&Hx|F!qkVNq^t--2ub1CTHX0cj}# zr4iV)QUZdsND2ayLk&Y%w1DJL(n@!i(%nN2N)1R!H+<_E_ttaH`{My{vd`=m^k>pg^EwTd?oc6N^| zmBcSg)Mo%Gxkn=yyTaxTa>dqio~X9>3S_BPQQdu|qezcZk0+nPY(vRdlx24hj|tav zr{wY%S57;(2hyyO!%oVngq44=^t65p&zL=4IZRCwtl6wO>o(iorOr*p_lyhS;t-LC zK`uQhI*Wrh4GOD4NdL3HO%sWHrNkI1IqmVNN-F9reV7sRs#*yJ1$nE==`qz#%Labk ziPB;il0D75r#)qAKaxCAkRAr#7~r-1{8B@|w%PTx^x!PgYk^}|ZKli3U_@G~D%(Ew z^9Lm^$FPfCC-OIwnduJ%E+?6zp6@pX`h^)qCfiuB3n2_nel*`=6V`u9e0?Y{qci@t z-u<4aj-GjL%LU`BlZeC^!48{o*(*7x^5|oW9+?p9??_<tm{ONo`C+R&d-vk*7JTLSC~!^0t^Q`?~u$vg(!q&ALS@4JO82eHz{D$ZGreB zLTGcaK|j{;{V0Q2Q@35h{eZn_R^g=gTR;DN%ZiD;=c!>GM}~63d%uB^+$9zXkZEq3mG$>$F_&W|0m=WZ1lPN75; zzvNH4cabml35AX1J9ZFh*BRHvv9m|n#0$4Zq?}WzRd_OJefZ6IV~7;GTmcEhz!#~Re#WFW zf8TRkQQq@;ur-6yo5cg<`pv5hy83o+mZ5l5;H2i`=SB785Wo}#)$GGd^pXX+gzmry zRROg?(@^Qm+j=ht)0hmt{l;q#j8Fn9N7kI^hA;<`-!=kV*4R!+%gj!?HhisHwe|%m zIWaP|;Sud>;W^IE`;z)1rBMb#@u}w96Sfhq7zAa^wUIO_kqX<@JMK0)o-RpWr9Tfd zvN9_+mTnVdR*tRR&l1;V7ofe!R%xjp%yHo0Y|ThjWOC z8~gix>PulSrw$Or_hUYG!{(NSc-_&QeY?zIW|AQN)v>2b!OBI zt7mj{#q1J4a_wn|4gIlJw|HyO;$Bwbq3d>-OH{};I<4Sq7PsUz+f)(}Sm zIl899&jM=mtZPrx+0&FdBF*}rmvM|&Gq?qhoCsp<@1=w&8^-SzcHXrw8h?P)qKPcrIZPjKR~1J+&G7e)}x` zR*^zLys&;bPU=J>l@8l{eS_4F?Wwnv+G7n9O;ms4N1v)i;?l~?Yn1}cl*X=XXlqtU z9{wwXkF|}>f?TQ8FExwl=YsmBpFETlc7^t#V zIj`{`+)YslV)pZjCU-+ejH`FzTu{fC*LA9w7+Gz`+~o~)Dn1ak4yC+leNPWxIe9(r zyt_Wu4alVTHb?IS|x-nIsr_c3PMmIYEj+KRZYEWid|}c1A(uj#<&ur7`2asAWy3Fv<^I}4xAWq3c4uUmaoDnB*6o(ndups! zWh)WL^uR(tukJTHG~)CsH6`t}gMJzK^IiEpsI@Wfyxh@c>MQWU(m>u0+xH3F;Zxjt z^oem|k19=JZ)@{Z_*aEkx%0+Y-D;PZgNh$rO^>7BJ#&UfPeEEzLl=ohIC*F8LoWw+ zh3V8~T{b(_9vl1dVxAo_46WF_UHFkp)@a@kHELyoCp--FYhfg zeK)0mV)Lcj5y?*@Glo9}+s2xvpkiu8bm4^l#4(MXSLPjJ>0Gr>6Yd6{S9DKwvkH12 zC$bjjBL@o5Z$V^x<2pg?H!7SQ@_{TZmA17}DYxxAAvJD;7KcKcQ%?Lw>%H_sp4Ae; zqjfXMhrWeE;v>Sx^k^qWwatYR7cF;fL!V?aIa{>5>W1Rer%^khf;u7Gob2Is9PmV1 zX$s#dX4)ohfOrL8;h^VDlFOaofoD%h6@$a*HWO>J zCd~1kx_iP-n}F8XO9c!ZGTT#NsV6tYbwd71C$RB`3KOgF``Dxrs~;q7w;vSWbw2FA zT1S`0#1uAJ5g@v?vNkBx)zNdTt;wNdvWr+3nFAt%djkC{-nlSo=)V!@%YntIPU%41&6efK^IWg4yN{v-i%s?8_sgQM?Lo%D} zPMv=F1c!{r7)O>Jy`){sx0yo6O=ky1su&TYm&KoMlm+K**W8= zjc6gWw~CY#sM3c0j7|-DQ9YOYM6q)j;$yavK6gS2#`hZFvtv9`GFcS&jwYyfIIU-n z1@xXJwrCm$DlzIAhp|s(E9ZKEsD*!hBc4;_xv9)?l6pK(0-j99S}ehSKoq**f%p>d z&E3v8i=M;Ub&s6No3m-8<7ejEpm$XP9335Rehw+xE-9;} zeI7sa7DnTjF776TuF>#G*1U#zHgvA);$(G)Tt~iv>lMb*LdAhsf@eVrNCG9n9?I0O zyr^(1$sG|&kBbpCX};Px={xBHI~M)Z>pt>#?J>;>;Z02?#7d)9)06M}h6M|vW+q)o z$({D+-OUt>;X2PX7qpG$KRC_BU#{tD7n(n}FJ4_Sruhh*yxLYhjoWHlG|_7ALppaO zkuXQ}c5TJLGA5p?b-U?Uz<`aWXsq=^@>AEbPS>S^mGR<8m9ClzG&y2cy5OigyFFzb z&`KrNbyG{zwp1Wq<@RO|Dth01(g1PlOPNJH8h_+_2DcVeAhuU}`(FH&;(;@ZGX$xk zk~|q!R}ZC%G&}le6GfaYxPe#fUNMg3&FU$L5MrL<*w23O?XKD380I8I~a^2^?ckM85g~?m(VpEg@BNhe-M4J7hApo0U^)fD<=s%< zjW?%C$)pY%s511J8Qft}18Hd+BNqZvtb5b$G$X4l#x=M*sNpFGZAN?zTm9dI_}SE8 zL*NWKT&oP(#-1a*`MLcPe}P)aP^!2R$>4qe0>1zyB~`~Tq7t7OL$o$am7-6&O(nIH zK#^iGvyrF8D&BCHkY*Hxt6QICRnNzy^6_%<%^k`rmD3pB>^eO$%XjeOneT+<3rJB( zaGZbPws*u1eG(2mX>WOfu1&E1_grvd7hWFCo}*i0shU*0rRP-mG?YBHu_>&`JZ-R% z`oLxQsCQNrCK9^-RD8tJ{4I=%y8k8mhkdns0bWzle9OqGo1MZPgH^Lg_mkNYb?Yfi zo*uXEuIzN%%iDt2fCIAd0n$kJV~-V=?Mg4wtqx?UbUZ8K$Zh^&e!n|)%i3)ly(>MjlteL#j{E_7?IORuK);Bb5w!Y5bdNN=ccFT! z$f|U!Yw4DlqE8|h4NaBkW?NX%1`-uH&JRRvA

    iN5KJsyrP`hkp_)N%h5wRI(K^V zZCUsv*I&1#m}n&4=r*9wBGS(#%Tt=))-CF7X50gSU@4BRmxQ3RoU>(;Hbehs_f7JCQ2*XWDt z9}s421?P+E`j=61hqZorT-&}mrBN;d2@k9GcnpGJ@uiDFoW$aXl`C%@QhIj2w9Hm8 ztqm>2IWTmvuh~Ri64^z$gj@ygSK<>?1?TMCzbv2NrK!=GQ~QCXM|6JHu|!~ZA?|s# z?)pb{X1n!3kov>t1LJrV0x5~*W{kJ*F}XBj_wm&Ud8(|filjGRQ4Meb_m}M!-t*($WSWD! zLok01<9IgnZ1yUdtxqyqaO-UhameIJL$N?locjP;Y9p+IJ^_TCKJ*gRRDpJ>(CYv4 z!zbkO3O>_&1u3TJAk+|ha=4Bg#>N>p;&O@qQ(JW<9=>kcgzeAbdu4g@>waWrewc3X ze{J|##|4C&jwZMEQv~_RaF1ug3tW?UGJ~gbm89frm6kqROT$e7E7-3qH9k3CUOQiY z(}881+t4$k+sLr|nDW`Puw(ueA&bZl4%cH)(>)mh%D5?IyRs>mM}~gi`Po;`+=bA{#4GoGE_*aEVj$M|+1{qmpwOxF?%)!b1MyF~o z3Ep=K3nQD#g$cHCW)A1u6jkG~FJ<-rtc+K9QXFF4wOOjo-&cSpOLb)dXb}ARto7WT z)_tCeTD+zp=3LLw#-Rc#LjM9vQBXT615z=01>;7*XeePj(YDy%q)E3HIX*PeJJ82P zoMV^Y+_5+TEMDH)91uESFV4T?&K{%F-JuRMs@YV`7FFZryD1Qb%5eCICzDeu*uW?_ z92Z~nBHe|ITqSz{hv8r>aouh#+m5UoDLJ>x#zk*BaH4b0h0hIOZ3gcJ8S z*E|`h(D1T`-6fACKPb|2$x=wA>Muezp0Iv*OtWfn?r-8K$x-l&B3|Q`>avS{vO7~( z{f+u5t#Q=1$F)uwpoqyCn^bPJi{om#oxZTX&de%I7~qDng;P*%zf|T;zK0msb4aTw zEm9$)qV?qJ?|yjf)_%$C&j$iI6MGHb4EE*ukAq|9KCD&SSI`W98`nz!| z6;hAzX&uZuhk2$S7;BoPujUp6ZbRI?L+FoGP%Sn)^7W#HxcY^)PZn>QtoKtuZ1G4l z2Y%!zuR1TEuD>R-?arzG4c9w8DS5imJ7pHnJO{hpUEDkydvaHx;F+wf!)9h)m&4}B z#6AA9mKIc4tlZ_b;jOp35n40))~8@9tCl`D5JG>de+{bQe`D3^X>fv^#$%;r+!;bD zTwCsiRQSmmT3w{}bMS*LQBlmp-n7or!`$2pw;VRqG8AGgK9DB}GmNH_PAd&*~^578E<$=DL0 z(%}+bELe*0oOmF5HTr&XNlPSN)4>V17o1?v5V)LEV|n7=rGq1O$mO^QPHS&)?TB)A zGV0_>N~IbrD=)8}OB6pHq%~dHFfHYsE~9m??zXG**uyWhMR6@o*425;Uogzx^elu8 zCd|t3>{AI(K@|>iKD*TM#K`Oj{Wl@wn1dd1^ov)Hyx}2-owHrupTqlR5)7&}cc?2~ zOqd?Kw{4Tjj`Rq1bO}*husY4BwDp-D@!sb(pLpTkjRHyQE^N7|$N02wPRJ&~Lpx|` zI4a3ycZe*_)&?W25MAl9?OWDe{D=r-!V4VZ1>=gZ#Wr_hE%@SSBb?qavs&WLX3QJd zFxSPlJ;)M3y|5qq&~gGU@g7TqGSo}_!1UGQY2I!QHGmGU)^kP141!=KyUHBb-HTME z?22!w_$1%Tr}vVm1X=C?Q;*Z-A9>JY#+W%!Iw$mZV7^$^=5wp0rBhP8#-e0v`Ke}h z425=q+5Qy=zN2*Ohpkr4F`wR^bst9ocE$1AC+YEcc!{l|E=0E3@tH3@|EuyrC)tPd z?J^EtGDwI1#%TW3*{_ve+@$1HTMP7)hs5s#@gi>uJyfM5MjU5d*{bChWrQEdF>_FV zL!4rI9*pj9@@~GSGMV2N5Ux_+i3YLe2$Mf?EMucN+7q>7H})21Cs+&qflRV0n7mbt zk9ll&=W5(LaiI8{b94P@jVlLLR?OpRkv%aeafDI9XKbMhak$kv&d{APl_GHz+=8J{`^^;rI zzVAqH->V65Mi2Hmvk^_wR=q@@E$hr5A}U)I=h%$OLzOi>E7N>;6wV|3W2M5>O<#K^?>1Ms+|i>3P-6v$)?|E@&1JTu)k3{xQXL$KYW7%LbYb` zYln%OWEOXI+mKI@iSLIlkJjqDZLhGOZZ#qN5@uQ(d^d{LJarwf*W`&E8Mob0c<~Vp z<-*66P6v;#_cNfJ3z7lqiTpWN*C!FZr(t&x$KQFYiknxog2TOCL(fN4R=NUadI%MA#RS zJzA^P9c?O_o15^izfnfttWn!W$Suir107sb_+mw~0y?o;quf`1)}N-Vafy#G6cv1( z(%mH~)rfS#Vx`?Z#u}WeuravYr^U@Hl z+;;BJh(c_N*2x z7Bfhk00%8?OM?xohd=5s>;AEBJkZ?wHDNNjWw9|z^VNjS>gSq+!Uks_%fv;Dx@}J3 z(DiMb3H}`36`G1Vk2xA}P<9igLisEx&X03tH+>S{)WS32_{cUZOVBK)2j0mD-{I{D z9YmMX-eczGm?Fu++b1?t2o)_#eY=XVX>;HC!5vLl5^45%#Z|p#T}r*FZ*;>!c>GqR zn|_Xlw*6}L=9Lgo62bw8X`%o*goBevsJDz|K5_chnMrLkze+zdKjGtstx(KVVLbSj z_F;j#7f3&{E+y_wt=y;_ckV{NHq>+=6qoA*v`r=RGRRE>z$u!+1k31}8xQ)pPQZ|9 zMW-xx;8FaPsJfehqfFvm+SOd1(`@|RwFG0$;_FP-I;DZ0nzq6S<6}89g#`oPb2GZW z-*xZ2#gB?DcU$)IDC$>^cptrK>D0tF-wcb_>b@;7BQkDRG}f)g7bW^7yK|r~`(mm< z5#qGxg2}rI*HeDJ#4Kd)U`hma{Jv#8!)cB-v#|4FW1vF6NJe-J5)BowNe{2|fErl~ za0>Tsh{gv0u93Op^f0lO+Kg+u5mV7ykCi+)zq&a6bblp9JR;={(Wt-QBQv3Ik@Ksa z$hDJl1?4~vrqK5n^rsmYl~o7l7kRG=(FA3+)erblE463Y4w%N@#mQG%QgnY~`5f06 z-oj#RDBw`TMKk8leELkLk<7fioxbRfycDwZA-EXdu{1Z`wqkT8ZOfx#SzMD`iPZ5R z=Qv2|V8Ciot*ZdjYh1z^d(C}W+Ae4&en~LIt!6b|Bz8$-M8BoWB$7+03&ckaQLEnRui@38vXT6!)j?mEci<$twP7=c*I2~q4zzGi9Yxc{Al4-OkG>FA(8a%Lf1_RLzL2wkE z=uHL^QSTAj=YB9>f!ZwsXe_8frdRg;3Eew4Akc$U4u3!;EALr=lwvF zri2a|IbSC)(Io!GcU+V1%wslFG$5o|dmVTVLOb3CM)gxe!v#E&w^9;_d?s|zS$`>P zU?>V)(UPB0(q)3Z`ygP{`XXZtY82kRKyhB5u%G!gg_i{79{?P=*P0?8X5f47K|rVG zv*lX%C}zn%F)Qfoj3D(-fK1THv{%OS0ZkiJ%j;<{NEv$pd3^bkxA1>KgR!(>Q~@Vj zu90zs5H)||EdUA|%piE$^~$ew2-Omvw6OFoWgU#+b=$is3Oqv!N_R>cflw0(4qiWi z*&>zUxj|myAmKU|vMHv7h?WJ2_E;{#6N~Z0&g3HLg(njw>kVF#DlP(&y}Jq6s)pC` z>@q<<==(Y6@?wz^yiFnjsCsm(ZMPZl+FM^)jBSuNKlddhytS?SXEnaLZdo^QS%XJ7sPS>08N=~ntz_<^|OHG z-*eCX4SM#1AWd+5;Bp9KJD`=bkpkV3$&b6@edfXsUu!S?s9cEWI8b-V*Q9k3A)qe}FcwT=AA5P3U1G2)wn_I$-;I3T^^`172^#B!n(2 z$Jac0x4{pN(zsP>Dum}y-=Lw+;C>_n+i)t4yY8I?wW|G%?^guNeG<%G^Cw*dnEB)2 z+ywUNHUJP&DrLp|E44kni3*MKP>Ev;HNRSinYq#Hh+PcW1kwL; z6K_JqZu-8twCN++KK>##^RdC>0{Z{ooA5j_yb%^tWZp8RMoYWj=gm;)a?DS=>y?h> z1rT%C|3b_m{AJO6XC!{@*1M}0)zGiY1UwkWcW9ONoyxI#Eb$$ff&1~C=CX8|faa1k z+6S+|AMgNPP~a~c4YcQ$laK&b2nvA^gmbp<|E-@uz1|u^lT^4)&iZAXkRTqwJ!S_2 zhFcelFdh?UfBLO@yem`SNqG%0=tG|1p9pfO8Bln;f*E3;&0F* zR#oY~{sFPt5`)+qVc>Ncxy>z@nte&m-+%5E1(lk!r!rPsz6OKh;Hsbl1)dKxFf_%N z)5IZ}eF2v1D^j|3(OUz^S-M)31D2?a(C%Vl<1YM*p=reHj|Jb-dN8*UfjBjL%DFSz zcL8M+DkgUxK5Q8q01-=77g)2go7J*syj_3=n|TPnKm{TMH>kC^8IfC@#XTVdTbYXP zd-~tE!pwTBex~j;Xsfel*GHy*{Kd4QpJ>%yO=@Bk85Vw94uOyl=k+doCqXqFQ^rMn zFgM9_NH;>bYoz`|H=treBqQc`3#|m5op&({D-o5@pS7DQwDJL0ILT~l-iSX0`5Sl6 z7^_@>vTJ$79Z>oMVFh)0qM479H9OB7b)3?PRSj!wQ)?ATAPsVt*ILNi1Ta_M?&ueC9oohqOm=CZ(1` z#W&LS2j(Iu3LR&NMxDP}#Oi*Y!+s=;4dnH_cZIIveuL~HrhLE(?6sa7h?eJdwlP01 z7}!UR2!Ama=l_2}HG)>IWYVogluGT^HX_`h#yvwNl~9Wd#Jje+hZ6qE5qG|Ecwixs z^#Ks{#7@J4?B99M0g3VTX9s=~mS8URrH)bT$|$)(U!04`JwL4O{Zv5pKSV*Y7XNHG zJ4P{q{}E{KBLeMx(&~qpc1#F4MaMxrzDZ9gu2yb~3|8wVC^A{OqqJ!E6RNJxSpvy; z45(O7#7P60M-O(uuJI2k-w0gPfa?zb@@ES8khd!2y8mhigDgB2kPli4uUYjovBcV?! zE@3us?5*wz=fV#7?w)r)U&dUJ;gKNx(%1I?To&jDT*~^ET=4G^MLlHvoh=rxK`Z*X zEEPP__@wCbU$Vsa!A+|bR@mMi$hYI(dQthKy!yDR+j#+JcX6Wr-Z1_d*uaCTYnOKz%_cGGdLlO*Vh{qsvNB33IJJ}cCWOSfz{Yi%f zDR@U!%gdz<3;F_+gNEs9cRN}%Xg{?Dp_ZGKs09SX{)!L8Ry>f@S{gj_(@&#WyDBb1*k~__us?RJb-0(VcB*V>3(O4wl<%Ld$H0Ebk5dgVz#2 zpvXud9UJV)mjDa->6MT;G{RpSxO$a9-{)!GJy-}HY@`xFn2u&!O6s=jAN ztO7~e8lbEj?70Qh0si$7SY=-D#g#wLcprfAm(-1Dp&{#=z%ShCU)+BWPmpRr=Sb+U zO;cz(4<}AFh-Amkj3@gwhvh~@*fg23d9D+d>l6JhNYHumi&($JJn@_OYgd$yZ{HeK6 z^|3GIA+{6U1)%#;OAOM75YN^i>ut_qL5NGx2-K6RjzSKy!$uJ9>rlY!1nV)dbGS&- zy(jeV&jx+w#Jdlwy7g;rpDV^fU+PnEGcH`1U6~T+QhPMlccq^L@FfWc5a!&I5p2dm z0&OCz!2!UD0FiR@UI#Qov;3+R|00q^Qo4j78F`Q-CZWc(oo4s`X5jo?85gXSdU;*W z%+7pIf$&uGCtCdiu(KpT(!glkZ@_)WV6zrCYuEz2wjW zyd4QO-bb`G3mAqTBT*SygnH0D1oEGN?5GI|VI|fb%riwyPXiv-0UIfiaDgo5OFiJW zXARF({;s)vRq*Zw^JF?M#IhUPR_l+!7QeSiCO^aq#VSGEEkUj&12<*=5LzdUj~=KL zk-Sg}OYE?_{^%vtG8z^pznPf+@dFGR2;h+uc)9M3@{`AIMdTt-%5-_h)t z*-O`M9eR70m_EQLKPOQbNm)P!ggF zc2tWG)B@5L)r)-bkl=p@CM-wg75raB*hS6@ugR@B+3ApoU!lMu#N%1wfD*5+xkATq zPMT>JzZu)Ym2D3nee6dJu4b~bM-@7lr)3vwbVo(Del(U#{qgnQp|SPi$ESG$i91ko z@UO|r@6?X&>t(Q{kc)U-&HjdBz)qghDvITWZ`WQkI|KeH$S6za{`th`{{XU~1JD2f literal 0 HcmV?d00001 diff --git a/docs/Design/memory.md b/docs/Design/memory.md new file mode 100644 index 0000000000..2f4b871bbd --- /dev/null +++ b/docs/Design/memory.md @@ -0,0 +1,3 @@ +# F´ Memory Management + +This page is under construction. \ No newline at end of file From 60e825a9a6ee3fd3556e064411e30cdc664981cb Mon Sep 17 00:00:00 2001 From: kevin-f-ortega Date: Tue, 11 Oct 2022 12:16:33 -0700 Subject: [PATCH 072/169] fixed UT. the removed lines were just debug and not useful (#1716) --- Autocoders/Python/test/array_xml/test/ut/main.cpp | 5 ----- Fw/Obj/CMakeLists.txt | 4 +--- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/Autocoders/Python/test/array_xml/test/ut/main.cpp b/Autocoders/Python/test/array_xml/test/ut/main.cpp index 3f95f88783..adc57455d6 100644 --- a/Autocoders/Python/test/array_xml/test/ut/main.cpp +++ b/Autocoders/Python/test/array_xml/test/ut/main.cpp @@ -33,11 +33,6 @@ extern "C" { #endif int main(int argc, char* argv[]) { - // Construct the topology here. - Fw::PortBase::setTrace(true); - Fw::SimpleObjRegistry simpleReg_ptr; - simpleReg_ptr.dump(); - setbuf(stdout, nullptr); cout << "Initialize Arrays" << endl; diff --git a/Fw/Obj/CMakeLists.txt b/Fw/Obj/CMakeLists.txt index 3b6f515497..25d6965e80 100644 --- a/Fw/Obj/CMakeLists.txt +++ b/Fw/Obj/CMakeLists.txt @@ -12,9 +12,7 @@ set(SOURCE_FILES set(MOD_DEPS Fw/Cfg Fw/Types + Fw/Logger ) -if (BUILD_SHARED_LIBS) - list(APPEND MOD_DEPS "Fw/Logger") -endif() register_fprime_module() From 0316a8263ed64a9914ec2dc39614a88336549fd8 Mon Sep 17 00:00:00 2001 From: EbenezerA99 <60404240+EbenezerA99@users.noreply.github.com> Date: Tue, 11 Oct 2022 17:49:13 -0400 Subject: [PATCH 073/169] Adding modular dependencies to enable compiling with shared libraries (#1653) --- Drv/DataTypes/CMakeLists.txt | 4 ++++ Svc/Cycle/CMakeLists.txt | 1 + Svc/Fatal/CMakeLists.txt | 4 ++++ Svc/FileDownlinkPorts/CMakeLists.txt | 6 ++++++ Svc/Ping/CMakeLists.txt | 4 ++++ Svc/Sched/CMakeLists.txt | 4 ++++ Svc/Seq/CMakeLists.txt | 4 ++++ Svc/WatchDog/CMakeLists.txt | 4 ++++ 8 files changed, 31 insertions(+) diff --git a/Drv/DataTypes/CMakeLists.txt b/Drv/DataTypes/CMakeLists.txt index 3c4e9a733b..03786646a0 100644 --- a/Drv/DataTypes/CMakeLists.txt +++ b/Drv/DataTypes/CMakeLists.txt @@ -10,4 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/DataBuffer.cpp" ) +set(MOD_DEPS + Fw/Port +) + register_fprime_module() diff --git a/Svc/Cycle/CMakeLists.txt b/Svc/Cycle/CMakeLists.txt index 2ae14a6b94..0f62a6a329 100644 --- a/Svc/Cycle/CMakeLists.txt +++ b/Svc/Cycle/CMakeLists.txt @@ -12,5 +12,6 @@ set(SOURCE_FILES ) set(MOD_DEPS Os + Fw/Port ) register_fprime_module() diff --git a/Svc/Fatal/CMakeLists.txt b/Svc/Fatal/CMakeLists.txt index 9dccaa9e26..5eaf08a575 100644 --- a/Svc/Fatal/CMakeLists.txt +++ b/Svc/Fatal/CMakeLists.txt @@ -10,4 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Fatal.fpp" ) +set(MOD_DEPS + Fw/Port +) + register_fprime_module() diff --git a/Svc/FileDownlinkPorts/CMakeLists.txt b/Svc/FileDownlinkPorts/CMakeLists.txt index 88c1974e35..1cf27cdfe7 100644 --- a/Svc/FileDownlinkPorts/CMakeLists.txt +++ b/Svc/FileDownlinkPorts/CMakeLists.txt @@ -9,4 +9,10 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/FileDownlinkPorts.fpp" ) + +set(MOD_DEPS + Fw/Types + Fw/Port +) + register_fprime_module() diff --git a/Svc/Ping/CMakeLists.txt b/Svc/Ping/CMakeLists.txt index 214a69daa7..f2dd7ceb39 100644 --- a/Svc/Ping/CMakeLists.txt +++ b/Svc/Ping/CMakeLists.txt @@ -10,4 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Ping.fpp" ) +set(MOD_DEPS + Fw/Port +) + register_fprime_module() diff --git a/Svc/Sched/CMakeLists.txt b/Svc/Sched/CMakeLists.txt index d949af19c3..04a573d268 100644 --- a/Svc/Sched/CMakeLists.txt +++ b/Svc/Sched/CMakeLists.txt @@ -10,4 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Sched.fpp" ) +set(MOD_DEPS + Fw/Port +) + register_fprime_module() diff --git a/Svc/Seq/CMakeLists.txt b/Svc/Seq/CMakeLists.txt index 33edc7fb87..3ad1b159ef 100644 --- a/Svc/Seq/CMakeLists.txt +++ b/Svc/Seq/CMakeLists.txt @@ -10,4 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Seq.fpp" ) +set(MOD_DEPS + Fw/Port +) + register_fprime_module() diff --git a/Svc/WatchDog/CMakeLists.txt b/Svc/WatchDog/CMakeLists.txt index 5a13e22a60..a5ba4d7ea5 100644 --- a/Svc/WatchDog/CMakeLists.txt +++ b/Svc/WatchDog/CMakeLists.txt @@ -10,4 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/WatchDog.fpp" ) +set(MOD_DEPS + Fw/Port +) + register_fprime_module() From bd5bd7c1514aa7f0b24bca53997108eb4483a31a Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 11 Oct 2022 17:16:38 -0700 Subject: [PATCH 074/169] lestarch: fixing platform print descriptor (#1717) * lestarch: fixing platform print descriptor * lestarch: missing spaces in assert messages --- Fw/Types/Assert.cpp | 4 ++-- cmake/platform/types/PlatformTypes.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Fw/Types/Assert.cpp b/Fw/Types/Assert.cpp index 046ccd8782..173beff3fc 100644 --- a/Fw/Types/Assert.cpp +++ b/Fw/Types/Assert.cpp @@ -10,9 +10,9 @@ #else #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define fileIdFs "Assert file ID 0x%08" PRIx32 ": Line: %" PRI_PlatformUIntType +#define fileIdFs "Assert file ID 0x%08" PRIx32 ": Line: %" PRI_PlatformUIntType " " #else -#define fileIdFs "Assert file \"%s\": Line: %" PRI_PlatformUIntType +#define fileIdFs "Assert file \"%s\": Line: %" PRI_PlatformUIntType " " #endif namespace Fw { diff --git a/cmake/platform/types/PlatformTypes.hpp b/cmake/platform/types/PlatformTypes.hpp index 4c4b3a5bd9..cc120cfdf7 100644 --- a/cmake/platform/types/PlatformTypes.hpp +++ b/cmake/platform/types/PlatformTypes.hpp @@ -52,7 +52,7 @@ typedef int PlatformIntType; #define PRI_PlatformIntType "d" typedef unsigned int PlatformUIntType; -#define PRI_PlatformUIntType "ud" +#define PRI_PlatformUIntType "u" typedef PlatformIntType PlatformIndexType; #define PRI_PlatformIndexType PRI_PlatformIntType From 8af699f71b19a902a389ba954e81fa3f91f436d9 Mon Sep 17 00:00:00 2001 From: arizvi786 <80656867+arizvi786@users.noreply.github.com> Date: Wed, 12 Oct 2022 12:27:29 -0700 Subject: [PATCH 075/169] Added SSL Error descrition and resolution in troubleshooting section of INSTALL.md file (#1718) --- docs/INSTALL.md | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/docs/INSTALL.md b/docs/INSTALL.md index bfc45c0d85..a9865639b5 100644 --- a/docs/INSTALL.md +++ b/docs/INSTALL.md @@ -179,3 +179,22 @@ Many operating systems offer python PIP packages through their package manager ( recommend avoiding those packages, but rather installing from PIP in a virtual environment. The reason for this is that the version of the python package from the OS may not be the required version that the python project depends on. Thus, users may choose to install F´ into a virtual environment. This is outside the scope of this document. + +### SSL Error with Python 3.6+ on macOS + +The version of openSSL bundled with Python 3.6+ requires access to macOS's root certificates. If the following error is +encountered while installing fprime: + +``` +Failed find expected download: Date: Fri, 14 Oct 2022 13:23:11 -0700 Subject: [PATCH 076/169] Adjust spacing in Assert.cpp (#1720) --- Fw/Types/Assert.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Fw/Types/Assert.cpp b/Fw/Types/Assert.cpp index 173beff3fc..a9133ff793 100644 --- a/Fw/Types/Assert.cpp +++ b/Fw/Types/Assert.cpp @@ -10,9 +10,9 @@ #else #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define fileIdFs "Assert file ID 0x%08" PRIx32 ": Line: %" PRI_PlatformUIntType " " +#define fileIdFs "Assert file ID 0x%08" PRIx32 ": Line: %" PRI_PlatformUIntType #else -#define fileIdFs "Assert file \"%s\": Line: %" PRI_PlatformUIntType " " +#define fileIdFs "Assert file \"%s\": Line: %" PRI_PlatformUIntType #endif namespace Fw { @@ -44,7 +44,7 @@ namespace Fw { (void) snprintf( destBuffer, buffSize, - fileIdFs "%" PRI_FwAssertArgType, + fileIdFs " %" PRI_FwAssertArgType, file, lineNo, arg1 @@ -54,7 +54,7 @@ namespace Fw { (void) snprintf( destBuffer, buffSize, - fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType, + fileIdFs " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, file, lineNo, arg1, arg2 @@ -64,7 +64,7 @@ namespace Fw { (void) snprintf( destBuffer, buffSize, - fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + fileIdFs " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, file, lineNo, @@ -75,7 +75,7 @@ namespace Fw { (void) snprintf( destBuffer, buffSize, - fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + fileIdFs " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, file, lineNo, @@ -85,7 +85,7 @@ namespace Fw { (void) snprintf( destBuffer, buffSize, - fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + fileIdFs " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, file, @@ -97,7 +97,7 @@ namespace Fw { (void) snprintf( destBuffer, buffSize, - fileIdFs "%" PRI_FwAssertArgType " %" PRI_FwAssertArgType + fileIdFs " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType " %" PRI_FwAssertArgType, file, From b653ba956379ef776d5154a0b480e88dce460a69 Mon Sep 17 00:00:00 2001 From: kevin-f-ortega Date: Wed, 19 Oct 2022 15:35:06 -0700 Subject: [PATCH 077/169] made pound-inclde conditional consistent with PolyType.cpp (#1726) --- Fw/Types/PolyType.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Fw/Types/PolyType.hpp b/Fw/Types/PolyType.hpp index 8d16d97367..3d6ba541fc 100644 --- a/Fw/Types/PolyType.hpp +++ b/Fw/Types/PolyType.hpp @@ -92,7 +92,7 @@ namespace Fw { PolyType(const PolyType &original); //!< copy constructor virtual ~PolyType(); //!< destructor -#if FW_SERIALIZABLE_TO_STRING +#if FW_SERIALIZABLE_TO_STRING || BUILD_UT void toString(StringBase& dest, bool append) const; //!< get string representation void toString(StringBase& dest) const; //!< get string representation #endif From 32086326ca01af2515b1f8a3c533c86cea029c7f Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Thu, 20 Oct 2022 10:26:51 -0700 Subject: [PATCH 078/169] Revise math tutorial (#1729) Remove outdated reference to v3.0.0 --- docs/Tutorials/MathComponent/Tutorial.md | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/docs/Tutorials/MathComponent/Tutorial.md b/docs/Tutorials/MathComponent/Tutorial.md index 335ae1838b..2543bf6a21 100644 --- a/docs/Tutorials/MathComponent/Tutorial.md +++ b/docs/Tutorials/MathComponent/Tutorial.md @@ -102,15 +102,14 @@ in the [F Prime git repository](https://github.com/nasa/fprime). You may also wish to work through the Getting Started tutorial at `docs/GettingStarted/Tutorial.md`. -**F´ Version:** This tutorial is designed to work with release `v3.0.0`. - -Working on this tutorial will modify some files under version control in the -F Prime git repository. +**Version control:** +Working on this tutorial will modify some files under version control +in the F Prime git repository. Therefore it is a good idea to do this work on a new branch. For example: ```bash -git checkout -b math-tutorial v3.0.0 +git checkout -b math-tutorial ``` If you wish, you can save your work by committing to this branch. From f319e7c0617e2efa75b2e9afa2aa99007d523c4b Mon Sep 17 00:00:00 2001 From: Esteban Duran Date: Thu, 27 Oct 2022 13:41:33 -0500 Subject: [PATCH 079/169] Add A CITATION.cff File (#954) * feat: Add CITATION.cff File #946 * Removes Authors From CITATION.cff --- .github/actions/spelling/expect.txt | 1 + CITATION.cff | 4 ++++ 2 files changed, 5 insertions(+) create mode 100644 CITATION.cff diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 7e1a503a8e..4ce0ea8538 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -149,6 +149,7 @@ cdn cerrno cface CFDP +cff cflag cfsetispeed cfsetospeed diff --git a/CITATION.cff b/CITATION.cff new file mode 100644 index 0000000000..dea4476a0f --- /dev/null +++ b/CITATION.cff @@ -0,0 +1,4 @@ +cff-version: 1.2.0 +message: "If you use this software, please cite it as below." +title: "F´: A Flight-Proven, Multi-Platform, Open-Source Flight Software Framework" +url: "https://github.com/nasa/fprime" From 0b03ce39f30ea0d4f6cc4dda400e8a8a1280c530 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 27 Oct 2022 12:27:30 -0700 Subject: [PATCH 080/169] Update CITATION.cff (#1740) --- CITATION.cff | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CITATION.cff b/CITATION.cff index dea4476a0f..0969068080 100644 --- a/CITATION.cff +++ b/CITATION.cff @@ -1,4 +1,6 @@ cff-version: 1.2.0 message: "If you use this software, please cite it as below." +authors: + - name: "The F´ Framework Team" title: "F´: A Flight-Proven, Multi-Platform, Open-Source Flight Software Framework" url: "https://github.com/nasa/fprime" From 8855f315bbb51941102d9d12386f394db3d72d75 Mon Sep 17 00:00:00 2001 From: Gabriel Zayas Date: Fri, 28 Oct 2022 04:34:24 +0900 Subject: [PATCH 081/169] Add tests for the `Time` class in Fw (#1736) * Add tests for Fw's Time class * Unify test comment wording --- Fw/Time/test/ut/TimeTest.cpp | 31 ++++++++++++++++++++++++------- 1 file changed, 24 insertions(+), 7 deletions(-) diff --git a/Fw/Time/test/ut/TimeTest.cpp b/Fw/Time/test/ut/TimeTest.cpp index 87ffaa6311..d2b744ce1f 100644 --- a/Fw/Time/test/ut/TimeTest.cpp +++ b/Fw/Time/test/ut/TimeTest.cpp @@ -24,24 +24,41 @@ TEST(TimeTestNominal,MathTest) { Fw::Time time1; Fw::Time time2; - // Try various operations - + // Comparison time1.set(1000,1000); - time2.set(4000,2000); + time2.set(1000,1000); + ASSERT_TRUE(time1 == time2); + ASSERT_TRUE(time1 >= time2); + ASSERT_TRUE(time1 <= time2); - // test add + time1.set(1000,1000); + time2.set(2000,1000); + ASSERT_TRUE(time1 != time2); + ASSERT_TRUE(time1 < time2); + ASSERT_TRUE(time1 <= time2); + time1.set(2000,1000); + time2.set(1000,1000); + ASSERT_TRUE(time1 > time2); + ASSERT_TRUE(time1 >= time2); - // test subtract + // Addition + time1.set(1000,1000); + time2.set(4000,2000); + Fw::Time time_sum = Fw::Time::add(time1,time2); + ASSERT_EQ(time_sum.m_seconds,5000); + ASSERT_EQ(time_sum.m_useconds,3000); - // normal subtract + // Normal subtraction + time1.set(1000,1000); + time2.set(4000,2000); Fw::Time time3 = Fw::Time::sub(time2,time1); ASSERT_EQ(time3.m_timeBase,TB_NONE); ASSERT_EQ(time3.m_timeContext,0); ASSERT_EQ(time3.m_seconds,3000); ASSERT_EQ(time3.m_useconds,1000); - // rollover subtract + // Rollover subtraction time1.set(1,999999); time2.set(2,000001); time3 = Fw::Time::sub(time2,time1); From 22759cc9e2fbb54acc067d666780c1a20dd9c939 Mon Sep 17 00:00:00 2001 From: Thomas Boyer Chammard <49786685+thomas-bc@users.noreply.github.com> Date: Thu, 27 Oct 2022 13:37:09 -0700 Subject: [PATCH 082/169] Switch to Github Actions Code Scanner (#1739) * Added CodeQL security scan * typo fix * Fix codeql error alert --- .github/actions/codeql/security-pack.yml | 19 +++++++ .github/actions/spelling/expect.txt | 1 + .github/workflows/codeql-security-scan.yml | 50 +++++++++++++++++++ .../src/fprime_ac/generators/formatters.py | 5 +- 4 files changed, 71 insertions(+), 4 deletions(-) create mode 100644 .github/actions/codeql/security-pack.yml create mode 100644 .github/workflows/codeql-security-scan.yml diff --git a/.github/actions/codeql/security-pack.yml b/.github/actions/codeql/security-pack.yml new file mode 100644 index 0000000000..1c9e6d08f4 --- /dev/null +++ b/.github/actions/codeql/security-pack.yml @@ -0,0 +1,19 @@ +name: "CodeQL security and quality" + +queries: + - uses: security-and-quality + +query-filters: + - include: + id: cpp/incorrect-not-operator-usage + - include: + tags contain: correctness + - include: + tags contain: reliability + +paths-ignore: + - docs/ + - cmake/docs/ + - cmake/test/ + - Autocoders/Python/src/fprime_ac/utils/DiffAndRename.py + - Autocoders/Python/src/fprime_ac/utils/pyparsing.py diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 4ce0ea8538..4f02ce4c1e 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -193,6 +193,7 @@ cntx cobj CODEFILE codegen +codeql colno COLORSTYLE colorwheel diff --git a/.github/workflows/codeql-security-scan.yml b/.github/workflows/codeql-security-scan.yml new file mode 100644 index 0000000000..41509f86ae --- /dev/null +++ b/.github/workflows/codeql-security-scan.yml @@ -0,0 +1,50 @@ +# Semantic code analysis with CodeQL +# see https://github.com/github/codeql-action + +name: "CodeQL Security Scan" + +on: + push: + branches: [ master, devel ] + pull_request: + # The branches below must be a subset of the branches above + branches: [ master, devel ] + +jobs: + analyze: + name: Analyze + runs-on: ubuntu-latest + permissions: + actions: read + contents: read + security-events: write + + strategy: + fail-fast: false + matrix: + language: [ 'cpp', 'python' ] + + steps: + - name: Checkout repository + uses: actions/checkout@v3 + + # Initializes the CodeQL tools for scanning. + - name: Initialize CodeQL + uses: github/codeql-action/init@v2 + with: + languages: ${{ matrix.language }} + config-file: ./.github/actions/codeql/security-pack.yml + + - if: ${{ matrix.language == 'cpp' }} + name: Build + run: | + python3 -m venv ./fprime-venv + . ./fprime-venv/bin/activate + pip install -U setuptools setuptools_scm wheel pip + pip install -r ./requirements.txt + fprime-util generate + fprime-util build --all + - name: Perform CodeQL Analysis + uses: github/codeql-action/analyze@v2 + with: + category: "/language:${{matrix.language}}" diff --git a/Autocoders/Python/src/fprime_ac/generators/formatters.py b/Autocoders/Python/src/fprime_ac/generators/formatters.py index 8c0790b2d9..5b75678c24 100644 --- a/Autocoders/Python/src/fprime_ac/generators/formatters.py +++ b/Autocoders/Python/src/fprime_ac/generators/formatters.py @@ -1310,10 +1310,7 @@ def subThreadModuleFirstCap(self, mod_id): and no '_' in string form. """ mod_id_list = mod_id.strip("_").split("_") - if len(mod_id_list) == 1: - mod_id_cap = mod_id[0].upper() + mod_id[1:] - elif len(mod_id_list) == 2: - mod_id_cap = [x[0].upper() + x[1:] for x in mod_id_list] + mod_id_cap = [x[0].upper() + x[1:] for x in mod_id_list] # size of mod_id list error in subThreadDir method. mod_id_cap_str = "".join(mod_id_cap) return mod_id_cap_str From 0444a02312345bfd5c0a9ac43fac88a071014fa2 Mon Sep 17 00:00:00 2001 From: Simone Morettini Date: Fri, 28 Oct 2022 01:31:08 +0200 Subject: [PATCH 083/169] Fix tests failing because of variable optimized out (#1735) Co-authored-by: Simone Morettini --- Drv/TcpClient/test/ut/Tester.hpp | 2 +- Drv/TcpServer/test/ut/Tester.hpp | 2 +- Drv/Udp/test/ut/Tester.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Drv/TcpClient/test/ut/Tester.hpp b/Drv/TcpClient/test/ut/Tester.hpp index 2673a28959..c30c9b438b 100644 --- a/Drv/TcpClient/test/ut/Tester.hpp +++ b/Drv/TcpClient/test/ut/Tester.hpp @@ -115,7 +115,7 @@ namespace Drv { Fw::Buffer m_data_buffer; Fw::Buffer m_data_buffer2; U8 m_data_storage[SEND_DATA_BUFFER_SIZE]; - bool m_spinner; + std::atomic m_spinner; }; diff --git a/Drv/TcpServer/test/ut/Tester.hpp b/Drv/TcpServer/test/ut/Tester.hpp index 9ea46a04e6..0f1ec0eb46 100644 --- a/Drv/TcpServer/test/ut/Tester.hpp +++ b/Drv/TcpServer/test/ut/Tester.hpp @@ -125,7 +125,7 @@ namespace Drv { Fw::Buffer m_data_buffer; Fw::Buffer m_data_buffer2; U8 m_data_storage[SEND_DATA_BUFFER_SIZE]; - bool m_spinner; + std::atomic m_spinner; }; diff --git a/Drv/Udp/test/ut/Tester.hpp b/Drv/Udp/test/ut/Tester.hpp index 18323d89dd..aaf438d0ca 100644 --- a/Drv/Udp/test/ut/Tester.hpp +++ b/Drv/Udp/test/ut/Tester.hpp @@ -126,7 +126,7 @@ namespace Drv { Fw::Buffer m_data_buffer; Fw::Buffer m_data_buffer2; U8 m_data_storage[SEND_DATA_BUFFER_SIZE]; - bool m_spinner; + std::atomic m_spinner; }; } // end namespace Drv From cdc452baa9080411749228e9573871be0f6e60ca Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 28 Oct 2022 13:08:10 -0700 Subject: [PATCH 084/169] lestarch: prints missing fpp error(s) in generate (#1743) --- .../autocoder/fpp-wrapper/fpp-depend-parallelize.py | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/cmake/autocoder/fpp-wrapper/fpp-depend-parallelize.py b/cmake/autocoder/fpp-wrapper/fpp-depend-parallelize.py index cc75b9e40d..2bb45a71ce 100755 --- a/cmake/autocoder/fpp-wrapper/fpp-depend-parallelize.py +++ b/cmake/autocoder/fpp-wrapper/fpp-depend-parallelize.py @@ -5,6 +5,14 @@ from pathlib import Path +class ExceptionWithStandardError(Exception): + """Exception plus standard error""" + + def __init__(self, message, stderr): + message = f"{message}\n{stderr}" + super().__init__(message) + + def run_process(directory, arguments): """Runs the fpp-depend process""" working_dir = directory / "fpp-cache" @@ -16,6 +24,7 @@ def run_process(directory, arguments): stdin=subprocess.DEVNULL, stdout=capture_file, stderr=subprocess.PIPE, + text=True, ) @@ -23,7 +32,9 @@ def raise_on_error(process, arguments): """Waits for process, raises on error""" code = process.wait() if code != 0: - raise Exception(f"Failed to run '{' '.join(arguments)}'") + raise ExceptionWithStandardError( + f"Failed to run '{' '.join(arguments)}'", process.stderr.read() + ) def run_parallel_depend(fpp_depend, fpp_locs, file_input): From dec263079297a2424f200b921b4cb4b490a05067 Mon Sep 17 00:00:00 2001 From: Thomas Boyer Chammard <49786685+thomas-bc@users.noreply.github.com> Date: Fri, 28 Oct 2022 13:09:02 -0700 Subject: [PATCH 085/169] Static Analysis for JPL Coding Guidelines (#1742) * Added JPL Coding Standard workflow * Trigger queries * Clean up config file * Fix devel branch name --- .../actions/codeql/jpl-standard-pack-1.yml | 12 +++++ .../actions/codeql/jpl-standard-pack-2.yml | 20 ++++++++ .../actions/codeql/jpl-standard-pack-3.yml | 13 +++++ .github/workflows/codeql-jpl-standard.yml | 50 +++++++++++++++++++ 4 files changed, 95 insertions(+) create mode 100644 .github/actions/codeql/jpl-standard-pack-1.yml create mode 100644 .github/actions/codeql/jpl-standard-pack-2.yml create mode 100644 .github/actions/codeql/jpl-standard-pack-3.yml create mode 100644 .github/workflows/codeql-jpl-standard.yml diff --git a/.github/actions/codeql/jpl-standard-pack-1.yml b/.github/actions/codeql/jpl-standard-pack-1.yml new file mode 100644 index 0000000000..bff4722654 --- /dev/null +++ b/.github/actions/codeql/jpl-standard-pack-1.yml @@ -0,0 +1,12 @@ +name: "CodeQL JPL Coding Standard - Errors and Warnings" + +disable-default-queries: true + +packs: + # Source of the query pack is https://github.com/github/codeql/tree/main/cpp/ql/src/JPL_C + - codeql/cpp-queries:JPL_C + +query-filters: + - exclude: + problem.severity: + - recommendation diff --git a/.github/actions/codeql/jpl-standard-pack-2.yml b/.github/actions/codeql/jpl-standard-pack-2.yml new file mode 100644 index 0000000000..61b0e53dc4 --- /dev/null +++ b/.github/actions/codeql/jpl-standard-pack-2.yml @@ -0,0 +1,20 @@ +name: "CodeQL JPL Coding Standard - Recommendations 1 of 2" + +disable-default-queries: true + +packs: + # Source of the query pack is https://github.com/github/codeql/tree/main/cpp/ql/src/JPL_C + - codeql/cpp-queries:JPL_C + +query-filters: + - exclude: + problem.severity: + - error + - warning + # We are excluding the following query because it overflows the limit of + # 5000 results that the SARIF upload can handle + # This sole query is ran in jpl-standard-pack-3.yml + # https://docs.github.com/en/code-security/code-scanning/integrating-with-code-scanning/uploading-a-sarif-file-to-github#uploading-a-code-scanning-analysis-with-github-actions + - exclude: + id: + - cpp/jpl-c/basic-int-types diff --git a/.github/actions/codeql/jpl-standard-pack-3.yml b/.github/actions/codeql/jpl-standard-pack-3.yml new file mode 100644 index 0000000000..2b56eb507d --- /dev/null +++ b/.github/actions/codeql/jpl-standard-pack-3.yml @@ -0,0 +1,13 @@ +name: "CodeQL JPL Coding Standard - Recommendations 2 of 2" + +disable-default-queries: true + +packs: + # Source of the query pack is https://github.com/github/codeql/tree/main/cpp/ql/src/JPL_C + - codeql/cpp-queries:JPL_C + +query-filters: + # This will ONLY include the following query + - include: + id: + - cpp/jpl-c/basic-int-types diff --git a/.github/workflows/codeql-jpl-standard.yml b/.github/workflows/codeql-jpl-standard.yml new file mode 100644 index 0000000000..150ebe1594 --- /dev/null +++ b/.github/workflows/codeql-jpl-standard.yml @@ -0,0 +1,50 @@ +# Semantic code analysis with CodeQL +# see https://github.com/github/codeql-action + +name: "JPL Coding Standard Scan" + +on: + push: + branches: [ master, devel ] + pull_request: + # The branches below must be a subset of the branches above + branches: [ master, devel ] + +jobs: + analyze: + name: Analyze + runs-on: ubuntu-latest + permissions: + actions: read + contents: read + security-events: write + + strategy: + fail-fast: false + matrix: + language: [ 'cpp' ] + config-file: ['jpl-standard-pack-1.yml', 'jpl-standard-pack-2.yml', 'jpl-standard-pack-3.yml'] + + steps: + - name: Checkout repository + uses: actions/checkout@v3 + + # Initializes the CodeQL tools for scanning. + - name: Initialize CodeQL + uses: github/codeql-action/init@v2 + with: + languages: ${{ matrix.language }} + # Run jobs in parallel for each config-file + config-file: ./.github/actions/codeql/${{ matrix.config-file }} + + - name: Build + run: | + python3 -m venv ./fprime-venv + . ./fprime-venv/bin/activate + pip install -U setuptools setuptools_scm wheel pip + pip install -r ./requirements.txt + fprime-util generate + fprime-util build --all + + - name: Perform CodeQL Analysis + uses: github/codeql-action/analyze@v2 From 356eade6a200efff537209aeebbbb5a239e46e3c Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 1 Nov 2022 11:08:17 -0700 Subject: [PATCH 086/169] Delete .lgtm.yml (#1744) --- .lgtm.yml | 43 ------------------------------------------- 1 file changed, 43 deletions(-) delete mode 100644 .lgtm.yml diff --git a/.lgtm.yml b/.lgtm.yml deleted file mode 100644 index 08fd0cd122..0000000000 --- a/.lgtm.yml +++ /dev/null @@ -1,43 +0,0 @@ -############## -# Configuration file for LGTM.com -# Currently only needed for cpp code since python and js works by default -# -# @author: Hunter Paulson -# @modified: 2020-07-15 -############## - - -path_classifiers: - docs: - - docs -queries: - - include: cpp/incorrect-not-operator-usage - - include: - tags: - - "correctness" - - include: - tags: - - "reliability" -extraction: - cpp: - prepare: - packages: - - "python3" - - "python3-pip" - - "python3-venv" - after_prepare: - # setup the venv and install packages - - "python3 -m venv ./fprime-venv" - - ". ./fprime-venv/bin/activate" - - "pip install -U setuptools setuptools_scm wheel pip" - - "wget https://github.com/sbt/sbt/releases/download/v1.6.2/sbt-1.6.2.tgz" - - "tar -xzf sbt-1.6.2.tgz" - - "export PATH=$PATH:$LGTM_SRC/sbt/bin" - - "pip install -r ./requirements.txt" - configure: - command: - before_index: - - "fprime-util generate" - index: - build_command: - - "fprime-util build --all" From f5c5fb1007ee536dbf2bb709a592a55fc6f070af Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 1 Nov 2022 11:25:08 -0700 Subject: [PATCH 087/169] Delete .lgtm.js (#1745) --- .lgtm.js | 1 - 1 file changed, 1 deletion(-) delete mode 100644 .lgtm.js diff --git a/.lgtm.js b/.lgtm.js deleted file mode 100644 index 41a02371c1..0000000000 --- a/.lgtm.js +++ /dev/null @@ -1 +0,0 @@ -function appease_lgtm() {} From 8c8b9d04014f9239842889cdb480b8faaeb4d4dd Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 3 Nov 2022 10:20:56 -0700 Subject: [PATCH 088/169] lestarch: bumping zmq and GDS versions (#1756) * lestarch: bumping zmq and GDS versions * lestarch: adding `wheel` to setup * lestarch: checking tools before leaving action * lestarch: reverting to mac11 runners See: https://github.com/actions/runner-images/issues/6507 --- .github/actions/setup/action.yml | 9 ++++++++- .github/workflows/build-test-macos.yml | 6 +++--- requirements.txt | 4 ++-- 3 files changed, 13 insertions(+), 6 deletions(-) diff --git a/.github/actions/setup/action.yml b/.github/actions/setup/action.yml index b2869a0ac3..471cb285d4 100644 --- a/.github/actions/setup/action.yml +++ b/.github/actions/setup/action.yml @@ -9,7 +9,14 @@ runs: steps: - run: git fetch --tags shell: bash - - run: pip3 install setuptools_scm urllib3 + - run: pip3 install setuptools_scm wheel urllib3 shell: bash - run: pip3 install -r ${{ inputs.location }}/requirements.txt shell: bash + - run: which fprime-util + shell: bash + - run: which fprime-gds + shell: bash + - run: which fpp-check + shell: bash + diff --git a/.github/workflows/build-test-macos.yml b/.github/workflows/build-test-macos.yml index 352096ff2d..3fea6f7501 100644 --- a/.github/workflows/build-test-macos.yml +++ b/.github/workflows/build-test-macos.yml @@ -13,7 +13,7 @@ on: # A workflow run is made up of one or more jobs that can run sequentially or in parallel jobs: MacOS-Framework: - runs-on: macos-latest + runs-on: macos-11 steps: - name: "Checkout F´ Repository" uses: actions/checkout@v2 @@ -32,7 +32,7 @@ jobs: retention-days: 5 MacOS-Ref: - runs-on: macos-latest + runs-on: macos-11 steps: - name: "Checkout F´ Repository" uses: actions/checkout@v2 @@ -51,7 +51,7 @@ jobs: retention-days: 5 MacOS-Integration: - runs-on: macos-latest + runs-on: macos-11 steps: - name: "Checkout F´ Repository" uses: actions/checkout@v2 diff --git a/requirements.txt b/requirements.txt index c35d339c78..07101c59c7 100644 --- a/requirements.txt +++ b/requirements.txt @@ -14,7 +14,7 @@ Flask==1.1.4 Flask-Compress==1.12 Flask-RESTful==0.3.9 fprime-fpp==1.0.2 -fprime-gds==3.1.3 +fprime-gds==3.1.4 fprime-tools==3.1.1 gcovr==5.1 idna==3.3 @@ -38,7 +38,7 @@ pytest==6.2.5 python-dateutil==2.8.2 python-slugify==6.1.2 pytz==2022.1 -pyzmq==22.3.0 +pyzmq==24.0.1 requests==2.28.0 six==1.16.0 text-unidecode==1.3 From 05768028571714c8f6b92bf433540bc65f8aee34 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 3 Nov 2022 13:53:54 -0700 Subject: [PATCH 089/169] Update/fix mac py path (#1759) * lestarch: our last fix worked for 1 day * lestarch: return to latest * lestarch: missing shell directive --- .github/actions/setup/action.yml | 3 +++ .github/workflows/build-test-macos.yml | 6 +++--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/actions/setup/action.yml b/.github/actions/setup/action.yml index 471cb285d4..af35e60fb4 100644 --- a/.github/actions/setup/action.yml +++ b/.github/actions/setup/action.yml @@ -9,6 +9,9 @@ runs: steps: - run: git fetch --tags shell: bash + - name: Add Python bin to PATH + run: echo "/Library/Frameworks/Python.framework/Versions/Current/bin" >> $GITHUB_PATH + shell: bash - run: pip3 install setuptools_scm wheel urllib3 shell: bash - run: pip3 install -r ${{ inputs.location }}/requirements.txt diff --git a/.github/workflows/build-test-macos.yml b/.github/workflows/build-test-macos.yml index 3fea6f7501..352096ff2d 100644 --- a/.github/workflows/build-test-macos.yml +++ b/.github/workflows/build-test-macos.yml @@ -13,7 +13,7 @@ on: # A workflow run is made up of one or more jobs that can run sequentially or in parallel jobs: MacOS-Framework: - runs-on: macos-11 + runs-on: macos-latest steps: - name: "Checkout F´ Repository" uses: actions/checkout@v2 @@ -32,7 +32,7 @@ jobs: retention-days: 5 MacOS-Ref: - runs-on: macos-11 + runs-on: macos-latest steps: - name: "Checkout F´ Repository" uses: actions/checkout@v2 @@ -51,7 +51,7 @@ jobs: retention-days: 5 MacOS-Integration: - runs-on: macos-11 + runs-on: macos-latest steps: - name: "Checkout F´ Repository" uses: actions/checkout@v2 From bba76691f2ff828e62ebb1fc4796c0cb6d75fd5c Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 3 Nov 2022 17:36:10 -0700 Subject: [PATCH 090/169] lestarch: adding Svc::ComQueue component (#1741) * lestarch: initial com queue work Co-authored-by: pelmini <37095187+pelmini@users.noreply.github.com> * lestarch: fix Fw::Buffer ownership for retries * lestarch: adding com queue buffer handling fix * lestarch: fixing com queue unit test * lestarch: adding this-> to prefix member variables * lestarch: fixing CI flagged items * lestarch: fixing review comments * lestarch: cleaning up SDD adding diagrams * lestarch: renaming m_retryBuffer and formatting * lestarch: update state machine diagram including retry buffers * lestarch: sp * lestarch: removing retries from com queue * Update component diagram * Fix typo in ComQueue SDD Co-authored-by: pelmini <37095187+pelmini@users.noreply.github.com> Co-authored-by: bocchino --- .github/actions/spelling/expect.txt | 4 + Svc/CMakeLists.txt | 1 + Svc/ComQueue/CMakeLists.txt | 26 ++ Svc/ComQueue/ComQueue.cpp | 259 ++++++++++++++++++ Svc/ComQueue/ComQueue.fpp | 75 ++++++ Svc/ComQueue/ComQueue.hpp | 195 ++++++++++++++ Svc/ComQueue/docs/img/ComQueue.png | Bin 0 -> 120421 bytes Svc/ComQueue/docs/img/state-machine.png | Bin 0 -> 17348 bytes Svc/ComQueue/docs/img/state-machine.puml | 20 ++ Svc/ComQueue/docs/sdd.md | 165 ++++++++++++ Svc/ComQueue/test/ut/TestMain.cpp | 35 +++ Svc/ComQueue/test/ut/Tester.cpp | 327 +++++++++++++++++++++++ Svc/ComQueue/test/ut/Tester.hpp | 106 ++++++++ Utils/Types/CMakeLists.txt | 1 + Utils/Types/CircularBuffer.cpp | 49 +++- Utils/Types/CircularBuffer.hpp | 36 ++- Utils/Types/Queue.cpp | 56 ++++ Utils/Types/Queue.hpp | 92 +++++++ config/AcConstants.fpp | 6 + 19 files changed, 1447 insertions(+), 6 deletions(-) create mode 100644 Svc/ComQueue/CMakeLists.txt create mode 100644 Svc/ComQueue/ComQueue.cpp create mode 100644 Svc/ComQueue/ComQueue.fpp create mode 100644 Svc/ComQueue/ComQueue.hpp create mode 100644 Svc/ComQueue/docs/img/ComQueue.png create mode 100644 Svc/ComQueue/docs/img/state-machine.png create mode 100644 Svc/ComQueue/docs/img/state-machine.puml create mode 100644 Svc/ComQueue/docs/sdd.md create mode 100644 Svc/ComQueue/test/ut/TestMain.cpp create mode 100644 Svc/ComQueue/test/ut/Tester.cpp create mode 100644 Svc/ComQueue/test/ut/Tester.hpp create mode 100644 Utils/Types/Queue.cpp create mode 100644 Utils/Types/Queue.hpp diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 4f02ce4c1e..c709f4d699 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -120,6 +120,7 @@ buf BUFFERALLOCATE BUFFERMANAGERCOMPONENTIMPLCFG BUFFERMGR +BUFFQUEUEIN buffsize BUGLIST bugprone @@ -205,6 +206,8 @@ commasepitem commonpath COMPACKET COMPONENTTESTERIMPL +COMQUEUE +COMQUEUEIN COMSPLITTER COMSTUB Concat @@ -1519,6 +1522,7 @@ valgrind validator vals valud +vbai venv VERSIONED versioning diff --git a/Svc/CMakeLists.txt b/Svc/CMakeLists.txt index bf6131e82d..92febc9ffa 100644 --- a/Svc/CMakeLists.txt +++ b/Svc/CMakeLists.txt @@ -16,6 +16,7 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/AssertFatalAdapter/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferManager/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferLogger/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComLogger/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComQueue/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComSplitter/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComStub/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/CmdDispatcher/") diff --git a/Svc/ComQueue/CMakeLists.txt b/Svc/ComQueue/CMakeLists.txt new file mode 100644 index 0000000000..b6b01756f6 --- /dev/null +++ b/Svc/ComQueue/CMakeLists.txt @@ -0,0 +1,26 @@ +#### +# F prime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoding diles +# MOD_DEPS: (optional) module dependencies +# +# Note: using PROJECT_NAME as EXECUTABLE_NAME +#### +set(MOD_DEPS + Utils/Types + Fw/Buffer + Fw/Types + ) +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/ComQueue.fpp" + "${CMAKE_CURRENT_LIST_DIR}/ComQueue.cpp" + ) +register_fprime_module() + +### UTs ### +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/ComQueue.fpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/TestMain.cpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" + ) +register_fprime_ut() diff --git a/Svc/ComQueue/ComQueue.cpp b/Svc/ComQueue/ComQueue.cpp new file mode 100644 index 0000000000..41038ad1e2 --- /dev/null +++ b/Svc/ComQueue/ComQueue.cpp @@ -0,0 +1,259 @@ +// ====================================================================== +// \title ComQueue.cpp +// \author vbai +// \brief cpp file for ComQueue component implementation class +// ====================================================================== + +#include +#include +#include "Fw/Types/BasicTypes.hpp" + +namespace Svc { + +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +ComQueue ::QueueConfigurationTable ::QueueConfigurationTable() { + for (NATIVE_UINT_TYPE i = 0; i < FW_NUM_ARRAY_ELEMENTS(this->entries); i++) { + this->entries[i].priority = 0; + this->entries[i].depth = 0; + } +} + +ComQueue ::ComQueue(const char* const compName) + : ComQueueComponentBase(compName), + m_state(WAITING), + m_allocationId(-1), + m_allocator(nullptr), + m_allocation(nullptr) { + // Initialize throttles to "off" + for (NATIVE_UINT_TYPE i = 0; i < TOTAL_PORT_COUNT; i++) { + this->m_throttle[i] = false; + } +} + +ComQueue ::~ComQueue() {} + +void ComQueue ::init(const NATIVE_INT_TYPE queueDepth, const NATIVE_INT_TYPE instance) { + ComQueueComponentBase::init(queueDepth, instance); +} + +void ComQueue ::cleanup() { + // Deallocate memory ignoring error conditions + if ((this->m_allocator != nullptr) && (this->m_allocation != nullptr)) { + this->m_allocator->deallocate(this->m_allocationId, this->m_allocation); + } +} + +void ComQueue::configure(QueueConfigurationTable queueConfig, + NATIVE_UINT_TYPE allocationId, + Fw::MemAllocator& allocator) { + FwIndexType currentPriorityIndex = 0; + FwSizeType totalAllocation = 0; + + // Store/initialize allocator members + this->m_allocator = &allocator; + this->m_allocationId = allocationId; + this->m_allocation = nullptr; + + // Initializes the sorted queue metadata list in priority (sorted) order. This is accomplished by walking the + // priority values in priority order from 0 to TOTAL_PORT_COUNT. At each priory value, the supplied queue + // configuration table is walked and any entry matching the current priority values is used to add queue metadata to + // the prioritized list. This results in priority-sorted queue metadata objects that index back into the unsorted + // queue data structures. + // + // The total allocation size is tracked for passing to the allocation call and is a summation of + // (depth * message size) for each prioritized metadata object of (depth * message size) + for (FwIndexType currentPriority = 0; currentPriority < TOTAL_PORT_COUNT; currentPriority++) { + // Walk each queue configuration entry and add them into the prioritized metadata list when matching the current + // priority value + for (NATIVE_UINT_TYPE entryIndex = 0; entryIndex < FW_NUM_ARRAY_ELEMENTS(queueConfig.entries); entryIndex++) { + // Check for valid configuration entry + FW_ASSERT(queueConfig.entries[entryIndex].priority < TOTAL_PORT_COUNT, + queueConfig.entries[entryIndex].priority, TOTAL_PORT_COUNT, entryIndex); + + if (currentPriority == queueConfig.entries[entryIndex].priority) { + // Set up the queue metadata object in order to track priority, depth, index into the queue list of the + // backing queue object, and message size. Both index and message size are calculated where priority and + // depth are copied from the configuration object. + QueueMetadata& entry = this->m_prioritizedList[currentPriorityIndex]; + entry.priority = queueConfig.entries[entryIndex].priority; + entry.depth = queueConfig.entries[entryIndex].depth; + entry.index = entryIndex; + // Message size is determined by the type of object being stored, which in turn is determined by the + // index of the entry. Those lower than COM_PORT_COUNT are Fw::ComBuffers and those larger Fw::Buffer. + entry.msgSize = (entryIndex < COM_PORT_COUNT) ? sizeof(Fw::ComBuffer) : sizeof(Fw::Buffer); + totalAllocation += entry.depth * entry.msgSize; + currentPriorityIndex++; + } + } + } + // Allocate a single chunk of memory from the memory allocator. Memory recover is neither needed nor used. + bool recoverable = false; + this->m_allocation = this->m_allocator->allocate(this->m_allocationId, totalAllocation, recoverable); + + // Each of the backing queue objects must be supplied memory to store the queued messages. These data regions are + // sub-portions of the total allocated data. This memory is passed out by looping through each queue in prioritized + // order and passing out the memory to each queue's setup method. + FwSizeType allocationOffset = 0; + for (FwIndexType i = 0; i < TOTAL_PORT_COUNT; i++) { + // Get current queue's allocation size and safety check the values + FwSizeType allocationSize = this->m_prioritizedList[i].depth * this->m_prioritizedList[i].msgSize; + FW_ASSERT(this->m_prioritizedList[i].index < static_cast(FW_NUM_ARRAY_ELEMENTS(this->m_queues)), + this->m_prioritizedList[i].index); + FW_ASSERT((allocationSize + allocationOffset) <= totalAllocation, allocationSize, allocationOffset, + totalAllocation); + + // Setup queue's memory allocation, depth, and message size. Setup is skipped for a depth 0 queue + if (allocationSize > 0) { + this->m_queues[this->m_prioritizedList[i].index].setup( + reinterpret_cast(this->m_allocation) + allocationOffset, allocationSize, + this->m_prioritizedList[i].depth, this->m_prioritizedList[i].msgSize); + } + allocationOffset += allocationSize; + } + // Safety check that all memory was used as expected + FW_ASSERT(allocationOffset == totalAllocation, allocationOffset, totalAllocation); +} +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- + +void ComQueue::comQueueIn_handler(const NATIVE_INT_TYPE portNum, Fw::ComBuffer& data, U32 context) { + // Ensure that the port number of comQueueIn is consistent with the expectation + FW_ASSERT(portNum >= 0 && portNum < COM_PORT_COUNT, portNum); + this->enqueue(portNum, QueueType::COM_QUEUE, reinterpret_cast(&data), sizeof(Fw::ComBuffer)); +} + +void ComQueue::buffQueueIn_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { + const NATIVE_INT_TYPE queueNum = portNum + COM_PORT_COUNT; + // Ensure that the port number of buffQueueIn is consistent with the expectation + FW_ASSERT(portNum >= 0 && portNum < BUFFER_PORT_COUNT, portNum); + FW_ASSERT(queueNum < TOTAL_PORT_COUNT); + this->enqueue(queueNum, QueueType::BUFFER_QUEUE, reinterpret_cast(&fwBuffer), sizeof(Fw::Buffer)); +} + +void ComQueue::comStatusIn_handler(const NATIVE_INT_TYPE portNum, Fw::Success& condition) { + switch (this->m_state) { + // On success, the queue should be processed. On failure, the component should still wait. + case WAITING: + if (condition.e == Fw::Success::SUCCESS) { + this->m_state = READY; + this->processQueue(); + // A message may or may not be sent. Thus, READY or WAITING are acceptable final states. + FW_ASSERT((this->m_state == WAITING || this->m_state == READY), this->m_state); + } else { + this->m_state = WAITING; + } + break; + // Both READY and unknown states should not be possible at this point. To receive a status message we must be + // one of the WAITING or RETRY states. + default: + FW_ASSERT(0, this->m_state); + break; + } +} + +void ComQueue::run_handler(const NATIVE_INT_TYPE portNum, NATIVE_UINT_TYPE context) { + // Downlink the high-water marks for the Fw::ComBuffer array types + ComQueueDepth comQueueDepth; + for (FwSizeType i = 0; i < comQueueDepth.SIZE; i++) { + comQueueDepth[i] = this->m_queues[i].get_high_water_mark(); + this->m_queues[i].clear_high_water_mark(); + } + this->tlmWrite_comQueueDepth(comQueueDepth); + + // Downlink the high-water marks for the Fw::Buffer array types + BuffQueueDepth buffQueueDepth; + for (FwSizeType i = 0; i < buffQueueDepth.SIZE; i++) { + buffQueueDepth[i] = this->m_queues[i + COM_PORT_COUNT].get_high_water_mark(); + this->m_queues[i + COM_PORT_COUNT].clear_high_water_mark(); + } + this->tlmWrite_buffQueueDepth(buffQueueDepth); +} + +// ---------------------------------------------------------------------- +// Private helper methods +// ---------------------------------------------------------------------- + +void ComQueue::enqueue(const FwIndexType queueNum, QueueType queueType, const U8* data, const FwSizeType size) { + // Enqueue the given message onto the matching queue. When no space is available then emit the queue overflow event, + // set the appropriate throttle, and move on. Will assert if passed a message for a depth 0 queue. + const FwSizeType expectedSize = (queueType == QueueType::COM_QUEUE) ? sizeof(Fw::ComBuffer) : sizeof(Fw::Buffer); + const FwIndexType portNum = queueNum - ((queueType == QueueType::COM_QUEUE) ? 0 : COM_PORT_COUNT); + FW_ASSERT(expectedSize == size, size, expectedSize); + FW_ASSERT(portNum >= 0, portNum); + Fw::SerializeStatus status = this->m_queues[queueNum].enqueue(data, size); + if (status == Fw::FW_SERIALIZE_NO_ROOM_LEFT && !this->m_throttle[queueNum]) { + this->log_WARNING_HI_QueueOverflow(queueType, portNum); + this->m_throttle[queueNum] = true; + } + // When the component is already in READY state process the queue to send out the next available message immediately + if (this->m_state == READY) { + this->processQueue(); + } +} + +void ComQueue::sendComBuffer(Fw::ComBuffer& comBuffer) { + FW_ASSERT(this->m_state == READY); + this->comQueueSend_out(0, comBuffer, 0); + this->m_state = WAITING; +} + +void ComQueue::sendBuffer(Fw::Buffer& buffer) { + // Retry buffer expected to be cleared as we are either transferring ownership or have already deallocated it. + FW_ASSERT(this->m_state == READY); + this->buffQueueSend_out(0, buffer); + this->m_state = WAITING; +} + +void ComQueue::processQueue() { + FwIndexType priorityIndex = 0; + FwIndexType sendPriority = 0; + // Check that we are in the appropriate state + FW_ASSERT(this->m_state == READY); + + // Walk all the queues in priority order. Send the first message that is available in priority order. No balancing + // is done within this loop. + for (priorityIndex = 0; priorityIndex < TOTAL_PORT_COUNT; priorityIndex++) { + QueueMetadata& entry = this->m_prioritizedList[priorityIndex]; + Types::Queue& queue = this->m_queues[entry.index]; + + // Continue onto next prioritized queue if there is no items in the current queue + if (queue.getQueueSize() == 0) { + continue; + } + + // Send out the message based on the type + if (entry.index < COM_PORT_COUNT) { + Fw::ComBuffer comBuffer; + queue.dequeue(reinterpret_cast(&comBuffer), sizeof(comBuffer)); + this->sendComBuffer(comBuffer); + } else { + Fw::Buffer buffer; + queue.dequeue(reinterpret_cast(&buffer), sizeof(buffer)); + this->sendBuffer(buffer); + } + + // Update the throttle and the index that was just sent + this->m_throttle[entry.index] = false; + + // Priority used in the next loop + sendPriority = entry.priority; + break; + } + + // Starting on the priority entry after the one dispatched and continuing through the end of the set of entries that + // share the same priority, rotate those entries such that the currently dispatched queue is last and the rest are + // shifted up by one. This effectively round-robins the queues of the same priority. + for (priorityIndex++; + priorityIndex < TOTAL_PORT_COUNT && (this->m_prioritizedList[priorityIndex].priority == sendPriority); + priorityIndex++) { + // Swap the previous entry with this one. + QueueMetadata temp = this->m_prioritizedList[priorityIndex]; + this->m_prioritizedList[priorityIndex] = this->m_prioritizedList[priorityIndex - 1]; + this->m_prioritizedList[priorityIndex - 1] = temp; + } +} +} // end namespace Svc diff --git a/Svc/ComQueue/ComQueue.fpp b/Svc/ComQueue/ComQueue.fpp new file mode 100644 index 0000000000..2c500a003e --- /dev/null +++ b/Svc/ComQueue/ComQueue.fpp @@ -0,0 +1,75 @@ +module Svc { + @ An enumeration of queue data types + enum QueueType { COM_QUEUE, BUFFER_QUEUE } + + @ Array of queue depths for Fw::Com types + array ComQueueDepth = [ComQueueComPorts] U32 + + @ Array of queue depths for Fw::Buffer types + array BuffQueueDepth = [ComQueueBufferPorts] U32 + + + @ Component used to queue buffer types + active component ComQueue { + + # ---------------------------------------------------------------------- + # General ports + # ---------------------------------------------------------------------- + + @ Fw::ComBuffer output port + output port comQueueSend: Fw.Com + + @ Fw::Buffer output port + output port buffQueueSend: Fw.BufferSend + + @ Port for receiving the status signal + async input port comStatusIn: Fw.SuccessCondition + + @ Port array for receiving Fw::ComBuffers + async input port comQueueIn: [ComQueueComPorts] Fw.Com + + @ Port array for receiving Fw::Buffers + async input port buffQueueIn: [ComQueueBufferPorts] Fw.BufferSend + + @ Port for scheduling telemetry output + async input port run: Svc.Sched + + # ---------------------------------------------------------------------- + # Special ports + # ---------------------------------------------------------------------- + + @ Port for emitting events + event port Log + + @ Port for emitting text events + text event port LogText + + @ Port for getting the time + time get port Time + + @ Port for emitting telemetry + telemetry port Tlm + + # ---------------------------------------------------------------------- + # Events + # ---------------------------------------------------------------------- + + @ Queue overflow event + event QueueOverflow( + queueType: QueueType @< The Queue data type + index: U32 @< index of overflowed queue + ) \ + severity warning high \ + format "The {} queue at index {} overflowed" + + # ---------------------------------------------------------------------- + # Telemetry + # ---------------------------------------------------------------------- + + @ Depth of queues of Fw::ComBuffer type + telemetry comQueueDepth: ComQueueDepth id 0 + + @ Depth of queues of Fw::Buffer type + telemetry buffQueueDepth: BuffQueueDepth id 1 + } +} diff --git a/Svc/ComQueue/ComQueue.hpp b/Svc/ComQueue/ComQueue.hpp new file mode 100644 index 0000000000..2888bd1e7e --- /dev/null +++ b/Svc/ComQueue/ComQueue.hpp @@ -0,0 +1,195 @@ +// ====================================================================== +// \title ComQueue.hpp +// \author vbai +// \brief hpp file for ComQueue component implementation class +// ====================================================================== + +#ifndef Svc_ComQueue_HPP +#define Svc_ComQueue_HPP + +#include +#include +#include +#include +#include "Fw/Types/MemAllocator.hpp" +#include "Os/Mutex.hpp" + +namespace Svc { + +// ---------------------------------------------------------------------- +// Types +// ---------------------------------------------------------------------- + +class ComQueue : public ComQueueComponentBase { + public: + //!< Count of Fw::Com input ports and thus Fw::Com queues + static const FwIndexType COM_PORT_COUNT = ComQueueComponentBase::NUM_COMQUEUEIN_INPUT_PORTS; + + //!< Count of Fw::Buffer input ports and thus Fw::Buffer queues + static const FwIndexType BUFFER_PORT_COUNT = ComQueueComponentBase::NUM_BUFFQUEUEIN_INPUT_PORTS; + + //!< Total count of input buffer ports and thus total queues + static const FwIndexType TOTAL_PORT_COUNT = COM_PORT_COUNT + BUFFER_PORT_COUNT; + + /** + * \brief configuration data for each queue + * + * Each queue must be configured to specify the depth of the queue and the priority of the queue. Depth must be a + * non-negative integer indicating the number of messages before overflow. A depth of 0 disables the given queue and + * any message sent to it will overflow. + * + * Priority is an integer between 0 (inclusive) and TOTAL_PORT_COUNT (exclusive). Queues with lower priority values + * will be serviced first. Priorities may be repeated and queues sharing priorities will be serviced in a balanced + * manner. + */ + struct QueueConfigurationEntry { + FwSizeType depth; //!< Depth of the queue [0, infinity) + FwIndexType priority; //!< Priority of the queue [0, TOTAL_PORT_COUNT) + }; + + /** + * \brief configuration table for each queue + * + * This table should be filled-out and passed to the configure method of this component. It represents the + * port-by-port configuration information for the associated queue. Each entry specifies the queue's depth and + * priority. + * + * Entries are specified in-order first addressing Fw::Com ports then Fw::Buffer ports. + */ + struct QueueConfigurationTable { + QueueConfigurationEntry entries[TOTAL_PORT_COUNT]; + /** + * \brief constructs a basic un-prioritized table with depth 0 + */ + QueueConfigurationTable(); + }; + + private: + // ---------------------------------------------------------------------- + // Internal data structures + // ---------------------------------------------------------------------- + + /** + * Storage for internal queue metadata. This is stored in the prioritized list and contains indices to the the + * un-prioritized queue objects. Depth and priority is copied from the configuration supplied by the configure + * method. Index and message size are calculated by the configuration call. + */ + struct QueueMetadata { + FwSizeType depth; //!< Depth of the queue in messages + FwIndexType priority; //!< Priority of the queue + FwIndexType index; //!< Index of this queue in the prioritized list + FwSizeType msgSize; //!< Message size of messages in this queue + }; + + /** + * State of the component. + */ + enum SendState { + READY, //!< Component is ready to send next priority message + WAITING //!< Component is waiting for status of the last sent message + }; + + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object ComQueue + //! + ComQueue(const char* const compName /*!< The component name */ + ); + + //! Initialize object ComQueue + //! + void init(const NATIVE_INT_TYPE queueDepth, /*!< The queue depth */ + const NATIVE_INT_TYPE instance = 0 /*!< The instance number */ + ); + + //! Destroy object ComQueue + //! + ~ComQueue(); + + //! Configure the queue depths, priorities, and memory allocation for the component + //! + //! Takes in the queue depth and priority per-port in order from Fw::Com through Fw::Buffer ports. Calculates the + //! queue metadata stored `m_prioritizedList` and then sorts that list by priority. + void configure(QueueConfigurationTable queueConfig, //!< Table of the configuration properties for the component + NATIVE_UINT_TYPE allocationId, //!< Identifier used when dealing with the Fw::MemAllocator + Fw::MemAllocator& allocator //!< Fw::MemAllocator used to acquire memory + ); + + //! Deallocate resources and cleanup ComQueue + //! + void cleanup(); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Receive and queue a Fw::Buffer + //! + void buffQueueIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& fwBuffer /*!< Buffer containing packet data*/); + + //! Receive and queue a Fw::ComBuffer + //! + void comQueueIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::ComBuffer& data, /*!< Buffer containing packet data*/ + U32 context /*!< Call context value; meaning chosen by user*/ + ); + + //! Handle the status of the last sent message + //! + void comStatusIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Success& condition /*!0qI40Z;Gf$liqs^C3K_<7Nqx1 z2uKMv5kjx`&75y$yywg}$NTd>&-~CQB#`87d#}CL+V5*61?kh!%g`f7j+~Zxcu(cX z5sKL(N66Mr9tY1DWIFgCIdYWQR7y(8TuNHX+QQlvZliBtBw=X%#7IS2@{WK2|B)js zp$2+-Di3e5eAPdvr}wp;jTLI^r1I+3TNOR8FCW@Jv@v~PYST-M*4Cc5cy{9B5pvGU zH15@3KAcSDSoCdc3~!=*uc8tV=Cj7g)S+;j1*Wg3*LI{hqE!wmzQn+!b)A*2P3OoH z+N1O*4XuwB^7~DXYRJD_&~nDPg4i)b+t@-)o%dDm22xckA}lZ%@5_d-0<9B$e{M zz}YK_Z=V>SeR9(KY}~bm4-@s_K0Y&NB-_%XeDr;&jvYHhyoipydhEHk=&_G=0?irs zjg$;7#=O0B@#M-;eoNUWB3B0sz|8R*smnZ-mp=jnk53*s>Ti0496UM-{#^$Dzyv3g z{r(KaZ1S<+ACs+-UOY}Ekb2~Z_z{_V5(wv`OBjl=x9bOoE5Rbe*EHB(UzhAj{ajQk zU^yZ;0++ov628&F%4(}%dQDcDB{co4O3LZb>#)~LGWQzmH`j&i4vh;c%VXT|{foQK zW5!SG1~+$f2G`@wUv}(oY+o4OcjCTGc9O~a$j|?0crV%H!BhQnpz|?Y@%G7>;8EB)WyOkp(B4W9n%pXR%crC9hXO3 z9Grs!{`f=itESMxaLZVmrI)`yxkN!0$7el${&tx8z5kq|)%+uehmYz!%=z#9FneSW z^%mX`|G+=j;*QU_)OfksiN3(v>0kb0qM7{3b(Wnf+GF`|`ad<+{NcUMem#BE*QGM0 z?auEL=Of9aRHg00ru8gI(&mOX*DaS9`1NN#;*WPa3lrz$2!D0-r#|A3cfLo<6ithH6Z-%5S1+Jv z+bI88u754-Kg;#U9t7L!pVRfjQTpd}{Sj!Gy#EP?Kc16+a@P+@@t@rF<2m^UYWxsF z|A87mo|Au&;SX5y!ucqkbAqHIpyt^0X^$HPCibGNHfTUz!e6EH8LmJ^N*n|M=D@T8?ra z^8v&CJl*DzpWUgxaPL4)NCcS-^MCh#HS+dHjh0mrQ>~2j3TlS-n<&Mjmqctui z$O7$Qv%vz(6O8VKJeDJUZ!WB(^EbdRjaE4Yn;0j{FK;hxG%~1)Ixn!)qy*g8(V1OU1 z9LQDUz&RucI-Hy}YM#cQuT5g~SPPYp=kNX!L~kw^d8=8_=Sv`+v51q{)o9#>NuD2K z&<`i@f8z892KGYB#YmBz9Rpgl+3makVoX*g#r134@Rd!oZ82d3lWKYDljNz?Z(th5 z>5tu(%N%hDPO+%@?z3M_kM1AykF%<3_S{=(dg!mhQ=_Kq(Z9`#M1`Mc5m_$nwdl>1 zS9s6C+YA^g14WlMeIHD<)9Btd(Q=_Lr=t_Bn4VU-^C6!v%5jIs*Ts`-?b;6~<3|Yk zukXIJLS~%kl6m?PmtpX;x$)ZS+SL{|x3+cLl;2+8mJ^?h67|^OkI3=ucogxm^pr`N zS^uMmJnBzcpeXd`*Ok@ zmWH~i+w3Y5gq&i1J+3`?TR5oeh4DPx-+Xa(wA|8ec5ox~nzUvdujRRNA{iLKnAhQc zCL=o2EYJz-QITNNNTG_>5$WBp(rX~gg2hFe4v4)~(p5@(q7$OW*N$I z?0vWB-uI8Cuvwb+CDS`}f4gaZT$XNf@CnQ0dV7*CZiLzjk%O(N4KNm=hMQ=m#2`eT z`W^GZf&};_MFZseKyLoy>H!7OZ9})UZfTF)NS9@4MluO9gD-E3PB1usu>1Ph31bAd zaM2>Vew<2ZiPP9+rYA#AE8qhA(n2n}T>sw(x$jzc_%qAiZEGnUWV3UzU|KZyU^$*ffM&P0)f ziG;z6Xi;{%-2p9YfrynFR0E1@nBHkjADq;>98Jd4K1(MpFjf6kj>`*|)@txoi}5p- zG@mHV{IA%)3cSqI^0YJ2GLVjM<4TK4dE%|gp5Z(VZu72WA6(JDzNE|p=AZqN3KT4c zeRUpgL`pi=@T@mThs6Q;UFzF4-zDQX^?f5);a}{ikOGT6838z6!Czj%lFfqa_g3Y4 zzJow_{B~!2=|?O*DmBXpu2p6hQR;%Jaws=w3QG4Bw3SZQEHg_y@oO}$S@Ng9juoZF zaPj93{;5+$t=JON-b@7+Gze?MqGi06BSYyjVQsm#i8s9_{b=*7v30|uROgo}$)sMM zTB+FzQxI&{C?Bvh5I6RN(kx+|uw@SdFW-1OQtMWcuUQ6538t-NRw}p9=zRW58__W3 z{9karKQOX?yvoD}0c^Apy^v!mNBv$8u`ok6!ZtFw{T>U4qxV#hPzS#L@L;GlU7FoI zcfsW@xeASXm3TWcFC!7fmQsp4rsa0wcN+{2!t8yY(t;l7o+~GiJ;{&fnN4X7Lq4;B>|7!C8eC~tP#7Yxm1xV)3 z7Tfg&R+uV{=65$dDvX_;!$L?=sjj!?dn09LhK%XSdo-`kv{!Ck5^~Jj2Y~~R57!}- zbczmC+Trp%vZJH!hgv6|ZENMThA{j7FVp=)%|VL6OD<&4>Gj3I&do-euhkR2l6a^g?!pqniYHq!8Cw@Xh zvlI$V>ICEz$bWL!$x6^um$*KahUe=F?XUI9_cz#9C3qcdmv4@{?J_)_{u)|tG0cTs zwh(91Nd}X$!V#9pHYZ>{ke7ad5RB!uG;>(!d*-OmI*ORKHMUUVL_6c-$)qLzoY=p6 zRLsHYb>O}`8)v-~rR!M)z>@|54f%*1702%lC*mZzc81N-wZ&dc!IuW|wTxS%IGlp= zp*BKJ_)>s1)B&E#2WQan!_gDYOA(a?9CcfbBvi((Rlb&hn5jRa*^jS92ZWZ;U^W0tLYtkIlPLYJ}PK3>^iTF(2q;jsUU5;YZ_5a@Ek~Iq)n&Y?NRo z%n3hI*1G-nipN^F54KFX!(UH_`o@=k+hBkFqj(~PJJ`XQZ_KT0R$h95B<+J!&U|!< z6pz;z`dc?ft?NG&Df7avr^3vj5$*@uxXg)2T{tJ953X2N(jnNYAhdk9UY~V6S8|}0 zquxTwpQ`M00PW~&=0ua;EJej=0}>W7>tk_S?^j#i-^B8g3o%~22dsW*X?yO}RIu2_X-=2G z;PqzB&0M^H47ai1)wH4VEoncQ(F$wpiZR;&)^yqd=sTZ+8(CMz6hK~2K7V=i{j)ST z_<*^ekJ!gy^M-rNJdu{=6> zDYvksn)T6Wz7}6Kh~Rl3=iu8-YX<~QGYAiD*R2UYwdiqOUl3@jT|nhNc`OqwL12~} zzWJ=%=cl5@wuBylsE)*TKCQ5u@=G9WojE--A75cH{A7P;-7eCzuMVXip#cA|u(OE% ztzsad!z7Ol4LugcCZ+7ha5Wp1dF-{qn~GL*&&-O0j0FfgA_r0V6BM7XC-emoM7aqnSEjqB!uTT2V*elFVOYc z@27sZW>yu2Y*%jRjyI{|Nc1{z$!Z*u=ffCsKW#gCcW^(yFzeRs+BKEl$`fV2ddb92 z(-RzNt+%V&a)nY9BW|zPvAmBPZS9`TYzAS(l!PPcUFT91Y}E7{)mapoRh5WeB=mTT51yl(Vd3 zIZOt57@Lo$d5v1Ajpq&h?)I9Z?6ZvoY4FNQG7>G1c>EShADMx2PA8Jq2ldsDK_wspEr_>n{YL`pq9+`A}Ru&up`$;}*Hy?krHuLgz zqwS6kh-5)_jI8&vX1+X+jhs=Pk%fe$l?&L-4v8IZca~zP&#Fc!Zfhg_aY+d z4yg-O*OmP!4dl^T@^Kg3V!qEElrVc={GbKCdZpsS=1xESuA88As^aT0Q4%*`Wn@!<{0a%0n(A2W)F9Qz0qy*f5PC} zSDOwCQ;zes*rDp)^sP&>Ma@Juqma4rXG>954@?O)#GsPvo5e=0sizb#5}TQmhQ3dJ zJin7#({&DuCpfT&=E{0#W@=+=Xrh=pvx854k%v+Kh4KuB0gR#Tzhw#yhqT-76BNMXKQ z*$6Tx{pI?@eYC@T&ka_S%o~zP&fh4ooKdLuoHx249f_Pt35kNmva(F|Q`_{OE2^qT z+=sDfXF(k_Z}MH3Q&y5iZXhP*k!z*l3jmQnIouhncaM_qFQUG_0IGKks8=7I(7*qQSfbzQJ%ljmjTRBWdN|cnPsB`*Oybx2AYW`*CuV8< ztsbSoaW^_#cWs}xzV$K0c&4toZz53fqS@_CF-^~hz`c`%ma#{ zt9d3uO89N0G;-*6L}pjID4_!57*|5>1lxTX*e-vbeN*IV+eKs3X`Ncv;c+*@vYRW4 zI(t_M$=VNqk|Fd204TVQ%{0l5odVT*-QF!kY#p~l+g3{kbacMchTU{=ki=f?*ok3a zF|ko^Ts*7(3#;+3gLIZT*+`s*Q^i~SDm!};>Wwri@xBrV6^u?1=^`Un57WM24k|t# zcJ^uz$UavIGtxX20$WJ9BB!_3J;g0KvIBYYBgU#~{$@2GMKBl{bXi*g>>aDgRDa|x zjc>O^7R&Bh#&8+McYV#%D0w6&j8cIEL{^*mYzF{BoG>gqdqx=?6|*LKCv8<5rT$HP z4N(DZ1cPkW#QM6S4ze`T!A+pdTdXmfQVV%UU8Yzsw-FyS+-v61thOGQnOCV4$NjZib?uTkBsOnK%MRa6ii1Gz9Z@_d*Z zw9b^(2$=`}x?QzcVAq)8IjI48`7yF3Pyn@)eUPWBbf<2fVQ{raIri4`FQArr^Q*z{ z{-3`C^$&kT1q#{T$vRMzqf#{LaPP*)IZGhWujKE|CMra%?~TL@*zNHOM8uYkEeFvH zo%>>v^AXTloGBc0eq_q1lNm~JYH|F}Qbl&=(sbf(iH>zAOB^GSI=J`hSp`T5QNOvp z*v9Mn$Qo*BJSg8w?&a!kDL059JBV714m)e}o>>#OQZASG<;UAq`_cD$Fn&qW1(9(| zH*;T@#r+a*P8$-#IbeU7U2HH^9CsPr@(L=pU6z&PIigyiJzp_A-+AV^U}%lwE9oBG zbWT=cF#x>~)!MgM<_&jH7$_k5AY+Y72D@7#vt_R%FQWl)$Ic62gLe}9JZ5P_L;xMM z3^40vf)tHxT4|hh-LN4Y7NLRkS9I4yU3OcbNL?64DpXU2@ezd= z?CSs#RxT5E6LNd=V%*^uI_tM0@~(YlrZHH!q6m*^T(wk6EnC6+M$B?ekgjaM2$Sqr zmRr|xiQMPWAA>GYx3zv+DdBFyW2)r|xeNyKa$UzU+(pldnvy57BKNNFm?11o>O9)e zRH$SWG(M+>@y;|K*1h*KpVblq`*uBJHCp%49!dgMBka0nf~)3Ps#?PkXzvE9+)->z zs^9t+Amd*-8*47fR#@eva$lj?iEx_^m40{op4^okWRl$FJtzN2%XO`ny&Q-Qz?3~@pI=CX%W-G+Qty2?7aaFK zdTfu^cs&;trVG!wTmRvW8zT}+%x%k@kZX-($5e0Cf!ebS#|x=k15x{c5?WxA1S%=l z<=8Y26!pbEUW=i#r2>i-tl^b5lZ`LzUKNko?opk%V&mNpxT`w0$?aW2ebRS9vAVCF zRGROQtty-Iz05NUE>)X?_H%lVs~y+(wYO^-w?BX4*g}062MBrDX@_E8^W7-N*hQ@l zA^j7Blzzz=d9Oqh3JfByE_lCA`gtApK8NF+X zI}q8sSOB=sp%Pr^(+r#6>0nIP>D|9KB zHvkO_Vc-fo@HruCkOmX}!dDx-b6cj2$E@$GQxvF)cC1=C=vJ$rqaKNV|8R`gdR*8X z)YmN*nin=f7A^->o%A?geRTS{Y^o}L_Ufhn0kkfmKcTj2X3JrC|^$WKO$3w14#b?ND4jVHve@a;}L{%Yx@UX;qE2(p$ zY%ICa@P0t1j`hQ<8UBo(L)*$MZD?EgTf@c|6h&DS!O%e?W^LPHqo`p}zr=7FFMVF< z&$Vpug_xc=d_uhEkq2^PUy9F^Va}%EV8LUVDe5-BBb%wz>qg{k`M4(8R&PTn3~-^e z`VB)x&lzYQ#tOUGHlAhI9Ra)`X>EKXFAX?_p_pLWk&Idrwo1w7Bc-Mt#V8Wg^Yd%@ zR*UOQvIaoUx1`NUDMV$L`g+)w`6*ZYCT1O|DdfvfJB5jFjhWOV=XvW1FOt2v8*1#! zhR^(6Q2!sk%;ywzDMzAqd9)%<&7t5ql_1M#m3~SM;5mkXJNBDPeDWKoM4|VBWsjBs z9X)gDNw1P$ZcqMKoFHPZ^$iW%%b?d>;zy}t7IYl=(4v8_&$UrfHdh8mydKoo|L`cr z=$rNwZVOaGBFCg9u2ygD!(9qyB%hRMw{=4F<649;Dqu&$cd`?nlmmI4yxHo4Nh8pr`uzB zxa$ks01c9=5Vrj6a{$g#_#Tqz3#$V1#+}i@=mm05nu90AzHH@d8+Ua@Tp>Yg+ax8g zPOvjxG{zU-1=NsTpfkkJ6r7;CGN%FQw#>E}C)NAUPn>bIw$-7vKi?T3n?_6v7F}I$ zdz~@)95$O#chT)KZQJc1=-lHMO+h}E@SJ%Pf7_lm-GwAq&f&j$uR@ zyaAAM-k>lbD@#Bio;E)YS^xIY6_SyfsLOwwuVz28sGpAhFd-UG$5?8Ss`lz8W@>tK z|6nE9YX}HOIJa2hY&#JXd7ciDW3h?H_`rdz+3hn*G@II4Uksz#2aMSDb()Q!#_8nF zrm;%9<ZD}-HRP%)An)KN`k>0$p8d8bNey&D%b=twuz)jeZyzD( zPNAZ4ZWEI4B^uI_NyP3hpycuaJtgsxtDODT$!wG+$eH3_f})yV*F;WWfKUxcVa0N0 zjJ02Tifjao_u035Bmf_8mL;*-2C(BqWo2QEvyR~lg?ce~X)bEsNHCffaR+Vkf@pN| zzlHv#qhu$5PR?Kxq5Uh_JSF-5s>r^EoueYVzGm8k)45s|1!bnaU+|SUhB&b0I~eYM z9^Q}CcwFQB>)q{efHbn7`VuH(usU)b zFksnIa>(7XWFxEnjb;Tg8e(x;Q{7+fsUM!B{*|O;j{=|_&lW4@RmTGY=Gn*eQNH3E z5R!I6;z3Kql&LzBL*gXq0q4x?k*O#!Lv7xj>PJe&V2&f6ODlMp)q9U@V!f(KZN*tZXX;<&)`dZFMhJ4+=dWK+wy!lYTY&+3Ga#qB_eVFgaf*|1x4Q4 z1;<~31{gpH0r`8^itQ~O;7VyOw$X{Yzb6&n0-p0F#+~KKM(-B;bB*=o2(w!<$FGP_ zvY~lB_na32z@lNVGQO1l*r<7R8Lncqt5upBzQWOBqwBy2UZ4>Ld z?aaqs`|AUMh<4Ya?+mB{I70`cpj+>`f6GKe5=$?_%TjvR2|xCN9d+{}wWKOd#ZqYm zo7xWEbL?5uHfhWV3>(XL(h-dluzMP$yHlwDku3OGJI^4wRp(;h>C1P&3qz36@pnz% z;mYj=*N4pkK9)}u7D&L@xhH`N>db7jNUz)-^KD#m=1dZX9W6hG3sXZsCmSU3pO&NL z?1Kt{K%i5$WBM8Rs&by?t%PueI0=nE)}?EVs5PAVB}(oDWFICleb>R%3M@)uiZG*SiGdO~yo z3$H#LAU+Z{1wd@#u1>@Q;>h*yFYKPBkqvrU0xsMKd(?9mvJSt)@zCG$ziijvw(#_M zACarCaG3+|0%uyIoScknJ-@wXUIN&;-8Eq$47e%AO5dV10elQ|6q`>Ed$;q19u-Yn zdd1Qr9-F3{J@0*tst^SK-DOpiUDCOxTvg=}s?`+a~Q~qifmr=`>Wl&!| zke?q;-DP3vn&OjD%D9g~Uy}}68|6_s1c@~tsN9(u=?+Ocw#_#}Hv$;LdyfmMdfL1~ z$8Lgjuj$BU@r4dhBwPnZJw%cYy*_gyEIq8{ITbRHU9BLV5SrwY_T1&p6w zdE;j^Ii_P|Zcom3wr6G-0#bYt-{G1c(g}<{OXPmVg4aa1@zsPSQu!-(xYxTdkiU3q zeQ|u9WOF!oL-u`j!XT9SG^6O4omP0qCGMxrREq=oamHQ>4zmv+CE2*!o!~&bQDH0X zvPhPk%%(>b+eDm}60!t{CR%{S`IVm6WP1vbWe;MnVI%-wV;7mbF?#rt&Z-cs#;zsR zlG=R<$V%kx#|v+(_cuo6vC2B^9H;F?w;Lp|tSj=^8>rQo*Ca2;u0mRdCdtK7Dk2tr zJpsXBKbJ@nEj)sSjXUDs9`|0yz0kcDjboPjsY8D00@EwpX_V2^=dm#5#}55Sk_jPM zpJMa^yQU!k!p)j*h`NV6QN~9Ukqx&&@Ot4frJG(|vj7IX462dWNi8k~H#pJN_^R}S z_$8%@mfV^9dWtEjzg&9|ty{PVfI_J>qetJOeJ>u)2~T0I-^C?Arz!^aD(OVssr?b~ z;&cUTiZ1RPqLPhe!U2eO%xyG>lDi4c-(F`bnZcHW#SUyF^MHU@UJ}Rxn zGE*ky{#iI77-sm?iPf+@4U}~?hi>0i>QN?hgR3K-2sJ&+*fMi9&1y%&xQI4tN`Ski`C|W z@N|e&O;v&@M4-ZQbhi32T{$og{Kl;omlU}Tn*WLn0fx3WgEzAXpg6nhkqNA5i$XU& zpW~k)F9LM8SzLvD+(qC{k#Mn0wgZ^KiBl1m-ZgJofyvA=<@0+3;HN?7K9D5M0K>B} zmf2Cm`#K?7_ac9}$bvyvPp^bsJa7#Rq~52*US)Lu?gP@ZN8Kof?xsS#$&R*58A@w@cb+A1RAD4~?tLeCW1`e}#{WwpR zECqTxew$?L8$!sGo-w1=NC(2gt}B3`GNaTNDgj~tZl_kz^I+Q;ZIz|ix{EIx)FF+Y zRR7>@b#fckVDf}^FbA`h0lM|LiFzR#9TXzxo#{N%$y+())9uGq`~(f9lg-w6^?J{y z)EU!#-w46FatP8Zpq=JWy+B(a7Z4plFZs1@)TO{}4e0fyeB;g^OJEZKX(z~91B{?B z!dGVil2P4enr{Md#huPG$$Ar5wb82})Lzu*qznumB~&Ti8DuUfg=|g@_jOK8TGV4l zjRAEuGilXZ%uk^85<3=wMsL>`qXt>)FDIxg^%)@%425%Of z4>+U>TA%MGRDEmuB&J*PRDQ2D52qaY_JH7ZXihREJifdOB+$DqY}c368sH}o-*0Ej zrjX@BRTk9os?!9H5)58J=i0=L?-()389dS2uO7 zbzhF7wvS{ttJnXXs27j-K1h3bXdLM4;%1hsogXP8{4_ISEO#wY_JhNJXfEQnDJ|4% zdtA$`XRjdpBXj^<(H4DPBQ(Y{s2x@oo&-|?(3O**@bcQVkTa0AY6VEmH#&(L=fEW~ zFM!D1KR%pqE8tA@Rbx)DS4qbJ*-sYE)RJq;+DEJ7++Yq@N%}$x@)Y|tY^wH=StOU= z`JH{8>;)1C66Ryu>(3hoLduN5hklJ}N6XH$!*#oObLbJE;5U}}Z?*z2&^X_xOd}1N zOt~_7z%FzM5rm1k<5}M7hX?!ea!0ayM7O8U<3zsa7G~>V=DO2JVv&N;NL~@N#`LvO z{Xmt2c@`{jR!v=YG7(q~NhtZ&g?<6R5hv{V>Ds6umkQp0gEEsl_bE%?c;Uw5@0+L` z)qxBld4Do@m3$u6M(N1yCIU`t0~qNbvtmyM;|Grm2G`gtZQaT4NyYm}JU4T=HKy+1SD|Ow z_6lT^C49{35&cSs`vfmzdhFtB(KKip>Wz`RGtx&NQceJ+4^CZY_sdRrl;B#IR6-{z zk&Qb014lzm^x5DuHSb5HmS;n__~D(rL(Z|@QK>Ys(#sAD zg!xn2|Ct`A-+`9fhM>C*HQH5^{EvLjDbb`Ur#%p$8OeSXWoMlLlg#NsIL0;p0@$uc zD&n_IbdYv}xOhAFV`@;`ywkWue*`G!jX>#N#}zKA3_^h8oNaB9U9U}Lx~PySJZz_>o)w8lbm)Nqmnem# zQSQ&TPh8O;M>lZMaq4*!ML(0-;GaQv=NaG+*)bb{wh)wKV^a%NfIqYXF5#Pe$O1}p z*ZTFkrV21sLdYs#6x)~JGj0X2B-jvj8JD3aXBW>*#&gk808y(s@*|H8IK@iVOSB%E z3Cxfj#GBk`RAQB`Szq>~Ti(`b7t>UNphx0zP#xESNac`Y7pPhAhjKA@C_0~dopgD}UHodZQZK&yB7 zk6Q;$GckJ<%}J%(m&(q;#%OmbKLVB~u1Bz4qDfzC@1;2H;Ap%oRWikaYI{{@ObL?O+h1gq`=&>>EDRt$1LNICz!mja~yJi<( zEg!L^Vu?!4n23o~U8npww^@st%bZAq(q-F5kDIf{ZG*%s&_9Qe??SUqWa(wV42)9e z-QCs~B32PlSrjZ`TsoisB6V8;jZ77=!U{i6fc5|rsH#Mpg3xTVLHvvpa9btz+}&;v zXO35+f_8Pp@o~J1i5yp5SHM(P(IS-<2(<^=%6`)InY;IsX0rQv4T#fzuj>{O0z|-5 zze;$}lP38RrRwtO7wPMkaR0h$M3E+z*;8)VEPmEyxol9fUW>+Fm0xkP$zBW4NC^{# zlK!6ZNk|9_EreA(3+E|6!}Pp-cRB0a94Ja^uupe> z`Fc(%=Ns5L!_-v$!3UhHyR_#tgj|HXqbdi~#Q>$Bppvqqc8g?}PfkAh=>&0O+6aDf zmL^;%lKAh}8zkGDJll3HT8$rXSU~3E%fSg~pRDLdsQPPtW>!$$`==YXW%hAmhtDE8 z*R-CLf#a_r4nIoAZkl8E4B!>HXoahy2?3tEm-d#w6glq^?z{C!xp0aZp2@*z1;Tq>0q$=)Yl7 zR;&q#&v-I%%@(fn@^Z4UWaoaQng;OVa^1<`_UAf}dI2be!iRRS?6eilS+4T%EHzHW zh<-$+@=-~@;>O5D#Ak{2TsP+a%u1Sj$cTn5BjL1;Fx^x3buN?1M$u)$MX|Ta+?P8N zgc24UUE6?)tN;;#uk zx{olj9@FDgE6NRhu*=?>4~XRS{^B9cR9>@QcW4qSHU)L0>bZ+%re+cn*@v9#*%ze= zbY=RoEI_vNQHL*0ZLR8l||GT@Me&<8A?iUFSg1-q|Cd8?YhKQsG% zEUnQ~ho61q!_1C}#Q+<81{S&C6b=wonhR38kI-IrDlhV0zkxf8;(aMZku?x|Q&NQK z%>e`2QCzJl{{^iX|D`f6vfO<>BPxEuyvR~8v(Y8z#cC;QJXxrT?zO;Wkeo+2lX5bte4lS#+9SSSwzAYj4wTFzCPA(c$z zuMqcd$-i=p zdJ3bFC5bE0;v+P~1A?wG{0^E4`#E0d-|GN~qW2pYL>rs46T9)-4~bWkna18;;*S6B zk3!}2XDffyxS&!mMpATwB=!z=2_3ejnx2SBnBN_s?<|sct_j(*%b@JKU0BwBDg9&- zlwf!@LA_P61woML%k<>{YE-bG@UJbiY*-n24$dhn@cP&xmANaA-$e&8 z)7LunX1Y3ngvt5v&Q}FEc=on$J^q9_bsPTUAOp-lj7H6l_jJ8F=TNLjds9+C(CZV-d8 zRaulY&I)7{8z-44M@voNj+xCw56V`DX-K+cx&(WjwnZ0z`G4u`0mxwfBsH7rTO}Pq z8`GuUVk0@@%JIS(W&?OFpHf2v@g`iM9#nC)kIW+duo zD7bC8WI#@mEW>O-o=ZPZCt#cY*kvZ7V-*$ZsCO1jd5Au^Ddy5~_UvBv$5nkKn~=+n z=AtkrvvlXxFW1@IX;0Oy%QSg=iudzZ#Xl_z28oo)l;d zM`L+)6Y=u@rcVBeiI}`7N#Zt1{$Nup&`v+^0m57!z)>Vw{r=@n5{JqZ2JXG#%F*z~ z0XZ*{Fr2$*yQounsA=jisA1(OYYDj{4pUbMNwti($jr}d<)O!jqdY_&bPuVt=mM zu1*6m__o89Mx)9cAOAqN!B0l(Yu>ad5mLW3f zE6-lE#|!kP798OR?kV%0^w)v(Lgjk8{KjDSLu5hAhmUKuE#7cS$_}44cP4Ww(g6e1 zhdeu6hXy=L^9}((#xme{`PKZ;cPAa}5Q%kM&3{q4NFq4YU%b|JeF=o{GHC{vPqI0OoScr6O4=mm#Zv*N!k(N-Nh27FRJ7U1ff)|-0z!ydq3To;x4#zj$NJ)E$SO;>8= zmX~p^t(P$f@IaA(KeR5wP)-|wWgvUqDf1r{^1q#C@FTUL&$rJ3qhRw`5pkUrUI)Y^ z(3BF|W$q66B2tTtt?kJ)>ELp#*P)0#<8PM|%>y7MC!K#54+o7aA95FZvx0%<%VzUv z=s`qCJ}|y=-&#;9uRqwyO#qI~4M6+6kWWHa(1LwB_%;5@zen_c+YI2x4-Bj}pjToP z%&R4k`O1Ln@pDT!>-hyv&;dx|*(`x>RL0%G|B+;?-u)K9L1KMQVxma*7>QH+d{aK2 z!S#UE&@bC_dxnhsI4;ZSgFoIfj?v-{+phac~fTVoz zJ3ur;<|?PXq__ESG!!T6kX#oJ*tXyLFEB{f#lP#nK!_-GRE7*Cw8~MdtMex^4$%Z{c{tSi34|9!FqT>(Cup7(`nGTCfI$pd2Rco4EgO_ojv(o#6yz zf$8pG{ecllV3z!1x(~IYZR~Z$Bws-LOy# zDR3dq^4d&@1GA$>Bkv}q-wuFI%5IDK6>a9ML!h!8y$zI_#qKnJddDGsJm#1#qw|E1 z!mEe+ck46tNCNXRV8u%4tZVM5P^fQeZ;sgo&ok$>CkPEv%(y%@-m3$p&-?R<0fb(= z+CdN~9h{hJ2X-@x%YWnLX7TSq=|gFDP5Ku>V z{Z!<_StiE~0noG~3svsj2b=0y`Vpf&AL_>H`OG+r)#>IHj7%pe(yRdYQpIE1^C=M+ zezWd=2jqL$mzn$ib)BH0*#M@Imt6E)o5rm*kKPJvUE@4oe>_lE1xP9d=2;WHDrnx@ zeEKu?La0o%5y*kK_glZlMt9W2^E09*(8BZ)YEhLBi$I~ZK|Q-atgD;X zDY~0S>;)XM+gyr2sS7=**nHrkUo45Nez8I=+CyubS1IMA8Kr%+oKUxWoA>&>GLaOZ zg9K(TGEesceKq|KsZB!!6o3jDm0)hKTLwF1L$MPL&l8SB`Fexk>}UZ`Zz6S5B)YFQ ze<<3Kl4)Q={sO-UmneHwLF!2aiN*-kLpxAEycUX<+lrbd|+|xLh z56!{4u`wny=`J~a0z!EJ)(=MtkFsQ@Cy3!UMHll*Zq>C!pz3p;jFLQgx3qGg=FkKW z5O_CQ*wBU^&*o3jJcOTobVG{gW`tf)B)oR5M=s1)3;H_2u0vqp{WAk&Q4bfCS*+w8 z{08V_5WFGnPyj7~u%mN1bdc5X7`WdmbsL2lbXprYky08Gwgl`?A)mmz6ln-gd*lQFV@@BD>s6H zyJ*C~O#10v&>zW4W(pxvXTo`SAz(siu%JEoDd?9Bb`S`5^#D9T%)t1-yC8fyXc{NA zPsXF&L+o0TDm9ICi#IV7@6AB>&dZ7wBqM z6I?&FU?10)l@#H?-aXXBoD~!^&(L$n9{ZUOqlntd-tEYp`Q#7|^s$^re4yC}SGz7~ z6)x%rTX#Y7GyyTrpWysYgaL4!x_JGW zZD5z_E+YbfpnSk%v+hz=YqQI&*o{r&jU&Eyz3Qy z8@+)w=!tPK8w%M=BqfzZ@Jf8_PLmc&Y0UE}UI|%7s5sC)f_Y`if+JmL; zBndMpA=j6X*i%qBdpWDPs9>`}nLBS*!heZ1s>9(wF2fXO_+252Y%&hr^dBUAt~t2s zIi7UM7?h8{?-TI@+V8j7X6?pNoc%=xO)r!ZC0R8!d0E1<<`MVh8u;sHX(Hb+=61<} z96wbZkAp7w`K{hnYF$FX63HBOEP)2sajph+mljLCGg59Dm%|koSrpG_od|A75%7H2 zNL2r>6hT&|4Ummgf6ybyQC;3f7Z))QIZTbz?~7ZOQL-Rl)U@A)-9vZW^(^)y@WrCI=2Fj+Q! z16*n%wE41Htbb5Bh*2zS{P0mJ5R}EVdQC2wIejPvWoe4tf@_lN0xQn#Dlb0=YSwg~ zB;AiyIz7ja0^5S-t?*2F)s(o8{>^g-+MR27 zyFnZjxRp$x_0Y|IvjhYg{U{yRoRYp>Qi~#~B^BP>OJCD534h}H7aX3C`)#Ev3l}!k zntP&Rt??ov`=YX+*?`mP&y@*D1bt=}H0r$^#WYHpTe&TF6d27uguN%thjUd!l^pR@g=F_Jf8H zV}Tan0{wJG#<^e-0p#EQRddu(nvot70vLAcY!?zTt-qQ%kr?^44`kLW??>0>dohnw z&^%d^aMbsV1&E(aEZ56He&E%~6JKR5dCkEj)VdW>2$HxD>Q_kwTk9#~yvM!R=saa;Cp zVg>!*PrsA16=BN4YRw(;p@G`1pmWpihe)ZE4f*v15wT6WONQbi3YrCVRURc}8dB3S zF~DY1)StmMyP9pW3^mH~eZ~s<6#=Zm82T+ungZ%qM9Pz-{^Fbqw0Et$D$Opb`;C;A znyXiX%E9Bgi(nmUfs|}4E@x>@(x_=qUTPyk7yT5r>W@Nc=f$el7~O&B@}??|8xQKt zyMAOej{G3L!bkWb8gj@-d{r$6RLb@9ft5E=iqwxYoFr=u8w_o!5fC96H{=ChG#Wz_ zADHgceDZYxozua^azR1L5DB1>OV(-%a<$av5$>@I(dQP@dNm^20tP1p$hM_HKhl8< z2mks1+{H{{6nD*rN7lk{Bk=otUZ9w$KZ!(6e92QP;MA7yuAz{tEEes zvPvUE-;9*n=SG^Yn?WO8c#y3D?28NI1vglFO$W8@0tr@vI!Zjk%jy}jG}!$lfNCG6 z2+Jq8Xn4}JQsZBrYY9krxHvF=sGn`*ydGxNdoDq#5k8md6FUmR%9X_+lM z1mTQuiw`%RX`}=CZkO;uYgM4=t82I<&uP-dM2RX;EjDa^*z}rf4wN4oS0c@nfWt;J zk(f;cBoz^J!RUG9O^*qm6Bgq&E*i0=5;=0x8X#?6!>?ztvR*|+_$FXi8>L{54|z6-IA#f$ z9>@Q~-g^g9-S_|FWi*b4GD;{7gzU0ONhveOu}M-^_9p5m4N0yfBeTq7h2z+>q$DHz z*oi~-ij4f8ukLGf-`9O#_4)n%{pY^iq0W1}Ua#l#@qCOYY9;W}jwL>|%@)4&+Fkpm zb4;1>B;vn!7KF-*$2Ww3c8M2q3ET!S>2H)3C?D*3<#=^j868{d1WV=~T}r;3L8m;s zY{*AcQdkF*HhQ|xDbJ3aDDhqMaislmJO68A|KTfnwN1CUMoD(PwxZ^BDpIbG6OISF zI=U?Kv$C*~F27@5hK|uxkYVrY6MvQ6j8i9-tCnaxh@GH8r~Xpcl?cj^D`q0JMJqB) z9B<5!0#mi6LDT4*Zpa{9ckr~mF>hO<5Cx}WbQwuka!$>F*qLGXlveUpfSA-2ku1$? zFYgiep#tpw5gC}4UduEC{xle&m`hLO4_pOsp>#m&xARO#Z^}I^m8LXp^*J$c&9g9) z8SxEZXAoQ8!TwY9_3$mKxC$BC0bp=NIFEqe$l1^DoU6w=a=b(HYHeeYnS0`8P$mXO z0Rl90h47X3DPu;hb1Klgwz5k#Zx-_8H~;KbtSh0;)FRU8NchkN6NGWl?ui%~K(l`J z)!iLW7y^ZFMivIPuSm|j15q6DCw54blqv+ue$mBl5~-OX;e)e~ef!~cR3}c9fZn)0 z-(lb?h!Sc0&Pgc#eRKOy5EbuCd-A3S(t%LA3U<^YppBB%l7cbluz{XnHp&$Kx3p8F zAPyK1;gJGu6st~BI<#{-iB^v1UtY#gx`9=~BH5N)9pEYC_XeReP1yvXuxBBrOb2d# ziHg>}Iq8Qg7w+^rI6k`$EnXr4l+b9W=l4$K^*j+X{=%aj9cYY4@r$w1rJ^_o5;(2^ zN!jUOvQ9&fYTd4%K8m|s^m}TtcWeGl;~}!cOtVF%3?7eEnJUY;;BbY^#m53hWX7Xm zQZ57}z8E{KOzs;m95<4Zu4w$4^R~S(onQ5I-yKGBN|pkUZGf+7VZH zg#3Z!@x4(cN`83z8GIGuc0JR&4&1IJSwJ;gUtCm3`e@1(SkDHlME(TBBCtNk0StHn z4CBhLv%#^(C%iUFUij&Q;V|SN8a}-sp>`r6(iYjcOzualwO*U^;)t1Cs^G*2k_jqW z`ciH?Uun)3#JH<%lS0qm2tC3>|gG1ku`_af)#2`EQ=i&>21FAxgqXfkc(g5 zt*w%C2a4K$Q%GX+AS344<|}|3uMrQ&u={CdK=tp=4~B-&hOj`p)p#vypEs%`P1F5JX(Oh@Ns&tW-5$J z>Kuw<6NH_l!gLB82ieL>SM1l(9syOykk*5D&0ik_i)_R8y;tG=-WsXdvK#p7yCt}| z#R%E$YnLYF$`g`5kO9v3VrMu**Q(f_FIy{my zx2pAt78jL61ymO_jP+$Mole(-o0{YpP2vSwqq9mL^hw*ebrWx}@cZDYXfYC<0@c^K z%;7b@!rZX-4Oe>2qiMkkytPDT(;e-8dRx{}2~eHq8}guShVAx}*O#%Z1B(9nN1jFs zl$ofDfI(r!@iJ>}%7{ocFCFud7ib|Bu-GU*O*`j6h!h75xagxl-?e>O>(%`}?XjTA<=XZ3?7cR1f>p--1-qsY|<#g-z!7niPi& zAuK=Xv&Lcsl%+8qxZ7J|o-$WY%bn5hQg~)f_!#$X+e0?Vj|I1=E&(#1i&PD2QX_}z zJ@zy(=X)(o%tyWCfCfK^iS}e(V#!$cyGZ&OIPFwAQ%9Gx%0GK(TB}yloq?=`0CuSSx9haGV%*cui zt4LPe4j>GQuInDq2Y|YOX5R?l;+sm4MReyMu|E46Xr}R~sbJ@pxaL@Xb(t%s%q?lKu%s8ysxdZH0lU*v?D!fRj5#q6^?i z-9-QD9q%OL!q4MJ;vdL2n?#ci@PnNPrR9Rp*UL@Jara1mbi4F>OTD9-fYA8m?q#@M zhQ?jP8VLer;}+Dj#XerRS}ZOT2_T}Lj4vsq4gpi;j2bP`OxEn%%2)4D0?Y#8>Gi?k z$lpp&hU&&BwQ#U5suPT@hTX!C?z>NsG%W}RHBFVs`|#j2jXt2Qm=-3MD$6bQQ5TJ7 z6vSW21$@7t91L7g+T@l6zd!ocAE1FBDoFUQS-|%TdIa{gA(U<&8fPdvI)Tk6 zOL5=20z*<)WSj&t*)$mV!9(hILfSbfeCQ@!16|(34;BSheHg)or-D^RR%G;J$*c|U z9ytm>R5aU1Hp{TO`_=+j9}9*s3KP*z(d4Y3wxG_2?(qU>r}NvGOE6U)v`1g=3gn(* z_Q~jVkg4CHTWxorl5UWLk>{UCm@Rp5+{!KI$ z&2%R3#BGFDkWMz>>pTc@#({I>AC{SJUTP1xBN2141MGlh+A#Yx669=djuYbU zPF3D1(ndKb>W+j4gfZ-`ZMp>tmv-omcL|F}Z}StR0Py7LPYQx5X3?mwyE%w2D~o)q zec}pX0<@9xwFBAI4lxC7IWmQ;g#e_czQf~Ft>4ejQokeL9?VIp1P}V~rFnv4^X|8X zZ5@W5BMDGMzG;|X%%r{^!y_fTZ7#35?E3YG=NBdbwCHx>AiJsd#e+0&gK^=vK(Pr| zO=3O1Q_|KO_DlQGM3CQS2dz6%d}Qv5L+Ve@T6r$UyF6h@%X@)eY%U=%We9bwBb6IG z<6Ia+_iFLmz?qY1bBbwBvpfU#DYYBi8b<1!;h>(rlZeqb9)FBg%YxIh+q%7j3f4XPa3azZ_+llk3S_rP*dMjp*qu;uKQP?Y@N3O&sCSh2T3fhB|E^fn&adR4r7|l>_5HR>!?!b->{ArAi4%a;C<5j z)Jl28ahPSWvGJQ`G~op*4lzZ|8j#W`?u$2c{7%gC^#R$TbP8+uP~qmqeg>$Y7$l>P4cJObZmZwI=F_hG^>^+xd<_r3tD z=%=I$-ZO8xRq?X9^7QAd7ms;oz!_wRoFaHO5oQ@pkisbP*lJx%J2Yrl$$@&5lmqd# zsBUIV;vA4XxeLfefyn!r$hYVT0{hlPRn{b4V?cf)d4qt05Mh&n3aujVmj#4MHyDj|5G|Wbm%7x#ML6Bd@VhXKuRl2RcgI{nwwo$3 z_uV6&-mKFpBhc@4>vA|BiY<2n;a$e8mY>E6oidK>(RdZUA=-Hz}9y4a#eSJ)iw1!okFw94W zi`0f=dtx?h-E+$|!5uwj1nZc^E4ln$MrNxY+X3!x3Z66 z>BoSIu+8>Ns=ePy3q0m7CT3*zHzg2^hkC<=R82yozsy244(q4Xt#1``&{>ssJyV@> z{76aIF>7s=7G5S-Es05R;eRlq=@?o@6$j!}e~B|V5kNC-mQ-lVO zD40*n8uhEt9?w<0=IlJ&$Tj5Ou{;((x!uCbjh6uzRB@|EaWChi4NI8cQh}@66gKiCJ1p z2daYfo%>UZKfD2EviN+yA=I^5?ijs^2CaPOgc=#LrT4Kiucx0;E0=CE-3dzZFDgaxMVdc2a-R# zA~$N@8B4l;cT!A?DU^baJxSm=^4{3J-|v=!hrV*ZoDDv;AxZ}htVoo4pth-r|8deR z(!y8EUp$(bSaY4+sxbk4mb1dDCj@W-S}%BuU4|Pf;IN!zscBk)=iNufkV=5wqsDo1 z^?}E+_t?c5crWaIP4F7gLmN-JArB2drBI*&Ywgo=$6kC>p5I3PTn3oN7`PDI_rx^R z->YvyS21lE~UusTJL%GI6^2Q@BJsl``=n&{1|7DeO0mj2HO5Bb&(^t z3;|Oc-eUbu6PKiUxsbSGH*+}udHP{^XGdusGIBMM(lKQg%LcS0XTielxb;|CLH%>< zZH^QCUGeGO-IcmzPpymcHV;zIT_JECw#JR|L3x)V6+x0szfe|+FgsvG1n0lJ#xq&7 zs?=WzW-}6Pa$r;tnSL*~B&G6Zmi8xXf+Xz*>itAy&cVy@`AkfQg$-=sYVyh_MEz>C zq8j-OhjO){F>$uR4PZ^2KwYQCS%paVxc)g6vX3raD=%@mVLAD;+qAZAaLl)FTKh#B z=G=hbD#a~P0xDZ;XYgh-OAxjFxG(ka#ujUs(7u8NtS8$*>&x(zxy0_oB^pq z2c_iG*}v|qV}|?(Uytwy8v8kMcd;#Ee?lrjxbLL$+hx&I!fSw)#N`v~u|73Lh`?vqc^`3>_ z3Z*&q3({@IMhHB;ovL$=P*r49S@BUjbI+i9)g0=w_0*Ual(+%v+nGqc)kDM zFZ{=sMqV2&p_bkg6Z?L@4cWQ!P=u!;(lE%4ufODw zk;zclcAK{WXI&u>CO(thredD&I!3JkEZ)y1HQrT*}p!`2@z zGdn>(#ZMk9_;a)P^9BCoj$ie1?HH%%)K4R4k{l?-2i-TW1Nd*?dzcfV?t_%E19W~@ z`z!re+(g4yYS2guVHi-BM8yE(&;W=C=_ma#U>NHGsAdY{+k<+Dbv8J@Dxy)qXR7bS zGANC&!j4)I15h+@=D(%^^i{D>whbIj_t;3j-k~JEe%0IqZlv(|ja-*e?amzYhbUsA zZcPA(81V>A#cj}_#(1pl85T^uLXRp5<5<1!%0BGvLSw=1|TGgXBj@W2dsG^|H=nN z0I>p*onfb=Y=2plWmaNaZgUyr7eEuFIVF4CzVAlwT%RrwGt&VusZ)n%!2kSP&f~tV z(+8?Ivq?F>0aoYGiYkx9n2yBFDG z?hHXD7Kg(3OcrdSio;1g%mC`c6(+g)j8-0q_q^yS@k+|Sj3aA?oySqS$S~V z@E}3xga+Xvj9eaA9>cv{2Bu(S44Mq#KOp#ejy>7_LM*aD#D}h^U0QD=QiP15V7NLf z3PK>5cdVAhJ|{%oJL>CkFWKS0M5+I|2w-0fq;I%xPq2C8c#f|7#Qr21(Ru*AS-4+# zE!bk2Qsi;P0Y$-SZtxEKbU;_fP&^HD$qt|l+>9fFsZZF+r%gIMOt+igGbI%>|2W7DQ)s!+}#_$DF ztMp*>_cF;LK%PL$IOI7LZjQ1H#7n+d!Co`NhP310g6L4EzW5c|r8Dlksx1#8>I!sm zIx4A@_fK_S3Am}GivD86i_$ZBFau2oN-E-GqtK5*0GIEjn)fCQ)kQr$@Hpw58nmF> zp+5Ws7)3NHI-@t~A0#GJMZ}Gc=2C?bY6z zfgBR#r(&sW>&?6{**mFq3x4wjauE~uu0Ag;*fANl;E9<8Zdy%7>5^3uWYMH+#GQ-| zW=IE(VSVu9Upugr_}1e%U;vXj1}I(*ctpM3Y@MRX^Zr5~Q0SF~;{fr6WxUGhEtL=1 z6p`g;UzJ~%2DMexGim7M4tI+}r)|6>CsuAHFzf{t|nyg-{w{cGl51UouasD$m4_14{!HB z9Bko6v9PvtL3g*SL(OM?1y_-XPVKQXfo$Kiz!(k9iay=gQ^vrg zF<%6rR`;>t4#+Su_cEZJUeO2a`n!A$&QM7ld-qUwNcz)rOLI{kL*W41sW?=e{#SlrUM46wwS1+zyMAWa|3s^ z4T-w?X)L;i`=7&(8m`l>6juzr0rJeJN_w?g1oAxOkKt*nkiu&Y1Z;mVBQ<#rE%}zc z;x=SP@?f#{R7>hkvsa(iT$25x2|1SUMyB9KiY)`mQduOa#*KFztSKove02ScsE{YaSi4SsY(nn*}lfKz9QH&nivA5R73@$oybx-#APLq6*dT#o&ON&u zrQpbGmGzuUMnwU$pmEyEyJ&D?PDeJoHA8h@9C+;CB{mmd+1dOn%u_d+!EH~DZ_Maf=L1t0@PH$GO2Kwt z?R4bHdR#4R6U&+^^8}G_)14bfc%c$EDk#|fYt2HC4;3&Dl$NSKn7#)k5*g-PgC3a( zWkt3iPBO=+F=rtb@l`Re;6!g(FS6QcHuQCJibdOuY>X$o%+Z&!wsm<>qL>T)c$sER zLzK%rXl6guNAUf8;`e?1jPSmIS|k2~Ab%?x%xusk0ysMh6E<)XFR-bP-+*v0h(d{e zw*_V-#A7^L@w&7p6`cAhAe4W-ZJ!)l4||&faMaV`cPgBc!*<2LIVuP-mJxZrtiNKY z2i?OXz8By<^+{l{x8+euB9#YBx)zGnX=gGDKl9d4n{Dlan3ZT{o>TL1>U#!?-jL5P zhw&sDixI*Wkn_+(25*OMmo{2;&VT*$#RU7)MHO9*Ttfeap8RKJ_v7{vltl&8E~TZd zhrm=o;Z6i8d)^9aQ*qoz<gNMR&pKR6@cJ;b%A_T5vtylUJJJ0X`FtF zW%t_Gmvi68mxo!P3rnV*y|l9#B zL$|E{_$>bCVHLzfOJpAb)jvvBJ(~Gh6LSbT>u z6}<35a0>N^YV?EfYj}a)Ug#;Nw`4>D4y5LO$a%e=QZYG1$JmkkL{Mu2DPdh!x*XSVFa>`m2-PrKkb!bx!oQR0{ZnW*S$ zd}2cA*}lC@{y>~0qKHYTl7^g*Bi>H09o;SgB0L>QCm^Nll#pFCxJZT?yAvW7OaLU_ z_9bb^Z^9Cs<-}l$<5YCTWE{B0l5NoaSjX~xbUQGa#JoRj*NL+me`!-P)5atGa`T>5 z&@+|hB@-+lW6ItK@hMr4S_I*eHTHju1YK%JqUzJD(;usbb`^hx4N?U+)aB~|Y*7&# zw*vUKmJSI!FS`1QT%^y|={D5@7LEf>Mq4(Apw~b_gj;$b8GY3p-U%T;5l&`q^ zPy)?GoPG_py>#F4NS(t+oLW(I8w9D+m<46KZ#X>fnhMNB2?uQ8qAzz8I z&k0vjteRm`z3ZK2h7-I6qvRNiBtjybRQ(Ijg&tf0(`Va4+tfY$VM*zDoQ*((NGFBE z{sO)ibKB~v7H!~3>Udx*x{*H0%r|4HvA_io`U>Y-1j!7ST$6g)mAc!_QzHMX3=HI4 zApxmitKytD@GD)HMv|oW*E9s_zj}4ZCH~GmIVTix`90g1qO`xzqW2}#8zQ)j0OlIH z%g9S>mOUo@~adZBM|BZY05AgFScx@>x{8zIfuw(FWPXJcZ=@a>`^m>DEM!PX4?uQ;>vapdo5j zH1k67oXB~5Jtpd0e%B+aA*xKeu5=1#q}QN~5cRgJ>Lgya0jyiKWr0f7;FAxG$kh(3 z_ZP!CAgKUUE?0t*73&Q26=8(ouP9qtD&SYn`Ji*Cg_f?k1!0k`9bYup3*hXrLRK)N zPBDyXTBSkRk#Op&3l9Qo*17T=8j_^`%oZX&bdwpcuM>Am{>V=pHUlAjcg6r`K?h2!`eGEtx7qI;X57D|2+ zQGcS33_kq!a+J9JCvA#SYK;3Ak|{_GtlBvT>q7R$DgR!KW6I}GpyR>L-PvcxMcr+1 zTJlz*p>w06TDt&IkZkS8g*!HZ+Oc`Dw*Izr>cOznNgK3TS$~358GU$;FYUP9)5f37 zOKRcH9kWqhhO0tGt5Nm|1hH?+y=z~(Gqh(1EK!H#q-w*>W&t5jy%b1Ppe;P$V{JVH z1rK+>Rmu*!+b$Zyf?IAW{DH9j6V};9L&f9*oByDe5%!HdQy1f$Chm~0r>)i7$>3SA zUyKrpCk3#HT@6Dn*eSbFn7B2F9wrrYy;Cj>%Hs5uPh%AmBR^<8utUZi55e^ReD5@I zcYv#E837+Y=rn~80gJ;xV!NW2d=`HoGqHhC>4EGcqn_1xfX{2>sIGsiMcgCoyXk(?hIznS9q01=1rQbwGBaRq$44CJmJZ4F>$mD3Std4t+_Vnq148aQ$S z8w7gWJTH9rl$N}=C2>WE_ctbqjsK(l`1c~vm#Wd%le{xD-R`ELa9IPX0vHYVrOM>- zR45Np7xW^s6f`I&avtQDq{_M#@XYViBPVVioqOAcDd{`TX1_o?&^1^*KMv!9D zVGP+P^m!6Ek9AIgq?Hw*ugO-6zLUS=(y-77p6eeyk5eTgvy3R@*#qtj@;ZiPqWACV z;52YfkeT$@^4*|CIuNv@Pc-TB4yB016B2Ldp|~jURLY;S?Y)FMI%lN?phMgr0Qf(Z zxcDuMo3?-EIr2Q+4oV0UAaXtANzQ|cW=rwQG=~vbw6Cu{C-@w79@dymwMgLSv3$Fu z;mhMjUp^>R)$6K0>Lvh^Q<~#8*4{52{o76Qldr%nI_E$q-tCO_AF$X67ORh-FsX1N zLtiFaEdp2S+VCU|PONMMxGfaDeyji5W9;?YJx~s|h%p z?8^sG@ZB%GZJ=w=vPAT=Er!IoV&16J%RaM(%uKVzW-!10`Sax1N<(!*mR8ExV~`1} zkqKZ1&HS}AoDspWz)?>0z#T2UG&n1Nqh1@;1G5-QI&J;Wv|4x}V)oNcf6jA{?MKy` zO5w0t&Y0ZQH76^~z5xidgN!=og_L?3rb)m6caIi<5lDSjtw>M@yH<#*!6iX(c>=X_ zaefDp-xdf^C@T2g*RERAXX^|_B1lHA*1#rp8{PH=g(osn6ZNoUL#>jPdXwM@GrbS$~Mhsxek~mN^M_Kut zI2RQhqH;2(adI9;+QU-U`pVb0eUncD^HEw~+;3uyL-SEV7FCe0c(0Tp^5@KX0D<>x zIz{&x1wE^22sZl5TiU-1cYO=72<-sM*aGMnIw~um`{IU4bgIg=s4SXUSd$-%Ot0oV z_gg>T@g`s#N(`5+Y+wDxc6x8K*`=RlT6IcYy=gZ4*-aAb1c+ZON5>&rR`3c+>C%T; z2*19BAYa5O1tp^6AWCs5bk<+#R07B);+G(oY?8dYh8;N7skN&x%@cDk$38RGzqKQq z6sZRaiZSruAc9wVk(_^}5V4t#5s0^0umzXN?z+$XXjVp;iMlak1jo+D6sl5_LMR?; zMRfPPiCfD=S?AvlDDIRyo~~X?*hZK_2KQ2(j~9j;Ujn0%i2=tEnPgK}Qu#=)PXy&_mg>acOm?4lN zyj(rxIl!y|3MzkF=%50;-Zw|bYNTG^yHHx(Yk&Je0c{{-Wt8xx)3>{^rwt`irHOz6 zqc|Qfupb!**^^tk@9qhLeGkI?Agg}!KF7eE!h53%oDB$^Qm-ere}M_n=Hj!FKTRWF z0er#Z4{ysCh(E(_TC@1v^*|of?%$l$^=DcrwBA>Z5KxyA=5^WIs#wN;a z-g30dVl5DLlX{`bpQQ*Jn0ubdDle{#*+;Uo1s?zAj*?Htv)>8ipdt;R-iOI{4@ju; z^+Gm4JDhTEo_z%$8Tw28`W&szA{~%Uk*%orlXxsV8`l*0aczjnhsL3ztr!fz(m4Be zHA{oz@K}Io-3z4SO}}%ls@v0Ma|-7yY@q%jlE<|Ap!>^%)<=rSS2YS?Z=!_SC^e4v zyN2R2vWJq6K7SKwob%_P5j?Pz?RCc0v7xsbn6P8W>E9dDmrL!s0RfIAcpyunSH)vy zJE!d(obx4V)N~SRYqM2dCdyT(e>%f=B$dMn;V8CF{h_=VlZM83{qg(@G>C*$yzG(S z!sAa!y0{kJJncef%RJkqo%9-0Z!*)3OUPd)x<|!1Q!X|7-XIVLbyS5@#2F~2wgyw^ zI0X*(KFT>gFHcve!#KiY1eXXDe0r2@R||YlLyDO=L))EzxF*3cijJz_?F6GF4dGt_ zK=0yWVbf<$uKNJc_Q4lBQ`u%6{mYRS5)K)?j}G9|WDPKZ1C=FmW6HJZY$e(xky!aP zV&$K>-!|)sKdB3zQ}=WqO%`l=bW6HUYV-)7R&tPsUoj5F_Cx@XJ9X@%q_DnFCivV< z9|_HH0u0f@c6}NI0_#HHaMQf8$c!n=_zNJKc)?SEUElNzQ~=z52QHLeLt~*kZvxYI4za)#zqmNfara0!Vn{O?9fK29!`C6*)Y1dxj>(pw>`G?WRU%S)@Uo3|) zh&PaX8`K7&lKneybIUL?9fKk=5A^70>fvbSQat7M5jHFm^of3M($(-Em+>S~VLZI5 zOVJWwAkz!TW!+QpdadzVFyhyK|IDUj)Wz0wj_=xF>+6U6?9M#g>%v;|#G7SY0|4LH zQP5s7UW*FY1&k^p3P=%vKPB9q4iLMSAGhVRMt)-|Pea()X(7RmXKBB5f^qHOxEs32 zn&q?V*(65jSMAJ5Y$Fl++v+l^2@`|6+zmk44O&FL_xsjhlbJ1f4FlRS>FCCrU?<~T zLTghk1070R)+s3{!t8)0{{rSAha5d4VuBmDfx4=|ns3NV%w}z@t*bOo1d=j*nw(S& za=mh4WcR9=5bqfkti7sLtIVg@s`x8)(~0%I?wczMB1y2ng&OBTrcFI@)k@|)|6zvu zuaXxh0PX5q4uh6;mR)^3miG{h;H#tG!O*<}ft>Zzx*I+$IrZthorVqn;UM$#y7M@w zp070!2PdJ@WpVLYyhRjim=__RXc>Vh-yPTHfKt7GQHn(nm#F|EL-=^@_Tk^lZGP?rTVYx7I_{OJJ&$;3LR)CSM+XQ;2 z8!ArSWQ(<7=1H2*6m~dkP61{D%1rPBOXF$j1yFbxz>`aT z%yRDSuHOO|6|$b4Oeg_jNwf~KK$5NA$)Ys39O>_I&%)`S=i$FEn-qF@oiN1`YPczj zzHD*G7WIOb(%skts0C-Y zt{d%rbZSpU@u}ut>c{XBG@CwF;X_`fpiwNm2&d8(!E-%Khc+I`kW77IFF|BIKD4w9 zY*hEnrnWQMy`aGU7Ttzz;Qb9vM<*1%=hnF2X4@rbd=+pkQxi{3pM5~zV2pTFV$ifK z1$%Jb{3XM<9J?$~C0UpEd$x-bk$y8BK3%@?W|(8 zD^xa87lG{H3Mj*pt#~2yb$4@Dr4XH3GSY&njHoL*$5js|YJjRxP8MkvYfCtS6&TOb zPFW3!X@9og;v_;4b7z+6}6(F0s`JBkqzr{ z=2*WhRGqY^fA$6Ne$(DNWp6B~yVaq)-#F{6j*034Evjd@Js7|Gy$=_yo?n5A%>c~f zjjEf&8@ceT%10U5B#uvY+KrBsv*q<7gbr%62Aek{K-!Iv1%JrsfqrUG^a!mQ732c+ zR_JnO{9xFwkh`1z_u~I+wzNn`|7v#O?6}2&{v4=*$na@GKYoBLQpaY3B^uR$s4h`L z(EbI4!;W?p?4sHw zwHY3U9vst=)8#9td{QxyzCn0i`+jRA?B-I9F!O2Yt*mc!IDLH^ScsYdqTp1NYZ6l# zLXOZem;?8w9<5_SM9U%*+`1z0VjGA0AP;aQ+B?g0BbR_Cu|9~2r;-9G{H@KXAxZfz{C5FyR1%M@l-F$she~Ry!6!; zRUoo_PFBA`wL>NvIT6!yAh0Y|Gg&@WC+Nfc&|2F_=~-eg%dg>>FOkf~H3~V8GPqlU z0R*-H8bGO1resG6gUW|%P~oFlZqz#MBlj)dbxiR~0R~_Ns7wlIon$`m^xW4?DsQ<5 zm3t1FaxHuS5SLpbUgM7M4YHIteRB$cJUqJDF!;VZimW>4!V6&j6-D2N@{X4araNae zLmGBk!Wg^LyUXz%zuMsm)LH>egRhEFZyvg$IUmI1M$R#e1C84li<_6g3N3h4i}nbt znZcC@g=%*{gg3@ed&?15ZHfGknP^%b`Z|MYn}gf{+0g}d{0xI-81czj4GYQ#H*P3= z7~njG85$|=aUa;)bZfSAzZvekvRPYUoe>~7rt9*|{i zr0kWu){f{n->F%^D5&^0waaraZWx6L%|@jYZewUq)2$3GO;W$w*S)1os`{_h(4pA} zim7ei#5cx#b56ubn}nl6S++PoXBml|dCW~$?CFwldAaF4Rge(8N_N^S}8oX8a3+m9HdmXFL!veSU$sqEO~vgS}JWR3vMJM zB;~5Y_%ZbX<25dty7LKdlm!Z2r3A1H&n~4;-h}eyDHVQcViD#d-qaq(qsbRS)a~;7 zH6^y~=D(x>41+Tk|EHy{1bUP(nJ8A1`YySeHLGvag_3YsrV+`AnKDNQAtQl@gLk zU5Z2X7ZI_bHdED9XTt2ur;U!iv+R1=z!Fe(J#Sysx~$C9P2_yR+rxB3w*g4^V#t%p ziLmoCkmE3mkp6gh=(E4^D9w`SON#s&SE_y+I5Jb`g*4dtsm_Z#LT2G>7oRIa4O`70 z-z>FW;Z?b9`dRuc)3N!E7IO#CDAl>$pbG3au)Y(WG`STw2Lo?M3%BMrmW$6CqDXOQ z3@y1UO642wuhPc@s1hH1LO^&ZpP%$g}2D{?pojTk{%z5$!10K`*E5!qe%z&vf# zjG4OI?zDsj>lGVpI@dcG__iY?;Ir#eRKyc*^}XEdR={>tqGIw?>$&X=xCAu4XAlUW zc#WX&L^QtceDir(&EPA6cL*M=HAbuY!(2DPB)U|3lp8*2?~jvqjq=w1f^itaHXj{|wK|1KLePbpA}8&8 zQ%j6}GH*Llz0-8Uz{$3r{tR)RvD{+;0%-{PMlcnYO|p*ml|}}_40|@;nsN4h-3(;F z@vAS3%--%aA3fE50RUOwfx7s$)$O>W;I(+V3j#Yb_^oyc7!KdMi+mRh#eg^{5M54( zyNWG8jeDgfEYyg60FY^&4TKwgf$4fg&!pMy8RrWu^OBpyQ(!B8A1&LtnLfo|_lWBC z?c@zwEj{4nX=C0wpj$^56RfudezYI;l^k!OpBTI*IN}BQ9lahDcEpQ}stK$(D_pG6 zu6#m>)*j3Z{qie~``;zqxkvKBneazzL{DI^4-f)?!?%q>n%8?|lm;I<-kL9nkp5|v z%57<499g=-?yMFhFjv%G;NHHbajXug3li7&;pv@B{3ozX)3>*=e=e>s`~tp3j0?-B zs)}zM{(=90fCjiiCrv4)EJN^dDMo8ydTEBs{MR&o0D`bKy>$!|%3n^2k18uVJ9WTl_p-k0FH|I=As{ zJe}3@S=^4UA~(BQx8(7A;77S@cEwDkRwag-R*>njex7aAtaui%&AHhU>&tu}Vwh42 zb%5CvJUv`-Oe7d@%PY%9L^xKza&PS!!+##gx zAv2n^l<|vq*(-E)#@xwZa992Javi@3Hi#XEoc}5{fB#B;8z@fB2>pKF5Gb?xaC7`; z57^A^kMw9&X;hrSl{`b!;_&k~(yxjR6jjRp%Ip|^K~gCeD3fB4JanJ5YIeg6+Bn2P zHGld}ejj?I_}W82dlM~T?V|f7iU|koWoX9sy)HYf!NG+`C9an^Y@_hUUwH@pl^R2P{`oKZ>$}2qD9sGe+{+*# zzdsTgE^1CjL3Ed12i&ui3xfMUQDJ; z0+IkJtB%%CAv+m2GlZcNBt8y4?a^14E&r$oeuB#2U(q584BW~xh-R!s1fX}&2Q^of zep|9e+{kgz|DtHC4j>~vkA6vmkiZUz_;|!$pIvwQ2R+C1+v+0(rT29!Xm5~E#3Y2=7;K3T8@Ddp~A zKB>-~s{6&G1a8Ga8Z;`xkVhy0hae3!1XU-dg98nO2eGc4KP*^`T%ll!GPr_NJ1OP6 zjC@hq7ba~O{Tyz{Rg4{D)- zYVI zf?Dkp*9NH##Jv3Bp&ad=bg5d%xjGOLQsfil;`KQ+5wUE}6c5l*;clJN-*nj!I^a8Lh z3~!-j_Rkl% z&UzGJw34C`=NkoNso3AkIQc!8Eg%*EZ#Z)pE~&mu%@-_j9{JE$K1G?#8^ADa+nZE> z-%va0?blX@Cc=dXTzbq^%2D$-#4qw-K2+%{2>G1~-T z!hDd_r9u(jjJKcyKV>4YP$bF3{MTsU3Dzpt3@Jj0V)8}_kBl{K3kI2Cn5=uc=eE=M z1!nKi{R=PVIy1*>X9b9l26@fi%oiN~>7GQN3A>kjRd)Y1zv;bRW5Q35U-vnwo(D{H zEa$$}PxUdqo43m>_T5ah@;pkTdGG}k_oKaK*R7u1l~@3D4B*^2)Pa~?!2>pP#b3kt zG%I_1nfP-%{OHfC3Sron?uYX(t41Qg81>31#Pg2y;A1QVr=LT?InvI*xo zd;wvs$gF~7thWE=iPzc%Sx8{8= z+hK|X4uB3+>c)BJOFUg5J9sn=SYL@I#_rONpYHOsi<`dMgglZ}TCSb!1OiFa{4r!+ zW(^&{uu$fXyJus;jn}oB-HnD~#aazfn@E1DY9M&Vnr!+N#9*Sdv&eH_-j)8aM(hnF z;qB-@Z|b=LCz<%FaI{{2&N12Er~QSg9S0r3Z2ox|3_krJKu!xg@Pqj9T*xh&KHCIXFJqnn+Fv`O#c)G z|8cbaaPs_6OWcsphU$jX;3z|8p7V&Nbwey3r3lRn;BaWJ?+WZoi3;hqvjS1%ArN$D zsa=-Is}Un)ER<7k*9C}LrDe%tQ@nOxms5Q%EYM{ECx8I;K;m(YBJ>OHP`@AX`sh%j zYf;G`0!Br@)}AK2yhM#2@Hs@*gSIb)=UqSy0*)@qh%qp_f_#KwL||Awe2T*uZxI92 z^VHWxhh~4dL{RdF^%XC4WkL}~q2>q@1y8`H`O{FRQ*O<`6t!P!uev!f32dOt9nzLm zA4Mu5m|pLye^jejj*A6EGh-EBXEA{HSo!5*;rAvY;%%$+UsAC#Pji^_*pp&aPahVv z$3qX*0rp5N5&?_pHa0lfhqvXeXb{1`%aiEP8_e?aW$^n6|9epq%B02)wLWC^wa#jT zYW^ZhZKJq9qec#yIrVa#^K;NFbiizRQm>+Z{*cs;O$>m9UeHyqc?pEd#Ie3je_Lq( zqlUmc1JD|(*1+Nr{-@?^1lr*a02L=Cqa%jsxfG7w8zk6*8# zHp+;FH#rA4#CjD_NT=3G#d>%sy-ypOti2s_(l6MpM83hRTZwo^tr#vTo_VPDq^ z7rBf~&yae8lW3d94b+G?kgZ_>?bf`EVt*d&Gh|o-HZT%Jx>fWdfsVR*mMs$xMupO? zo8QK*XcxGF&w4BZ8)Y19FzU>ofy%SaD<$3A2_i~b_VP?DzgOD;t=`d9{t@Zev%y>$ z%uB{AAOTTv62IDR0#q&%Obj}~sQ!}Yq~)(Zb4m5`V_|vFqGPLafvZppPJjb2#M9W1 zTK0K}+(2tjTKvfgKLagA)r(=!LPz)-7^_wk(+L(g2$aleq8x_e#HyAx7~Zu5F~bCO zlNrc<4*9DiVATKEw{OdK%P@%?fBsM|8wHS%%(mKKJ{+@XC`ThHWFn_<=YTO^Gs-bQ zb3WCJ8B>W?PDmHj4IY}VU;^Q{y=X6AgM{0JVOy5GInYI@1)Em#wiNq%6fVBH$AG1o zg@O6U_R~dKNF_$~6sSJ;!{CoJxs_ai)^JxiFA#WC?i(_@hVFcMYY?O7&4ut9D5$ow zZ!6V~B?5V&6~v)fB|-gn=eAj1rhk8!|MmQ;IIx*mfjP|+mWGu3ir3`kRsrleZk}=S zWxr}%^N)h9eM7(6%y6*M#kbeEf>_?Q&B(0-VMXA1ad%Hm@H-$HrGY21YYk751fqv? z?-!s=^ZYVqiL4jl9(OSx(d}ccX;NggLb@#mS1AP90G6yaOvc!ud^kuGvIanhgjh10 z2Q9OvOky+QG+ID>MA7o3gVZdx^rRcwfW#nq6;|ieGHg)kV8MW_EDc@`b|Fs|7@ya4*Jd%?6bedOD!zP7!R zHTCfrvp`7NXou939cVnsa07X|`Nqi@anE_lhwww^zDF9IpU04o9Bu(`i=%Hsxfr!7|c6m_!i*z_ZUnwKD)F zi=nPBw~Ffmz7QGv;G~-|%-F9ozCQ0h3FD9Zq+-zw>%+r~Fl&wv%e-L(6Hb&${RPVE z_}#NoL6c~vgw!l;k4?&W8@}d(Demdw>prtsX=a$-+b8)3;9a5gBqL_=)u^^Ly-{hEhTfO4wqe$altjRt4OdL#~9^}4egT0`_l^k_rj)? z(caesb0Qb)5dbM;yN1De8DyK?V|WG8>$HIcoy-ZEd1A{bYrG6}DCAWv z7jTwY0au$??fm-L)AnK{9FfaWp94~Mwt?G9WShFo^erQJJ`Q(w zxnxrrk@tumEgn9y=gaYDv>Tt(4pu%BYY_GL^9RmO@^aJHw$a9!S3uuh^L3yY63Pv1HaGD4KUa2 zzR0Ov7-e3ik+x@k+qLcq$v!3UJ%QA@g-5_(c44mv722$E;kMU}DPBl~#%7)mYYZD# z+`w@W9M-;1kQY+SOF>fRz4l~|1$QhLD0oE|rmmNSzwKYka@#j`UaOP3dV5fiJk{os zg}}K3IRDri>K-N)fgG`SO)C6pW9ISx9EbgB=`|SXe3Lm8Bd882dIlSxoMf-OUcb`& znqM^M|6}aCA697klfDmoDK+;<%nI4F?T^$eyS9fDr{|XzT~XhRTGzJMm8uX;p3XkP zns9Xp9XKj#- zj9G#?Rb@|&HTZ&9xlpVF&Q3*ISXfDxGku;o3mI3)5?l-|S6yJ1!SY&Xdmk7k3Q)P$ zb^Tk0^qGxsd!yZSqLKkL*0;*-J^NCN6#Hgib~Q-Y*zuxL22<@Fi{=K<>7(+CZ;v=KC&Mq%`+I7I*i{6lwM`o~;AP;7=-|4kGq((BiGkCi_gMqaC5=4kiu;X?3Z2TD z(VcDCmD3RKx$f^dKt~l#u$@bkob8j10wWkL#1%?{8-HVd30kz?v_9?uchRJoTr;9V zE32$&3+iAEY^_vlEJEkzG4rkb0DXFy;kuNy*eyZI_9ysF8T)&)vVDu2NAJyvNJ|eB z`11YnH5?Hs#{g=%o zxj`*wYlPVY?7n-dy1;{^KxzI;=HoKbwo913EZ!?n1pOm02CAmRC!(}ebme6d4*DG# z>Krt8`$2nm>XbbVsZO6=%>l`8K9%q+1QESPDJ5zc#m{{P`C14xI*?V0wBGm#qxUvMH zRqR>5c?enya9@}vf`$m^XT>;=SZH1>sFkE5iU)1KZItE8MvAw;mBTQk>Vx`@M)qIie+?REBwfKEcJYQ2lB{fK-^Ie`c`R*2%Fsp0! z6M>l!+hh~lwx4Qj<|DiFY9+bzGPPgE7N@75Ng~1NyADmbJ|zo}5^6<@0C8GyvJ7%` z`^%p?_rn7%qWVdSmD?HKqMFYWtW1t$dm!kT3nHQAk`&<63NBY0txgf| zmzffYcaxmET+4GstzhhHpEs>M!8y|wW_$%kQu=yI-d`n0QhjwnLccic;;aXTZ!FYipuS8cEK!!Br0i((~ z_i6&5i}Gqn{l2G8IFJExzDkBy8$h2>BQvp69%i0vN_i*-s|NJY;hSW z)$C86Jn;f&@;p${d2On0ec)s13Yzws)sZKm{51Q)N%?*TJUkQqrX(^zs19VcH~H#k z+@$*Py7|GB$!uZleL076P47M6ekWY|Ffwo#(MgU`hIFKa9VstMBE zh*Lt9D$w%E8*wgHQ6CYhCF-$CUq@}`;@*~L&!4-N+YY!fE~clNF_5*cJM**qy7~Hz z+lYj>)XCQQWSF8`X8YrjQO#Jc2QG3h#gw1+S!GVdI@bFH6vOE~ksi_W9OUBH@69e+>7Yf5qBZF13ApwcgHyu7ny8fWp3?Y3 zXB66;KOb@-D>pl1-cqox9L{l#?cv$sv}ut5Uq9Wdc7+<2eLr1^WLGIal76*haNeAi z+WhdKD@DnFyVVhL*gpZV$-X|Cyihf!Kmpe7xCAP4|3pcpV?USwoE)=0F#$m*-P&*8 zzKu3k-2-NmoSM5YAT9&t%1?0@FPwgpdN*gBD^Z&;lV66=yJDEssiRr@yyq^$oUA!7 z2FG?lTL=T8WSSp6X{TJzMYXe(hJOAZPxE*rn$jHb^UFo~u5+{TTZLBZHn6(yI>6}7U z>B#Sy1Vf2>VZL^*#IC!)#B1(dfeAd+!UW|P3Lg*MiU2&e7m{fhtJ)m&VD^a#8TF5$eVnX}R zU4Op8ht9x&g4yaq0ji(*fbSJLIGczTK6;)2=LOyO5vC+fL}GWJ`m$|!nV2y13DExu zn1w>a#AGeP-P1rsN(5q&>%fwQTJ~fs2|<53EALEo`znyioCgdf z<{o7}4dmaY5GxJtc~-T3V>16Au+Y2YCeA71&vU-f{Jc0O6eg|-Mc^X4f< zdpX}+Z9PlUS){oQQqwcLH$OarOi&3t!;|5ik&DBa{FWO11_%2F&?_`Y0%j@P$z=qj zh+=_0R0EBUv)$w^1(fmyVCb0o)|pvAK>bsRJuiY6OdL~Akk*Hu!dn156NAZJk$x^f zUBzPzQt2GQE3*T*5-O^e3ecHvt_vFPA$z%z3&B!xGo0)r

    PkKys3CAZ@ibR}Vh zfV%6%$M-bXf)@Rw@Te_>ntX@P=allg8CPNSvQ5O-{(`jGyJz-6mfYja6m2RXB*=$P zsDUGm0pD2VyoeWZM@*8X`{Y4q$2_VXT?}?w4ZP=-VrDU5{F0CQQ(W6cbn}$MRL4nVa+<|b4e_4+jlhtn7}fc`>LG*p z&I8T1iV+fGu5+<12{MKV#tdgM(c)q~#4tr*-~y!dpo=a<#D3VhpOPM-#PdUZw2b11 zSHV+(<+MqN zO`2iQt(}r1iZ1$%x=TkNQ0799hF<@Ir_=O9dyc%|rqu(-R3IOxAowqSQ9z`|TxeD+`~SS+#_s3kmL zZ+fK;a)_EW%#x(hWUb?GElSNYO?vFR}1gOiq zti7yGT+h7TL~hV+AKem7CSoODHtyl{N}Cj-kGG)QfMC0%@fwbY<=DCRwOE<3tys6Y zXMF&Z2_Xx`I4|h>=aurgw!8IlS`P)FH?%B*@u38ub5DYZTi`gT22p-fxiwq&*wa3> ziQV}cW?|ESNFs1$dxX5s({4?jr{#lE6Qe+cctNuiBxqjh7GtD*bzoEM3EB6~oqTbI zRGDQSMfnl1bY4XNYGG0sS`00^o%?L(vhN^6mGEVZ-#r1{V=xS8>Frs_1j7TfF-=eC z!i|9cp~)Vu*pCI6NWH$4X6jF-8&woQe!A;WDJ{Ed7_^{7dVPlxs1JdMy%Fy|Csx4C zo~2epJx%XcFsh{g8hEP)a}55A_(&$ibbIv@JN>NB$zDSkDCR?hJPj=v%qx09A0C0q{l6^4k%0l>k;XD{%b%7TmK-Go;-+{wo@SamX53@@~sK0yh}Qel{#^kqNSi~$EIfW67z-(ZxOp?5(Lu#WMZu&cqgU;FCSt1bMuy8um#NAVj!y7astqI?8I5^E~G`%F}u zQ&P=32BCX>bNS^lfE)y8OQyTCT{vt(f_aE4tk8x1v0Mrg zjcb-9p(ek&o9Z2>L1pQS-8b&1UkW&Ka$Tlp-Ln%AtHA79uxBjUbeFhbA87l>q9|E* z6ae^$569h=0SRGqU!GB{yBr&>O#;Z`d6v~S!82-EFQtIe%m)DugS1EK3zAe=D0!Rr z2yPWEdnqeFstDR)&*g%o(!{eGH792*&{ENLXF9L1gA#@&ko~8w zDLK%`)F|FSbvwV;MTVa{u+Z=WBse6Z%`C9?@}R0Q zD>GJc%{27Ljy9X@>dvey1S!OZN*}K#g6136X!{R|sMMJa=kFzVG^a&XRBI=YQN)Sf zerwa1KjNI9MSy;PG%}&6P&w1=S{7@UiDvydf9Y}srKCvNc6|dy+HXK3gVX|GNHW*FXo1; zB)W?+UR^gvfuIod>Ya;mzySn_hSt(cw~S%w5bF{aPJ@IZvN6P3DE&?AjjWGpHrS#rM6y)5821<~?!^hvd(t)YHu-~_>-*pyBb z-mF_JyEMExWmoP&9YgzlrR_GtWM9c|R2#E# z58AT#l3Bgfre2aNur4rfM?=$Iuiev;$bR$l?3OiVX3ilzI+%}$--f;IY)4DLx?3To zp0LylaQ9KTv->hORh)zJPg+&&bF$l>+A(ado&K7=I>k0o-<>X~TvrFKiG?_dOvCb9 z_}0t|v=}K;xg+Me6=l$atq3Bs&2>)+M5cY+1eEBXCG0(3;hhNa)K+`rX|?hwlF+$ZzRX}ZS$>d?wjwsZ7M40A3A?Sc-@;UhudAA`Rl-ZHg*(XAF8A>q*IUbIt(PTp|RH=esDk&C4 zq(}S(d@63NHfNz3wkU_4JG^Qo9JO z8kA5P+4|VpIMA0g)od;CR#V|OBQV48u2zl?D>Am( z(xeh?(i89~n)S+byEh=M4I9aQvEU_oJAsiI8IF+wy&x9idak=-ajny9j1Q6x(}k?{ zF6+S45SUmvp8c|azR<=72FMe~8^CNq7E!f=`6wZ(<$Z@n&0XTP4MD3ASd`sG9}`Er zcR#~Tq%7zh5$$Y$iql}9jLmc#{kU<5YhulGesdzMex=YAC8Udc`g&57P( zSOx3<09lPJu}^uX&xCv;0D8x>CoCS4a) zD@c{W9_U6*j-|%f3B;vFZDgN)9u+UUvx%}Hvcg(?O^2nr6s)O~-*DoiozWjCsSb51 zyFqfgI7PKJ@%SK%3Fuh7ST%<@Eh*GIEnY{E1z8GnQT2YeVT8GM6pIfpw)fQ@r)t0& zB|vkNJCE^NIS@kf93R2Chdm`(Lu9DJYz|T0O_Ws=Gaf}IWHR{LGb-k(+$Tc?+rmo{ zl;49F)6uy$LflG|R_9oUPVC`LgophVp!xEJB<5CyfJZ5T5_AG&4hPm__E$_#U(&d? zWtEr^n%cQ8j`+>W;eljIaS(dkt{9w&R_!fXBGB4kmxP!v+`l!O zze^{F>Fj>|&DW4uBxS$uw|BX*M)I}K`LmAtGT3@L!VqsJ)}ob}e%h(R~U6&6Mg9@%2uWRS$laoU|45rMlZMSu|$8V7ZU>AC&F%BTU)V?6QeKQr9?}j0( z+RCj{vYM9BQrg~E&ktl7wnxxRWSNBP;-r65-!b1O4VoF@R2#n1_wl0UmI%Y)IkmhZvT@o;~{D#)t=t`Ie{kHmGiv7^`@z@qq!5&K;U$xMg8$vmcUBJ3r zn<`Da#tg#=qgO3o$D)&aXd3E-TMN_s59fUH-XffEL+lqG1@3iW6dWA@>j*RLS&VBg zn{Y=$OpH*DQJP}t&jPKE;`HHDec9^ktwm)18c>9co?VY9CzG_COba8Mz`sYGxx$jO zM46?%%t)oV0phC(h`vJcQuh}YpAA2tpbbzD1q^#phjBbfdl?bvKwR90Q;Svu0#p~Yu8=%_pD=XyPZ(4Y0evNWG~dXe%C85v%L9DF3I z-1`#~mYCkb!^aS{wCL#pu07X;&Zvnb@3sX&rI5gxXwPe(hYQ=V>cu+JTJtLR>4#d6 zIctHkjHOgvsnzOR1euUkhW<*adv#9%ndTN$EdpSl!T|&GdQf>@R1IIjJ;P#Bc#};) zOwO&`C|xw!U+%(%2eIOJnlbz-d*=4VFh0)o-twbp##&D&9Hx3I2Fm6)hdpIbS!uWt zMc?K0zTQOD&5a9!CSAYNMgJru^U*#MN%5LCjN;DegTTAWYl!9??*Y(c43`^i<41Ro z2*EZiuNWvR2XuqdNt>y6Mc;eNs;4mjq`-BUFsjk-0!<2Xpz8qDL=%#O6`|LmN%t`L~&>%ZRkIMvrq=hYq9 z(?^zkbyooUOhSD1@x`{Afd@CqG>9358dYSnbPO~E6Y(OP>rCXP`gPG}Dm98-?V)H< z6-#tJpjt;p4o!xA0{ zsdabO3E1&sNRgYt_)S@@FVkn;>2_9a4PXUP@o6#@y$MMYii}Bbjzqsx3>{c4h8k?u z<#qs)7mv!;a`Lr1RaZD?n;YJ%3JMGq5{S3#6?DZ$PemV7O=_{UWKXO!W=u@$C&Z#x zd+hh4Y;!agJ#=O?YhJ>_ual<=fgM&PJ_yHV&KpEu5_RPAeg;#c`g-a=15-PR`ArVc zzN>jlXHh7jd?~m$Nfyngbb!t8H?0(mnICY4;Dv#*%09}(0z{Q)UpF%iiaVYvUWLHc zXI#$+nV(R8jtS#1W{fl!kJ|Bq^z|WXBcRFj&f2nD?4pr#v$UQur~AtmtAOskz-eQNM)ZSvsj6{jb%vgyi;2LQ zhF_o~N}m+LNF!)9n84kn zjieuyKB8*s3)yxf1O#r)7faO=U|iv*9Qcy5KA?E5ht8;%c2*wuI9ZeCy-5o zzXhXSyt~ai$wg&@s;FI&J`K6vc82&WkXrcB@5Y;zYDWDR0flC8X_JjxyhIa;oMVKN;0e>`jNB}uAGr$U#K`*Rx z%Np_$cDf9GYl$wXkqS3=2`(}fLMXWmJ)ZA)h(-cYkVOLl``iPjE!_&A?3Ic@0Kz{D zuzfpdZj?IQ?0N(unXtuZdLR@Hh+KT{LBmA^@=(ICs`f9 z?pD`Kcx7q1A2so zLs<=T56%mWsHD~((=T^!S~v>|kHVu);zkktyd8`PcMAd&b9Vpv1SWR28prc}^fCNQ@ zeAWQ)AtB3;uV2o3ko}eu{MSMY7$9x)`2g-2vmk1{>+qTN#k0p1js4|!TVVNx{o*zBzhI1W(pv%2AlV)kP${?8*VC-J0Gm}x=*d-H9GND zl0~Kx^LRITqzTInG_&J~x&<`jkt!-*5#;&832+JtL!?FURM~eIt3}uT&m$Irv`be{ zdHRBz)sapxq}V{Agq0BN6g-1MB9f`UWMqB{?~vxW)U zA7BUwH{1&}Oeenzncf#6Q_yTTw0{Kx!fr+oS_kqiv22RU%F5AwFk5X6DKdmY#1WfJ zK&82M6A?n*Hz=M3#|{ma!*j3@Cy`kOIbwMk_Rmkq*iiriF2<7H9ybhzwKM9F*L6BK zMT@T?J!Fy*f5pi^UvuWHz0{8*s^=@>mT)^*E&G2$DPY1*(QaRAyM|0%6Z}=Om)I z{>ad3gs@UYy2&RZ=WBt2I0*+|II|zQU9LAg@{(4PQ(Bh1?91_NHETa@C{C;S)K-p{ z-A4P%dU#Yyeyb&JIA4>_tDS!V{7raaCqm&kot8qKX)m!H-$Yu{B@6AOeBG+g9sRRx zVdrJ?k%dMRYF^`!CFuD&O*&d+KQjC=04>lvS_$)qW9;mJdE@|YxWqmIU;Zg093NW@ z!%`ZhRt8z-5-Y(?trsf8!|F(>~h_-2A z9Z@oS;V8a<2`B8fx!|%RuPNpVkwVG@XllprUoN_8brrCsMuCk6La8cx)>U>iJDcsy zubW<;#*&C3VZqRQv**Y(qTo3pJ!pUY*iM#%XOT5BSQm9V{MQ|0eov&c>3n zP86)&OKrkE|AcVuCIy~AVO;3*>i02&5BS>-YYV1jAi#Ss=oDvOEID-FEDxEp1)5=L z{-G`yWf^ifGL6;D8)kjh2!R%b7e-en8rInR&uxN3y~5sRq>>7NF*>e{KMl(8XW;XR z-*V#k`}469MY~kX-6!MF_WScFmo7!vz%aQJq7KZalq7C0w{E>U7$yR`|2#oYVuJHG zP?LuOf%nWToq!O#p)mhZ0Z4BTf1Brbq*_aH1MzN?3_yo`pIw$X&VTEH*4hwg?V6$l z(?%r4caB{ba(5OBCjXvjFWW%`LY9VYQNvP)lT%KD7z$*kKUS^@U}hao>@4GXbLv=7lDc9C#pR{#W1eY4J@_B;i*{`=LHHDk+$YZOPztz>FTN8v!VKcV<1K( zpqiL=&DHn-Gb%P80XEO*2KHD#06Hwpof@t!Kc+z`VZpyH*}0jA-Ap!fX@jKrEU z7lQNDaDJOAen)s7EDZ5EC6F`g?|sfV6%2MyQ6PDLQElL@%Ud-7ERrdtiw&ksMK#*D z78=r~=@w6rWEy$~zB|kno7*>W>$k7>pHRRIv6+a1)mu-n6KOMW*}VxYN3G}p?Y2mI ziX%NB%WyP{zKgmoB#&4!hS7rrx-ah-V`CcbIkffJdjL?m@X`3WHo9U-N)Gd-e4Be% zitfY-Uc}_l4>#zk+0ICE_sctqn$K{|8{w&+>znU?S?3@9LhU}ekVPIK((+})K-e_) zXc^jGU+8QX-w~)V-`%~nyl*%_@UKJ*P~r~fmAceQwHzuC!U*C|5Zldsj|@9w$XbLp zJNDNR{I6sISlk&BlmjfYhdiCort1KRdM^V`eF5{ROI^(fCUE7Ow;vxM6-vwnaI_2B ztyySew_a6{1><==tQBvxo=WSnSbQmG4gKP%46lXfkA|?)+z5j_88~pw`@CH zscqo3W@-s7Jh)&BP1)A4v=pnQqKXO7W|1#qVThs1{qsorria0csp2em8H1>P0(zsv zAoz>#r*r-p?tNRhARd@`xt59iVK@GbtTbh);<5hdr$b;|*8Zho6+t4!hO|dnd}IE3zFx~N*IxUVnehL5QIe~D z$i^S)T!|kxO|)^Vrh&UAD9|f~i2oT5_hoCdfSEu_CG>hU6rh9dlt9AO48V^GhyvyI zOqBJdgQ);`+6~_r8H)JS4rw+T=HaC-=kItc9e%S|dOM z#N_)>JYCK``a2>R2T>Dm@Q_#J)&Ko~?|dfTD~F)_ECn>e0vu;}d3aQTUWm2Q1*5r& zL2$3_f+{mvh}WPpa;Hj!o8C)g(o#@-ljOH=ByeT4rD@FZOXJD0+Y3`CjoESS@h?8E z{-BAd2_EOZabsbU^NiT3*lj|?WVm-@C$W3V-Lhu&eD$S$l@dI0nneD~b798*%b2EZ zPZ!lvX^AHhJWcN@ajaU($D2ZH633ggYFB3toz<3KD3@0HO{w+vsu4uLF2MQ4oTs+8 zhc3*&gn^0Bs`_=iCYNj*nb>UvZVP&%j&F9fGee}Y+n77$_JP0CZ?c*+qWAdZdb!p$ zdVg$XWp5Z)$4YylMrU!4ABSDO!=xD4kTZU^FUdKa5h>}hgtmBT*81aBx^3~|H%W}C zV#*qvkH>vxb(m|h)Sh3j%wD$*%HHxUKC1YUwwo#}(<8jwqU+P@KD;@{DFO2 zu=oa0mqHQ>1lmOqyjAkR3~|rAv2Jm2^ndu~y0dd(*jbIUMQBsxNnyT538`Vmh=JYy zUv|W|gHAzNIqW^QCY)hRCRjhFm#nHE6T#E`D1|ccg9wX3sN{FjJ+dLHl;eJZ6{Y3tQ{)?A~5Vz_3HH0@3r zm#x_djrs96^#b!?pvYqQ`IdT3YoL0z%|)?F`;voqP2EqD)t?(3jX$Y&vyO%mUN7sIl*J0X`HKG4C0S0`Vcc8 zKu5EKzX{u5(zyAwJcCeT$;@zmn+xsxX3db^k~^WP+h0$W5yqEdV(zZxXKPD>kNam% zZT=PWGUxApeX&V*5Dvc`$=HC z{k{4aO)h>Sp>3US&+w}coy^D6`0Fnga1C$F7+E^j=cE#*ezi|vP9j;riEMihgSr0& zfNoe0NG)D@TI{mEXt@SbB!qE7Vz6-zc!VfHN_nl2haFiSZAIA7>_t1LykBFk$?MuK zZJEZYZOK#7Q7yT5Tu3#By2ox;aD+%*+Mm&r9r#`JwRJ^++tTg+(iztQrz88+b{c^i z)7+cOWhMuPWuvT$k~f~6Pl4N4OgP(TJAU@gpn}($N0^7uA}glFJv#3D82t(KF(yr= zh)a7I6T}7{{$>jS`e($5@E&W9Ix_K>0s8R24?>#E0c}ipy^%IduAyJ7kTqI4l249J zEuM=p7H0)9xXU=lvWP`w{z<|qB-*1@PGw#5Ef)Ik5@Z5CVlr;QA(RR(Tq zj0Sz3F7fk5pVdt#@K;9|SQToHF1#{amK<3->i@jfcW7W@=+gWP&jFDEyK>n#>I?7O z4Ykdh1SQtiD^48RoC&!5Dn{@2=IGnZ&4o38`LzLmGS5TZ>zdP@zd8oWUM2+rGz(H0 zA(fDG20XD(qzmzbppjAppz@;NES?2gQ5?UG$|))+1VghLLpx-5XegE4b0B->hB=^_ zi}NERSqa3*BLbi!pfAF=$dIr7cUFh|E?HLA``SkR?gNbp1!<&u6U!eA_KKfruS!Sr zRrPAD7dt3Y6_%^<#LM80e-TqAEzZ&9s9zsqWq*FGxaxjvXW7JymkF$#7P+d=T)N(v zdq*vF4ixv@sB!kK?42cZyE&uQR30?@Wygl^pMQ1mK3@d!pG%p{d)LCN%hPwji%ulmE79OvrEw=lH0YpwhP0d zL;4I1ykxN$#0c>p>EmvaE*;r|VX%w2R_-zzZ58qK>C+If+EJQpi?cQvWI4mzW1$UQ zUHORsKjx3dv~m9ySPY12yaYAP0=Ah)Cr|_WCG`GJrPJiIT$Y5oHfoYgN;zLYqw^wS zToqpEk9V92c3nGKAi-gfn~$>dF6a*)tDX^aY#dUnIY~TkaqL^H3MU<=R3tuR!;q2A zVaH1mIl9bFHj$ zs}J)5MoyIA}a*o_%uw`C-|R?odvbJa7H=yHJ-CS<|Eq>w|GHpxdS5>=d@R(egars1l<*g@4Lxp8Y{z-1WY@vMBrGI$=glAvZ zw?bKRThnbaT4Zv?ieE)BzxM2t-i;I3{hy2Y*3bwDl`cp*zttR^+u0C!BcV&+19`{B zy!SRIG=ZU^mzi5M`w7#&?5L&ptEiH zH=V648-3~B&y^m_>(@dcI44QicH-?W5&Yu1Cpsfc>Jw@(!#Pa%rNY-3PQSi2>>RZ; z!5)+w&ncXT+U&CpniP-f{#;!hL_~1Tu^;i)|5{Wnw>RSKw29^9f9{!VB*oMUgV?E4 z6ALNXx^JcZIkOx9IUw{wK_ulsEoVf>1NsEkQKfm`Zd~hWR zUCm!Tc$hJJTeiMl6DxF0OWJ6UsR_1lsVKA%OLA(uZ|}jJH;Cm?0%u=t8|ixx^$gWb1 zKYbE@$v-GUqo(z8GhbM|>l-ipx&9K{(A!OL5jcm4$Ds^i12>iz(36ykvvuM|u8=Q^ zrV)@5B*zKVG}lJ{)oxA*w%PwOiO<)BB39h%da9>*%l9%ZAv=7te2B~Tg{yE=yVi^C z1gyV&2wHjfF5uv*(=rMWh^nz?TK3&y}UkM^X7vwO`OD%Kvv49h8t%TWeX-$Ht#BQy$Pi^&Fpa$;7%7~ zJj1BGF}Eq=7uBZsUqA2f=+bzK$Z}5)k4z4s6|$H5mb+U(c81(&>5W@!?@ z)0Y0g);3{wJ;0jtMt0%%vd;DrantvYlr%m1%KnAJ0?>ts;3qP+@3)0{P5rUZ4pCK`;Nsv}vuy;xCf9Ydv=F>;-;xT?w8qV-i-uClXz#d7&&9(~byq0~K$dK#%# z-1x-~L3K>gr3#lXjdE*i1uLd?VZ6#CIC$5R&$W^{PP6bTlzqK3gI-|L<+m?4Owhm7 zZ&ft=C{&6rRK#F!_!(moJ#l@LCHsOZ=?_hw+ub#qgkpn;&Edn!_nHqYFxX^$N{m8T zI2pfAEAvz0Z46-;!7LbhhZH@-HAC_SZH4>70wo5|+Rja#WNp^sj~nY}Xk)u~!gAt^ z9{EHm41E2?eM3an3i5WNn8%j=d^psD&Y@ zZmu4S+U!YlT~6NcIMw~ z)T@tgW!l^*@37HPPcVCg-Bo|{`5bgAVzGbT=T&0f2JxOt zf|#kriJ~v^M5d;wVGDXJKItqTw9(!EK(uC5ON@@fEYNe`GF5 z?yf5OhON_Ogm(;tLX+9Y>=jSuWFk{p1BFB#MpqeV7?`OY+j|2YTf$lSA~hkD)hQpa zvilrjYHCYuZgXR~;)S-VAej|*MXi7}6(y0Bt5JTLs?1?4J66==$^mS$rR)Sd@kTQw za#6Vn@I*n0s^j>6lAlOQ$U50vx56T~(y@JMp(FA6MWx*_MGk_U?g|I!1v$Y{;qS2Y z_wNM!WtUrSGY$UUZ){RnTRp2g?(lXlvG~QXubZ6hoOftMOC;C)Vg**bF>f(u8btvwGm7N+5{X>gCZVL7_Vo#_D6HO0p`o;^nzqH4;V_zHgHYRc? zC97hVtLr(Wr9U@+T{WB6<+{JnTz;9RM#4IWb83zSzxNYi||j-6{`y}pSr zCo?wtVJK`@m0nBs)W1P!jYr{dnFg)AsQ7yc|Ff*j^`s%8LpfKTEVf3{b9KGVFf8|* zx~GfI<%WPexZTCaay}aO39eO0MS@p-0cLusE9#o*>X<&USs_L%J>A(g$1qdePQ7)j{&sILa=)zy{>feS~GXFqw z$nBM2iQm@ZGzlp0Xcwh#jdk%%Yj?za7n4)!3fh>*N>>g0N1x;sIQyxB;C)HOu2kiV zzV97P+tycxrp=e^b*b2wtog1j$#aK-Tz6)qOo-znuefW#;8ORr{G)>B5i>8es()x? z3R{@D-s_4qvt#-p%ibB_I@g^QAnKL1<#MsL_|WX}e9zvZNl%G3m$oM?brF^- z7+^rNJpuE=x^vyg4m-40fH(nvE?1R%k8Va=k7m8xiuYD8K^||KMH@5p@#52ntQnD5 z2{i-Duj?K$MN0I%jURXy-?Wl5G_&1PW0<%#skozA`L8kyV1rfQ|LCjdk4gMGiaOX7?HrmXF6W?6EGWD7wm-&rA{55XF3QT50 zsUQ1B%}V&CGMxQVrRV)qi;1<6Hs&xNU*HPy1mnkeEa3sc=C z&x)69q>SN0>3rSFW%YdD2K7;(I=QatCpxt>Y{yEeOsd5j35RuSWvC`4_f_+rEz3Wr zQ=}i$*95h5&ZEGsE2z#u)52%mjQ4-9;Xq`Byk|G6^lj*Vslk0a4vU7omY8at2-x3R zTY2Kc{s`iVl7V400J&JZG`?bUEfsYuQtRxE4W|>rCfcm*OjHTk9%clLzJ^x(k+q`8 zaO1${a9zg2vZfgnwtCg?;&{JWszM-J&W{G6P(wnH>-tj6ozpX`x`V!6W@AkhEttch zA8azNcB{SvyqU}u&Vsn-4pH~X1I=+9WquS?lE^Ss?OS2M` zt~XTk)N3*(B5}3v3Api&;kbBx#XKRS`R?y5iXT)BEXZoR_g)dKFmMFH0MW>ZU|Z2 z+m$L~+^_rkAgng!8NJ`ITJg-w6*by|>K_-{;-n9MGuV5G_ppQNOBz$+woVF}AO^b_ z{g%#Cxr%Gg4uzKbEt_5=O!7`Si%}f%I0ETaKCbbzMb&wC*QmB@)9)}5Dj%}NSx&{7 zCKiaxT&cmjFX(+}GH-D5lCO>zv{bIe;5e^$yQsSKCFpZI+4O0)#o37*bu=!0FsS?X z(LX--e z(x*;I+AiX?7M>1k6?8Br?x`cH6XtvilY>2~0_TeYS(VE4OQ5NCRL5!rY=pUB;9M^XlOHgf-uC3T@-VF zP_WNcRpdqe%?8P=rBkO^^y@t9NQ?AulSag;$$yLOIqtF19w#!8cVHky%NOxuA51>n+X!$K|BxFeb?4mv*&zCdHvVgW(E0DFj8T2?H|CsB6c=6lUY4llj3T|No-0F(KM~Kw@>DXG6wuIQq=-u-fqWm9Q z9&l7Gey`u7UVfoG_PJ6ypVPr#zcFAVN)*BTyh>F=ga0+r0ogK3_TUUe|t900k9dc+4_)H^UPx{-LhD1~#(5Jwgp$%1n3H&ur z_mS11xSri3>nM*yQ{vi0tKR`SbF5wE`ICMpQOaU$6+$C+qWviBy0Z1P`T6pCh5DM1 zY_Sn5#SzJTc|}Y$;l93vIGbi>xAhn2wS95)FRL73e!156#wLEZ zv19sMgZOKXlj9VZoCNDn>j~6XG)n!pFW_>8+$oEy6EkGLzT~gz(t9LJYbC4t0lxHa zk=jFhB;xK`NRp>vwR2~uWUJ_raL$I#!4}aBJIu1&kml<;Cslfxkk^;s*pEAxj{{?; z)9Ocg*17U7qjF0ed)xQSjbd9zNs&SJFEn%W%p1QZRB(pQA=;b{ceRfPe~m&nIjIfP zA78iqD4D+LuWn?ZS9dCC#q0AAu}e;IZIs1fSxL|QJCmbZKPdo9addul@q3b^L;L;@ zggDhfIukbO*2M@;;pf;1K@S6)SVDI2G@7UJ+h%GXnS&y)W$yj|e}Vt{oyjqHDD&Ig zTjPE^HatZ7$B!N9z9Y=Fq0bX5!PG6r5#_P|j{nWs^ST+TEFY8-T*E)#=|bQqlj!Ri zeeWRnh;zV%PR9WjUa~vx1AUu^yFJ)LOY&T+Q_V1xF72wz!Dy$whdA+f*X}&SiN!O` z(cY$5aSh)570iXp4ZdVX|LRKyZ{r!=oMKefn`dM09WCYnvCZH0y3A&$U35LZ{7v;f zs1d{_%5&|rZe;la);=*{d(UHeQ4#Ak(pJE(w(1gfT&rT85xbS$t-bk`&QW6w9c1qY ziTttlJL3G2LIXos-KXe`QD=N`q*j@o@rR9%`Crv;Gv4@mx05>VvC`veejCbPP7(Yg zxiOM)thO3Y|9TZ3WY%(fCb*K8PPkN7B}g-!q(6p!bf+@C{hbPi9uq9BKMqGYe^}!c zp(l4%PwvvNoYTP=R4iHC*Ntp6XVc(NYdkKQJANxJR@~)X z)AdVE!g)W=yJQWJSrx zA+K@k2$_C_a2W(PHH89Q-5TeYmDqVzG4EyNE+LdChk$uovhm8ZV%J6FeUNtHt8>xY zqjp?s=8j4hEu(Ac``fR>dKjZpYLt7TyC%MGih%Gc%&5oDF#5BK3sJ`v$F6AHn z#E$2XUS+W8uazExD3DttJGMS+O!#fba%*eKWlpt94CC+K$4Vb#^Iw^DksQIl8}VM( zc_ekOL{D@@?TP^aQvaNqH6Dg|Ee5M=c6;7M5nEOP+*w z<*Cwj*Cu|yAOAwlU}jo_t)!5XWq@|xo3-o~;RX+3eosRFQKthlAE`^n@h*Ezuf{l+ zY9K|ZLGL1HEzNz+gPOg>xlUS@9}I2d3=uZfnRlD4$z7=CR?eLoy0cg-O~HnZTj}3E z>M8X_s4OIMRn7l>Rip@#9Hfp9{*z~twcX2;9Z9X5-eu+Wubp%hWNW)Wf&Y5kmQN=vB zx%*cHJ3SxzJsa@<7x;IV?>Bll?LS7&|73Rl0X_K!9|p9~f6;5~Jj>|&CbpIN!L#Sr zonL^Bq(qdRn0bBv$V82lcypfN^QGu(`M2)4IgaB-(Ktv2wBqRle0fuhrQo3a5?havS1m1J|JR84V_j&(Q zKf5q<-`_arI#*POzhl7DZa*u0`itZG6RMLZ+ozl5;-&L64s{>6ZKY&8tqeTIrCyb$ zw&m0Z4_wpp(&R~G89uy&_+E{|G9rl;(VvGi7j&C(s!*vO&rL^fb;ecP5{ zpY18LPFU1ps7#D$l-+ZAc4DdX{=QCWQ;y~-?aG%CX0{{LX_Jl4N3Ig^%t-jvZ)@ko=>ry%@hytc6xP{0OP>|txi?kUHgK;?Fv zNxW!(V31&O&MDiAdK8?o+`>XsxA7$+Xvs#D#b3gtXt4^A=8vh)v)E-a9sTO z<=xFIr6g-(b^E1?AH`6OW*Sp#W83zj<1vRNNEX%w9M&|fVlD{El)>yAVP=F*o1%-~ zwyp(vkDJ_k+dj!M9Zn2vn|$V(MT#7{3?brPjz;>1#FhCIy&bA*vpR84o z1$-ir4a-4O{P#5c??+sSqm#n%8Orv2n2U#{U_eu|tkrxs$*bn7*T|0;ZdTnZ8P3I` zz*~h@cT#J4&$YMQB4ySjc2}zUw$xqCJmj$(=e`J`-23}!g&fAC3~$DT)6aPJ8~=xv z{PVw=rDJ!TQ&tB~&%B~0G)>>8ryFebj z4l1{XAd>&X)fv71rg^=8LbYo9NDu!X^`S`L@wJ6sB_Z$=9>>e@6x5Xr&Iod%G%!Ls zChzN)V?`xsg}OC2ia5MMeD5A%Jo}tY?Y1nH;1!JxmBU*L5l0Rj+#fvC^6+3NHp@3) zcuf=f;Pntof7iZOX3?_YU~B2&BU03=+nU4!?Rp9Iv?V`Bm;9Z#0&NKxH_rXY>M;A( z;-JOf3QRO9<3|h^!dQZUHidt}a7}v#b2TmAx{;)PE;RkF{NRvPO+uix0i^6XIvft=~1QpKnB^pLklC?~$&U z@#z4UWK{9Vy;RaMJ(M+F`e8&?GY^^k;Z@EGxtrKole+Xy3lHCwp&E*7mORbhdSJvi zF8XR=%$Q_kb^Dxtj%L_ zCg&YY)1H%7#YNuI{7@Axi-eS};Pk^o!K++z;eaMD_LZpU6pi=Ak581HUEd}7rdT!n zifTe&KIZG!os#WjnA?3ao$ZE^m(h(zb?4qW$CueTEyla88pST@Kfc$?_vY$n9mGn= z-8Pi{l$#b>&?&-9EZ<@2t+M=jw}UY6{JmZG-Ftf$2a`*ZA=4}=p$%=G&Ipv^qak-w zaHwyYz|7vAbldog#oa<<1|m~E%#pyFLK+#Hg-hKICD>KYX6~)tdAaAI46?G!Y9+Z2 zUMtkez#9>brU9V&^0~=VW0yq}`O2G#{yagNeMF7+o*nmK%>xaT^1v$+G! zvgFlTBg%2`u6<9d^K;0I0e1E4YV}N9w$nE)Y_zG90PzopQ$LbLEqB5@EN$qS6J+j2 zJkLAdFv2Kh*f-;>O>bQLEOa=}Vu#nXBmLbXycLmL8SY#KK~QpPRc>%O(`H@Ks7V^(x!TJq6C+ZkG1FeIl5xH+TE8sqJ!? z%-u7kFmI6b{zxCM7tpSl=Xvw8Ey`C$u)koroKDIs{1Q?lYc%&sh8&Rrl$?f_E7JIx z*4}PLwjEgHjWh9jEa>^HYzMYbTNn;wuRr?QfI7vJhV+^em1x-w%7&{&2QTd&>eo{J zJoK6v;43$6#@I>xc_XSLoptJFjQt2FpfRIdtQhBBzCenH5r_07?3{^pcVEi?@qEmhP9fmfkexoo-r< z3?KgCS>C<5^1jw)%Drsby~VYK6K60~-ui!bxETJiDL*~i|MPGE{aP1o2$Rf*CO3sb zJ|#T)P&}>?$!F~_gg=t{Ybor-6nwP??vxl3*}nriKVP%Dx9?m>-V1Bjx*+X#m0FM4 zA<=yM{tsO%Rm?$x#2f#eka|D5lxe@qy=&C_Iv@0ZFLl3#%3ScN)ymZK2Awp^)~(ad zh`bcBFoUFK!!cVbumk`7HF!T_6k!Lle3};dAD8qWTUDN&AaJ>7&}nhtLF<8g?BZY! z1LKo!n&Rp+oR+<|K*pLAbFx0!oE?$|NP~TMc!B3H`&Nt4I#;7II3&TzoA+#g>F7ryNq3& z$&XI6Up}OgGxSy^)g>S)S%ppAvhhrF&gs^=Xtt(Lvd?}Go4prMF|}T9bmtlyJ>|QJ zD`1CL0HM6<5PbA5%6kx=g7+4_N`{WrYr&14eZqv@v3|OmBya*lg8B?z>f19BSeI=Z z_k+tfQ=)XQ7FcH%K(<1>rO;IbygYRhV!oc8G5FQnU40_*?j2u`c1CM%*wO{d;imV& zYrL)7GuqfR`Ozw;kxGBH^*(>i`gS9$`TfaBm4ndeU|d*8VK45qywU2FqG4^SJc34IRQ zVvPeLex;tyBX@SBmZ%FC0nJA$kn#~Pt6rd@T7V=`&ZP>{H2U94(3m;Sb!45Ey+t>= z*GuQ>Ew~%z)!HQ=lWq<=g?e2ocjR*5Me@|dMVx+tLXy>4d!y6jZVr;CMs9DY?HX38 z^>6jF@$${;(@XX}kf1hLe=SsbKDw=o#9}}|0+;oZmi*@$mnR^{U|HIf3vosB={X?d zI8r3wl@A84G>^WE@6fniC73!P--)qBR8trtF{Z z(}_^qFYgP-zDPXT^g<%w2I!VqA*Fpb$Vlgp&Gwg-pL!}u<5Rw4`Pkk0zJnu?2eT3z zlM}}`<{Lg(4z@B|Vf(ny7#E#1<=#~%(@(~`zAh|jp14qz={mGZuG+(l(Z93nuQ0Yj zRW~>m)^rPHEBdEpD`G1>5^>Fk421sjwj%zy;g_#Pkkgu5V4^ z^`^jB@ltVgtwzKayrNfq=yBk)wu4`qK6rX%gLG|us;%=JUR+;Val_r@` z$A^^Z{-ef$m;B!q_~x89xGktbC=L=<6LVAm@&}Gjy3QF|`)aahKmY=gje{ibq{_#M znem=O4FW4W#$L(A21M!HkTV7ursa!0S(g{yVRZJsGagEW`nWUz*g8wLJioOba| zC*GYG6gN>F*jGQ57JvCPyLgz)Daxi4kj^iCxMDJLo%upT?8PCF)Js1olr8{WQ9opj zEkNWN2|s6L347p(F9dz|fUtUA`3mw8Ge7XdqvG?fN{)OU{;MbT&wuldB2rFKX?8xv z@P>k-KO+e7n=aQ2`lTtg(bz z+<3E;@MS#>0{{FX|Laf3k12z@va_75$faSO6X0B@F~2$n|NiCbG`xYtYP?wZP~YqL zlOs69Tw4Mn%5*Q-&&Gs)O9M~p?=$!~AM%!H5V`e&Roj`N`pY2sdI4FRxtSb{zb}*j z^?l%ZmlKHjx`K&H>+=^ZpvQGw?Bjymboja4o5hC3GkV~`@DwTn4kQw@ zdW7ol@~B@wnAP$M2vM^Hb!xtG^Lel}8MbVV5p=3JbQDR6Tm;ceKB64K7nLe(d4HoC zIZ8kv=!i)SVL~;SccsooRo`cbHblaj>k19WMU`c&!MtVzENA*#qWKrW5j7Wl&v=DE z;+rkzM`$!|R_iDW9P35ouB<@pgMOovdUYAh|Gu7|D%yjfFee>S z$WVHR?9z0DOZ*g>kEX&+qR1Xhq(86eU;Rk|5A)0!NwNbE%BThxg~M8W$_Z8zb#Gf1LE7yo<^akZOk>@b zqI~N?b5OKEa-lm*I<+$x`yxSh_QeogA}z|o;-LW!r-|9R0PIK`D9gwez@Fu!EBk!4 zHCvQWa*p>rL?%N1=8dV|SyzaR$SwU|Mbrh^2<{+_PX+JenBDq)P>AP)k5;w)%l;z- z4K(j>Bu;r$Js`JvKc#8#f%T8T`Kq7EE*_L5x7x5kM0 z7jv--vw^>w#%8x5awwY6#(t{l_=R+wJeL5$61l7rMJW*Q8$H35E%Tup zyUmcm^qIU-FKUgz&D5Nh)xM~_J;D!gv~;57KF~M?YN&h$bDEZ*YK+Qs7kQ{VSV3EX z#$u!9f{hwnqytZT;a0HN9I$_lIPJ?mvw@Jp^l`jsw-zLKk>R&px zTGlp{hQtypM{pTTlEo6w$HcUP1&*J!(-Lz>nCUHc^HX4vaIqHhVC|&q@PD-${`PMK zq9T=41WB^IljIEVKaEhN=@B757HB4Wa7{TbhQwc_m+hDrLtJ(mL_<}24sLgs?;C08 zuR*Y)gP6{P3!B0&lOd{6B3)n|YZg#eM*f)}z6}dUaH5d{YMmu_eQB^C+%iX>Y+dp- zj~icY^zd6H*GG)>e8W266(>qQfI7<81M_AREQI+e*2_R>t>-n;0zw$$Ay(zTBK{a^`JEK5FIIbpE7$}npq&|@!N&KNqNM$G$!{)dZ@^TMG<#t z3!W7uBA_ER!F9hi6;z=Lk>I>W)hPk{=*m@CN;lZ<{xPCGN7)0}7DzrOqjt=!?>t*J zp4EELvSoMRqPPFKZS^`rbtuo(0~C!o>;y=B{-{p=@6ob#9HegmoUfx8CgLZrqj;qo z?=baXbIp{HT-)I#%SIDCjV_0Z$A=VD*CD!9^MjDb$DPB}ZfQySgGk0KxOP~_@^2}P z-Y7*w(31VIk&-X}kL5rypEx>JM`nQy2>oQROTwu=xL%5epi;eU*Iq@B)>G#iu!`k` z7&FG6HWhHiNjyISnY<uLMR>?-wVt79J{N>aycuB-Ez8$7xvkWiCg$bc1*b^GVA6*^^lx+^ zwO3>#Q)QRat;3K{Bkm8ubw9wTN73u*wqXs_oV{Q>B0VYNs0k`*#yhE3iWOTV={M&( z8`a+lzLk>gF439J^w@P$+R-%oULlhpyB-%$`msW$+Y#)e-DJdn?*J#{MZ6v)9#kl@ zvla9MLoJ9oQ9i+qxOo0mxJrp(vKFt<(f=fL{bi)}-zy3aPeV-63OCie+*uh+eb?y>H2aafx!08&4^2tm(P);qtHzIL3>SfNT%woY0 zE@2GzWCJ4)P2e(<4JoK=24k`fVr{c?9sEn5t07!|kN-DSP|gMhPl}a7RMTQ+}}T-oq`} z)?Tf#uhJ4HBQ=e|eDuU56MmQqU?WetG0vQzV$c!qMU0(l;f!4EEIh zyuRWjyjKKGf@)1r&$W$A*GK2O@I*_&#Gwyrk>wKgxv-n`qk9@fQ;z&o$f*liRF%_O z$tx}q`*Y&+G4tr4<{iIxPeqvUA-j{(eQVTT=?2P{WY5kKqT2Ck?T^AUt#k5*7QqmD zXP)S;40WS4O&eia&J>Yb>(LrP-nBPZS03o2&-q1P5HPy(C)_oysWSi*;`uS7OxRMGz3f-cG>_$uQJM&J@`~c>| z1z>mQ#(L+%S*>CxEBCc;5{pQU?%=oA;XFoow+n+}?hyvFyhMGSSaGS#1yId>XHO75 zK9vysuAc1J>0?K5YcG5x6UxA6r=^)?uklEXta}eYnK0aXde>xT=fUAGTywn;33ZLT z9CG26G;mvu7=z>L=3j#BwP?QlBK>aq5`9NIn-uJ|O3lBHH zH6%=Xx>{^L3QKnHt_TGmn2tVFI&M3tT;&R}H^=1?bdA@E68BGeCxo4zGB^s${L-O4 zx$^{@M3Ru%qs#tYRX#m@{@10o_YcMqiVmbm>uE38(FqM5#KVLpF0&6tFtyTS*AA*n zeO&osFlmEeI2WTd|9Svg*Vd#(LTm{5A7F;lK0$;_dZoZCl<3EjvrS5GKY|GHiMF*s z;|c$zSSBYX$y^xKv@MNzOp1>kpEC1DbkvY!H&GP72=*T1PkunnZA^IhNQ|7{Rb9xL zR5}#l!1Z5{VV|;z8O&)MXWA;s$(8QO*L|o2Juo$X%s9Z1iKrBP|3}-sn=Cwq6Kz}V=SyG4Y_V@9C?4pN?gAgxE zeBq0=U#ewEs;mK>) z@LGy9yIMTKgLD!44#)N?Oson7%KPZQS#ul$d)NoN5F%2Te&}Kv%P?FnnOWXP!Np&1 z#QM8Q(NyOl#LL}e@L`5LgecLv&Cn(CHM0~9jGb@53V>l{mXa***W{OpYkT1)G096w z=!AO^w4rP=xZAdxsc?8!n^{(bq5A}iWjF5bPE9{fK-*UeTuNDFgZJ16KkKa{Oz3;Xk+81(|2OPjdMGu zf4Vtxx=2Q<&AhYNMFUXVC_Eu+gS=dG9ShhX1>o@QADz!ZBoo2;@HtEJh++v3Y6xe( zQ;<@1XN8+Z6A8`f9(5}d%b@}>bO|wyK#!v(6F;1*ith@^j#1jak|+RYIc2lwQ!KH% zkB~Ah^N?q~IepLTTVu~MSKQjly$&+V9GX*no1*! zO2(YD39iYAZS-oN(d0I6527BTd?c(X+u>X(So*x18xgJRS6uf-edddfU)aXdpasCl zq||fnx{di$VQ2w=&6QZNXX-sw`jtZ+B4bkNDi;YWljlA%UEkrNK)H?jQJ!kB-fFJp zhQo&1`=gFOVmDOE{jFSA4>|w^5-#(OXLCdjV1QYvzT*g9R%qRzVD9Dqf($6A`Psj0 zho`%uR8S!`Ylp_W$Q!Un3mYyo^yg}2F#U#ci}9ojutb7!kQD9~f9VNsn#*sJDjxV# zpHZpevGW?LzI4asf7?&JQ6(VnAR?XzUqE{mxGqd)H7VYh0Sduo)z?A7JMpH(4TudT z;1js0?k(FYAsazBHd7b{%I|qjzI;`zbE1w+<2dZGZVP+0a@8r(kjYgI=t>;7GT}T! zcMhETiSdGAW;ZwKKfPzZ1yH7zxXGOtZgy^R zXR_(3aTv}t$sss6y6Gf#=F=tn0;&1AB|=vBBNodyWd&Al7el(LCHN7(jf|?*=u!#T zgG005kw5y_m&@{L8eGENMLFDiiE9gtAz`9q_8pqw2}=e1};@rI38JMVLxFJO6Q6TaIrw zK55@_*%r4-q+-0|w&vyv5JxItARFMYcb9q}s=Rz~R_s@hpr*)U>7-6}Sw!zdy(jhl zap_IY6?IRAd*AtfbXm*UVlqc(-#bGmw*f9we$)(Wm0)9Q3F9l$MalX-DC#0Y)A!(B z{WOK;TS88*XxpmecTqXlX!yp+uL0J#To-l3$b-S;^1nlc+sY#l<#9r%x1QkxRY@xt z1l4Kcd5V?-vd8-%7Sca&*=Q@DiCTmbL$DRe*NEvK8yqPh&(dtW&Yq!id!akygCNWX zywgYIC~(`YUi$`MB%+tuIv=RXE|)S&!K&3`5th1$I1+Uf8fo@ug^&QI^~fFUML)JU zg869|_^Dt|)y(cMMe6C03sWD9m%g}M>W*G$fA`_qn()1#5A<%W%B?A!KfnR#oJZ`z zI;Uk%TMj0ATK1v!HO2U6@0K>)4y%s21L*y*rH1`~u5WMYV?W@Dh2J_+3orTv(Y2%k z^G+tEubE)OGl;Y%Cq9Vo-x`3|Bgke5nBLECt9pa2iwXikqFpI?6hvtY612sqqacDA zw{vWff9%<1OXzCjv|Xq6VUF{u#j!DzB_HsKr2T=pHoH9VzgQFa0b_*)@b%mrh`|u+ z6b33cw+b91H$22NMZdDJOaJZNd)CiVnCVV7CC~XLU2wToDREgDSyA#xRQPmP_P%BY z*Eb316cDeVoK!2!>*hy)Lp1*O*8n2Zub&VMs5c9+Efp}H{=)Ep6n{1Au@46v*{!El zlbAHY4LuJ)W_55u0Tf6!$KbVK*P5Vpz$yCGFIVOpoSWc}=01UI!JIgFm808%yIh20IF6lD+g_+nJ1afG{m#4S}v!RVH|z;+1I z2^UImEsf7_maR50v#4C$2k*^H7{*121#!ZHa|h%m$fadKGUnZQ2 ziS?Opm*=Py2OoaBLm3Vox0eh%So*sI@}lUWHub-6|9fI16^BVrEUj;izdntB%-r^< z_W_}4Z@ne))X6VW2PvFuf*h-+$;YO)2@ZY)Qs1HkqhTgX-y_6?4g_8p{UJaRrmtJL z*PJs^iP%=qCQk_2ohJ!!Fl{ueahs!y!f;h zO=e1T5rNLp%OoP@G=D~s%;9#vJ^AHA5m5hPH`!2iCJ4y@V>~Ia@2;u`pKx9f7nm&Qz>51HG z68GIIz_EaeJa-cS(S6dZWjY6_}mrFNel5bmhn(i1$dC`5c z%aKe^xni3j84}f9E-6O&B-hoGV+;0~%t0vBeP&F9%Ux?an{a7H)TC?VHLQg(?a=4L zx^J;x&L{Qw+ot*ZU#~EU+$p*J)sEY9W$f!lhSy#rcyx|mr^oc>l4oK)vQc}lB|Iu@{x8|l29GhiB14B6(*$VH)1&zgOQMxr}@`L<&zcq0c;#W2u9I70TQFGafrEa*@bXx=c;gZOGuG#M?c(#yur=1;rHp`* z+KHc$o?0I9N7XK1=vOD>I8oo1NsE_ER`-xy&SvcL-ItjFD6*yIn$6VD(%OOLZ1ndK zrljpW=xM&@<(k3KCexT#lx8C2yrji&I|uTz%Ebu^k|z>1XYSfOBJ6v@T|Th}xZL<| z_YuN5Wb)W@!JKc3IBFU?FKDEMhy)z=l6B8=biy*4I@g5doe6u_rl-SQdSvWIPyy2c zG%78|Em5=K>D{_=NH8NTkr_(-?^|C!nyK;VNNdk&7n}`M3m_CU`E4RQmcJDuH@|?p^AWF(cJ-2c>|ULGIRnIY=oSP-B9CCkAkzj<=B@1ZZOHJ zm>Ow?pyhr*78jln6H&?zj=hIr+m`{+i!6BX0ZQSu$kyGv|F9g5F=g_=^uw;VcKfv5 zKfFIx^g?lnsdWeN_kK7|wQG~?kxGoo-ny~`Z1(vl-9j8%?kB6Egs?0_XNsnZ`h}Q; zF`?&x+#L3D zZtzU`k)sO(iWd+>qrEZePs=x|gp!T_|JYlP(2J0@N?pb6A=dh(;MrMu_^6NT9NgBv zCUI002?|4TP#afzoGv`AUeB7DQDv`@#~hRIIIohZF$AH5(WB5)XG+j|bSR#idOj^+ z=l)XHPgGEjsq9mOPd&E>ZK^&$;pFW0cCGOKNqY>vROqd9krfqy;`WM@3X;3bTsKP5 zm(vJQ9BrsWe^er*0AK#Rw~;}fsg?m{qztiPoOJw`Mws6?yi`GzlV{r#Wo=O_&W%IuJZo9_hqJWu^rk$ODw%QD!qpD&d9o+Z?S zc-0~li|F6XZNTrx+qcKlX9i@l+tt0b?<9C(>&4i3KS)ToGjvVDkAs#DcarOL*qegDH4d#?UAdfDj@UqRf_;ln&`OvOdN<@r=3oN8J+`Hg_;5)=qz}uO)Jg%CmHk#L4pxZ(?#%P*|))(5@T<8uy{dwl& zi>l{Rv%`-Jy(!bmro%$M1r>Ua?@+T1S*KYLE2ya? z`C&@qk@9Uej417`N7IekD;`vfJ>ZjXvfWc>bZtCbdD0~Bw$Y3XsA^H27brWtr!@dfNtNzhUhxcHni1=NM zMck(lqu5y|q}Y{Ng`GV$Lup%H*b771EP}NdiWH31g8JEC(JuZoOc80pKQ=}`l^C+h zF}Oxu9!f-NR>hsPNix3G-Vb z#e7HZ^B9$zO++${xo&w;B_unW%gbD8N{=Om4{91zZ_CC`KBn+g7P`F{>q}y%bMx)^ zC0gOF5nuFm(O9!UFzx2~&b}~B%rl@zI8&Gh<3lVti414vOjxg4fpv6$99WTflOMZ6 z)ug1aW^*=9#)gxS37K>uov3mw;oy>!?x;YT*;2s-MzJ3w8Hz;*MNUUM>r`P)g`>qM znk_!oJ$(E6@GgS0{m801s?&Jv=!V?7oVHD@Mr`*0G8Z4bQa$j9_;yUNkm0%pDeV(941emx70a{xW;A7Z_-d;e5x@r@E_is z)Hr{u7a1V)13E0=3@+b=z*1srYPSErPwZxm;9^+CT5l()gxt!`;2GqOjl=DON16tS zz1)wszK@L8@w+X{Cn>5E6`(JPdF~c3o>mWMb9h;{ykSm=2gy|zUA>?9y2kk{aup-j z@3x($jew+QIkfb$dF&o-Gg7wY=t(I9)R0nMo^mcSU7^4l?omlr*6!%FM?OMprW)+* zDTcs>vgbnq2wu?|p`mLCQ)rG)%1+7?0BJvGr`Qbvdup+WCHJN#l^ynC$7PC5aEM;| z!PR(}RA8jU*|j-DHND(t@{@Woy95SCaNc{F(Bs28+19v!{P( z7237zxaIL7Zka;w0~pLEaZ!DW54j%x3oW?xYr;OzW#q zq793PWgjBeW09&4%G3x#a?L+H$9Lr-;6|oo8O;iNo^T*?PH$+qz_2iiERL|Z4c;iP zcRWlXS~g&Xu@h)2H#6rl=A{H@Di&#|_Gb*bPDi78G%^r8D?{e^x+;X;#jUtHW(skx zRgQE63OZfD%hIn;jZM*yk-e&^bJ$IA{xDna0bjbz9GKTqTcf%2+W zqgu)wy=du)D*J2y@~$p^I4*yZ%|kB9$Ka-M(|5rN2nBsqP}`TZOoU_xG5m<{%m;Ju z(j;y224?kaL*;TlWX55F5-oVOLo?QAk>S`s(U-VP2NwV2`7*<#08WW=fNQ@Ie{@^XHM>mK7)+iGqc|6EuA z!q(yH);ir6joKvg@n*6x4_~Z9>q_cEWDyV}Ehf-OwLm(st8%q2k5#5 zj>6p19U<%_BvZ_Fd)ZptcSO~!VID zziKsbTxJM+P4dy)0a%M0rI$R)F=H2Y4z@JDN)O*>zMhQ7ypt}Anov%Y=JD%Vi_W#i zRG{haBLxM2Ik(eXN4@jQ=WeEV_z8YoiY&8{#|FiFj`A5X0&!z5bI_4RLy>1Ft%xeQ)u?lxmFF7lonG!zOmdn%>y;o}NAiKg@nojYX z2MkuV{pSVpv{N+ip6Pf#Aexbk5PJdiqbaO+O{EymZI3D=RiYPSSxiN5@@`{)?%XfK zc^kA6$vrNS`zt9En6kFO>)Yqvi%WT*Y9cb7SV#=*?1*$ReSF=nWjkc*!Q zG^e_yCWJ%GGMSUC$IjYucdB{OG>yC{yIdXG4InT*P&tYt^zl}GtXytcbGiX*5epZZ zte%or$f@47#_KQ)$kwf3OX`MNO;5fxqrrGXm)-;-F8|&G|L2{)dHERg8V)@V{FR_e zT(89N1Lo_SNSmT0CuoGk1hmeSbIU-<qsQ7E00%RrO%sLfZq zFG_iRemrEmC+2#7vB1e?%QD%0LPhYpgOkT^M)p`m|2UaZ3BQ}CtakkBQvA~IEOTAu z*@aCvtc$s#pONrlun)qg28(8)wz^JvEDfD_@Jx|F+2hEJ@ZB}qk2|E+1?G|Jp6XHm za7+LFU5T8+W4iY-WZX3Qw0xTa0VnxwrS%LKao1%2!<*sII~c&HwjVy*p2B2J*puAw zA@sv5ON}5^)LwAjOm9x2l83A?DtrNxl1@l8IlFt*ukFVrud|b>H~eI1ewQfDyey!0op>8)1x%8$ zL3+!mmu%%f?6BDx7{loCd<3E27Fh+}e7+*FQ$w`U!#f>t$!%2N+~>N35`= zKct(kF6c3e~RB2E|DY zD=M%p3wLWB`j@@(SY(GF*U(t6w`q-*W&iRQOeiJqJC)^j)g7)^do!P2M=kG_)|iEG`CZGqovNyI%oftG zj;n5hIyPL%wcSF80;AAbZQsIMo6{ao=tvB)W$KG^)1t5fqmDy$FSTI{t#8pg5>>ID zG{$vV_EwpzS!FIhu32Js0n|6jzGYQCw)WyB8*ZAVU5CD^ScPtlsF&VdWrwUw_pYI4 z^~EfcEB(wOSDm$ox+gm(cp!a0tP^Do$dH|ai zA=PRYJEff#QGPEy%8*u-K!}i;3k(8zuhNHQm^*3oDa#N%$Ys)i{wsR&KF~+>3A@Z* z;@KhLqsf`ip4WcS2w_{BfS4R(h^eVl3lR~Cx5Nc%nIYQ9;C!oE`3+3fdrKp+a@RbWuUFC1 z;rd8Sj#BKs3>nl4)j2Z|PuqGhAtpiVq^tW>xI*lHi0 zKUGj#ScU8VKwU&g@YhO9S5FoZ^u-9eN0CJ_)h2vmbV+2g+)3uPo48jD9My5Y;8g;z z{cV%)=w&`-nI)J|=Z5LHF{Tnm<}-dl>pjr1sik&~npGj|Kh6-PSM&|OO)1_vqN!Pq zpL541Db+rn(nr0##h9sWlsypP4Qk}HXj?p4B877)S+&kO&Jn7ZE^hg>vtPT`%Gn(N z@z`X~PRzZc5$sF8l$v03d@eyeiud1fi#nl0D03;*YjVTWF?J1%vU;+rLy#Q)Ssd!8 zG2tS=Gabj3SFqV=Bu;vLd06=K?G!Qh-XGNE=>Z4_+R#_zuCJ>nMNLWQ=jJ2vB~Bzj zpk5`OD)dWjcYUS7ryAf|?gWX3J60{7RvJ3o*Q-F$ZX9vlJ2&y;q{zic{5Ag9 z)-cS;;kBPSD_Uyl=5&klUn*A^q_2in04HnwdcpZE*#aPKI>9-Wuy6@@mzI>;4sQ{R z7smJFO~ugV1~<3fhSOWb^Guy7dj?cPF`<(FSjEe>a6k4RrF}HQ+dEKbFIbRZPz{&X z1^cuuz#QVo+Ze;`p~_UinMSYsbg*xz|pBsfXnUj;4T2BZE*}To6_3F8895_-AxUJL|SE`2v|Pb zQn9ArJ~~12d_T|!jNz=+-!HnA{wrxel6G9CFiwbDpa8>JO!Kt2JBmA zU>C0L8Ae&3Kp<=mjT>?U5Jc#V%1}v*un>+8AR-4|J)hHpDMDVDZdoorC_^T>G5tz~ z4*>iq!>%v(cRRaV+oVFdv@*~-wb5kM%Y|U&=V^APt359<+9`q>D1*Rhy$mNSiXAcbQj z^CEui-Oqf{eTTf|rxa-k4<@M&!*5=cdIHt0>VKooo_IRLqk#}+0jB)sVY;4$!%H^` z_TZ}G*8g%0;UfYRYt^y^SbS?B;70FvIexxInADxqKCp$c6WU1ma-?LkF~&`EA`3S^ z4osLKp6?sLeL_?YSkG;kVV5l5fXZ#USnvWjK#ZXD%$%aPKR_^Zq%d7tD_Jzu# zgm7eGu(&%NrjbeyuTU%~$X*`GhrG9G{_jMrpDS|bM$7ltGxV<6z(~4f++|vy3Mo?_ ztKVgwV$m%d=qv%G13jsF+RB=){PuKR>o_dAyEx6eDi#$;)nSE?d9wvvX15lvIy(Oz z=z?Yo1!IWAU5IBWLt&futvk>Fix9Yn@8aXMkONLwVxV zU4%_2a`6?O@)xPgtV(}S&HuTz9|Ntpk+pb%1DIX$DK+pb%!`uE76KSzOm_lxLN*+j zbxJ-1A-+p}{X4wJhn}8L6Knt#_Gzlw?NZ+bCR64o-b zXXa9@fKP`*sRJrUNl}Nwt^M0l(L5`nEt>9lEwq!A ztf4QfaaHH=4#C$HWW2}iw4k;Nl<_65E5-+a>7=S==*V7^D<|6inWdN6H`=T$`v zms$RtbFnw}DCT4E(d)IB5u%6@GC5oz5n@%0zxUm9f;yqVY#)zF#=TASXd#K>xjrdi zVz1roMEazk(4Z_L)P<>ENF3{I`l+*S*P*ul4eu@9b(sr{RR;flHjvfjKE@0s%eVSb>b%bu4}$}A zn?y4Ompn!jR}%b<1N`vFMZ8}U;D%hri8TRIC0_yFpT1}30*T;STapJJb(Z3=_e0nd z*+4BgN^^G)h_nXEA5?2$+FQyUE~ZkS@6e3=j~5^V%GIw3Iqi{v&mcjo?mefa0W+XC za1|DF2`07*;9mA$?Jl!)Ax5HT)(1M0yXD{sEJ9_oMm3&~=q;Q8y6F27a5}n~P+sTJ z%2#Xg=&}K)x+A{wRH)-?7C;zUjKo?2HMMz`d;tdW>Q_a`*cxNVWDyehUx0rz|LeJR<)#*giCWKh8{Hi&PkxD&5lEP%qwO}z|jWO!lGIU?K zXhELOLN69V+brSf*z?~>T(E&Oss-Tx^e%h%W_BqegMFswa<+}TyxgCVc>7&GJ9|B05t@=2@EN8QDwCSIZ%3GRf=3sI+ zZ9jMxcYkvQ0&OCf#Myr;9YoIK!y!F~zqV93P2bgN1qf|ku5jVdSLnw`1Es+e!7 z4w}=zWOnHh6QI4Ofo$FE7BdtNF>ono|Xd+LHxNCx;a_|x#s?L(C5I7!0n;l>ntgVXPswQ)zL%157G zNQGC5Hd4(?wKc^C#UdAoQsMV@DK_H4;5HA`W9(`!#4g(n%GGvrmp9m0^BY%N#DX5z z2|&hOm0YFIirvEyn_PNTxa6)wIZK5|HE zZ*7<7bn8Z2A>L-`REGusTbNXo7m~EryFZzK0yaY;4KNf+co`J%i^uwiPX4p)+Y!eZ z(#pdr!}$C}bUW8XiI2jWt-rZ!c@2({_^ z+qrCJwzcf)>1D6UQY-=)FYB_#LC|HeBiiG*9=G9c4=y zwpoU$^AD54qp^bVPW#=)FaNx=M9RpLY(-Eh-3uxW!E;i#G;LJi>?O6OH|OjROt1G)E{xQa9b+9lBbg_|LH#f z^Z;{6hd=T3;^kTkYIhbRDjTw!c3y%lq1}&TbVI&tm%8Qkn_V49j2(k2S$fiE+^l!x zP5%+QBA69LZ-%NF!$F*`RLS0T%c@(Ke~0Bx>?R9=ivbtvy8sB!1pUp5nV6A*lRcis zb4@R@*jAoBl24mDd+tITJqFPgIl~-d;rvp|mjSqB+M;cQ$kg=GjXsMZUtDjf=iUwh z^L0{cp6Y!k)4fMdep)2|09*`HwGO#g^QICW>B#udd%*Tl zm|ZUSnK=5@t-oSty{seZH{>W*a-|o5TXNo!Sfgtty?DtEyxxFUc)XX(to@7fDMvsf z(e%a?LcJxf_B~~Qkz~Rt!Z4a39m!>33{Yr+w%6YJ1Kd}fNawQhXa-OiZuqAd&L=0v z%xMtIH;!UN&4buY3ZQtnUEneg#@(cGDfL{p*@4+oCL$Vi zU4BS(n%RLzuj031#=L;Ow+ntl@N1j(M3*T^L+PwBdY@|4RxF6_Dr-Rt{^$MaT|x)XpUrkh zdEKFY1Bry7LA_cgc+PJ6GS6Yr9rFM8T9#5}`Qor7d zUY~)g$qG@E!|8_JC78Q-+sG}%89Vr?M*Kv^C$(SC;g0o29_t9#WaQT?P zcPu2~?AJ7MlaO&M&CuuCq_M;ZpCpYk?zi$W8`yFRR1H#_)9|(W4}~drvJIgPm^-$s zh}e2y4U7-Idic-d`PZel>+OriUj+*0ca%*zBLwY(B~3e3QVrw}#WmVEL3y|a>yr=5Y? z=26ADZrpDnGAiX)q5=b|AH`|_S(?r2?p=`IQaGSN%mv_TlTE(I%{vh)Dk+MH+sNv~ zfd8v-gN;ZxH0spf7s9c4^~cX$&5jtm{bjFlTzsR<&USeEE1jJJl36FaUIM!E%jr4t z1mb@Guf6w<=X#Id#!Eh(qM?XNN_83%QW+KXY0wbad!3ZBlf9!&Ql~*y6e*jGY&xNg zh>Xl4Dl;UT`+DhU$NByqzsLQ!@5fz#ee&TwUgJ5g=k>f^i|6gS{Vym;)ul{poRcTk z%IW;#hp2&_XBtCZE`7n=H(%9zPNY%u0`-S1j_BDl9eoiUn1URcIdMj0t=UsAfr9>z zt<7s^HVIrb_^-o_-=l7a%!mSmZ^NJAgoI3@2~Me7yHst+A?u)%YAGvUBS_uX8SZ%h z1zj5I8htO^j9ZU*8=oOvpg34NVgB-wq&}n{ktF{$Z?9o1vz$5(Hu}RI`lO(HVQ(uh zV<`?$04&QpN>~W>o@OZa-O;r{XzZ*fbn=H${K}$zv2CND90y5>fu@xXe z>R=PP>U~7lu_EHe7LYqH{7C$70o*h?q*IuMfz)V}^AFgbd})-+z`*Du$EySiU2 zu_gZnPvfi^ze-hp_7sHH3pbb0(=u01Ud8;^{hpc zYul-Q!X6;V3z`y3nLZFjAXgNhEHwE4qsYYQ5Lj*ZJE|_Y_bG1@g){)tRlFmBh?lTU zTt3nJ;8xQmO;R;XIWGFJk+CG_jwfaQdA-ZB-_QSU@r?K1$70~gcNX2h_Q%s$f=0RkV?RI#<8bAG zO3jvcM0o%qs5d^_JpG?M=s68+sX_S*pIb+d%W2~D^HOlKRE5v(Uu@e}m2g97QT9(x zJ^1=ru*IawRyurj|Cp}Yv;cL#J(rhd>~%n|wwIvs!S}}76J;JqzH%~6Q01J+mb^Be zocb!S{s4Q>m^k2;mwCg(&Hq_xuIXCAD;o9v3EMwT%;Uu{--ioKGH!gf zU{W;LGSTmfg9v|@NTEno7FQeR^OcojrME27et(~_#ZUQc(7>fvUF~VZ(eu`v?&*Md z%Xe@6{eK@HhvicmrZu)6+jA#qAs*v%Oc_PXlLx5pj?W9#&&>HQ(E7z?kFjWSs93OA z|GM(>GwZQuAEs1V|Fgi|*n|9FPQUr$MAD=Tq2KrVcYc45;pdHlRq}gne7)`ezpf2J zf0$@1uYN$YCEn=1#`U42sGj8uKK%bn6>|*H#%xlfX>590qAG2C4(fgUqw9DQY28wg z@JAbA+|g&tIH9;0zUbyj;#XgAM_P4hvkF;8iu($^Ae;~)ZKYzEkO|_Mdu!0szR~dQ z&>mQvGk%+9jBC}YH4Np+!||ch8XE4D;wWawW*jbsa!!@d%!{s*Xehg0BD0AD=|sDs zGg7Gve9;-Q`AwHeSJU2@o{YrN=Yv2+VG3U^G$JYq_F>~Rrbv%ATT zUdfQh`I2W6_b5d7%Q!P##Sh>TLcewGll%0=((H$v5XYJ85S--Dy>#E9+_OjYRv$Qo zN~7D~G9pqDcaGf;9wE&jdec5h&Qo^b1t(kGO4vXC3x4`GT3izd`g9-ZR}W8z$=;Jj zo)h)b9+VPZ%3!iG`iV|@G0{Bd1)9y;(v?)toYzG^ml;AzrWeuTM@DU0W5>cDNAD-M zc2u47p1zR}B{kBm0B|Up6bTXA_(-b1KF@DdQ-xrH@kOgp8_H0mpGK z$cl)r9l9H~KNqA7BOx#laT%T$QP`1O0R|cif2rQ0Pp{vnal*rV*x_OVsc`>tn8&_| zmQLsLP`I;yflWsyi%(!|JJ9MaLm!I6&`=fbpL~dCpIpzzASauhXJ^Hd>JG^CM^@~+ zdd_oww5~b^B}~knTdE#q@FNG%yDW<~S7Hn)GA|?cSY#yIhcEnvyZ-jcj_(DzT;ZI&&%V)j40L;RVq-$uZlyD1p}s!KEMDqw7tk9oryI5 zR4ap7pzWe-Gby+>idTMZn}6cfFNM%tE_n+{tIM4J$&+?Ky-6QpYW&d4qPmOt-sWdQ zpD*b)sB)T;@ab40>bXf`FV6g29e8Y1zYP5PRSZhJM$oLevE@PbWi-0oiR41xQ{?1N z4@*rKIicxGPp9@xeDRa#9JNW8>>bgHhE&UY#b3n^vLnl(0{bLb_TJn@*k*e&(Buqg zoE9r`#fePG|1$dwdwi&1Y9M~U=Oy^Z2BL$9wYkvSQB(br6GSa>*XhWr#U{D<|F;L+ zOdb%EAuV7$>xeESc8^VUvf579HaZJ`vP*7sjGFPw)`M@?g!IZn)Xa)W|70oP-mCdu z#pf&H4D`TuHM_&1eD$b^gzyVuOIDwwv9)G;bi_yR`;%gRoDQJ2^t4DHNWmr7X~Xnw zr}3Xk(AbxZYEY6Vm`hYdCo%8*Z-J!a9%3e6kfLW5vNEQGP5#-)?|8Xx62-fMAtJ+v zJSm>+V@OEo5Wp4Hb(PD@M1*=eD&9l%u@Xuq1~4@8=oAQ1x_^h1j)5;W#EM<)7tk+% z={aOhCZa=tMw03xEPZ?#fz_J5lG$1*f@ z_lX+NN3=c?JF`ExW+h{u3J~&?-Z~eewF*1b9*QyN2XwiPo~vgI@D9?cOv=qMV62@r zP`DJ1%=#nxkyW69_b^UmtK?lE=xz7GhRkKUqKN>3qC=xxlJHOCPd@$lYOuy%TcXY$a^!koFn-XHK!qHPbkMZC8@kpxBy&2nu@ z`pb)>Ab0d0zhlfk^g+K;$@|*KQcLMpuMS8rMm<_w%&my-Ogd3_pu0lUOZcG#9kA1i zE&;vD`A-GwX9O)%4VA1R;(!36;cu`NvLB^2TvyS@E_nI?6+^6(=IfHHd5%pw{hDy# zPlc=aC(mNre2ObOMDOy=;Z|Fa%bpgc(Fv_tr-*1F{nbPJ96vO)AU?YlX+J6qY_%N` zfx6{&!QB(@3P)8Ik9B`JK`mU%9G!@jgtC#n$mGIIH04ZhqR>bt*#GTK&7m;m5QL@L zvflM0v`{zym2ha*trK3?&lxtcV z2uk-1-Uw+K0sVb)wIqCIoGaY@T*fC-z5K+`Y^Eyun1`q7(W6?ejb{Fn*VZbnFEqe1 zGBzaLy`anqie*m~I8$|lSL@6>!Kex%X3U%;bFP~d{?pTz#1GBh{FZ%{cTnLimB(_| zx=gud3xBv&+4g~KNF@$xW^$;lvLMHQSQyF6{4Uj?8PfYw4QyYF?DH+}0>#pFN zPFrvvdYTfHcv=gSGk-vf3;HcnlAxky8}w{_IMM!;UCm<}gtr`(nW&g&rs1ECx?8p( z0O?3{y;3PXvYQTEW3R6G@UFNz@t^*Uq9wgF;$;KanFD7!X|&{?9Pr;Afljz%1E3hD ze9}`m3@0rwGcuIT47ur?9|Yp$9?ooID^s}qOu?ylmHK400BV>KGA~h zBb5xw&v=gO!^5i`{<6**?an4dp}qVQ8ea`VSBJ5}$4F zmu!%oEF!6YjzSS(xUh_QR}?MZN-0LpXMDrr&kreBxQ6J>74QfZ)yfkUSG926bI_G7 zvqmBP=&46et>@>^XF8d3EE^OyGG8fEV=>?3V@=Oc)f+2|HsLolCIx-omm~8mo<6Z@ zMrCp?#45FGHlL=Q#;}@yaz^q&uQ@|YsV62)rom6xfBM1kZ|1uTo`XTHe1TPfJARF) zpSt;-l<4SarOhBCW^3!L;){k5UBk@AlB%uoygY=gmQl&ft*W@r!#&P8+$x~wj)8gE z$N3wNN@i%*pkK2zZc`571@fKR> zva+&|pxD$D>+WQQ1re^`E8j%47xk_MaT%PQu|PT`l$Qk_WR0atzfqvS+yLFyyH0pZ z19o#D`5e{UcQQ$W0+i6cp^)ocWh()eT1zl^C7UZ#8QYzee zEzrgn3aERwCnxUSxil%UhyPJrXpYckR{P3=ap zJaNy`(3oz6iZ!Ot6L7K?f6sMoHynP2{?5IejSX9nY5PV9`oiNRH>eoI%GGq5aaEZX zi<|gonAz2sU?Pu-V`@vEf8_r4tbQ8X!d;F?r*`+F8nYb!nYljOjpe!CEgcS_npC?= z5h|qpuUVhs*x3JE=0FLj0@jD)@i|A6wq45=DHj~?eGcu?1XfTYoC3PfvatQH*{Ltv zX~2fes^xKhyI(Tm+{)WClZviGYCT22S_{$-W-h8^NrYla&no@H7(D%|d%B#0+PnkX zhD=vZ^@-zaMNkWA;T2$#ExNti?c!hmoXPate)1NM2e>i+q=fcvP1tM~+gHgbQ9t6% zUUbFB@hu1L>?uWE7qNhsPh^}0&Ynxd@mR)e5d@idkG)I}7Sou{(5tEmjSZ1z_Hzm` zGBV6;&ERkuiex38oR=5ES?7s)pW8c78=9;0JZs-Lmmd9U{aWxeUp?W>2oKU!Ppt>J z&UIw4VB~_cv$JhU4(yC%5sj183gMKgyC=9*AUmFi?!IE8RymmBorYb5;4)+q;R(p2 z@3}u?80;jgD)2=*PA(Z_C;WPC9hv212XJ5qT>ra-dz{G_{Yr87jN+x2pv^%?>kJ?5GY@;om z=>!8rnbtT%r*;0ExCRiPra962- z>;urxR2kY4%H>s?gBU2<-=4i4Tl*l(`&DvL1($~B{M-|ajU}~_LffHiNaxO_A|KfS zZBeFBy?rA7>t4blFQdE$&{%f0vFzOoCe2)n7KE>)$}Kx&R^iE0&;V8qe{(<{Wo!(PG80kj)gE$s%ofoL^XDMaG~?EH@42(^bOdrWZ|kOeygEezO+`ez4XQ%2 zcCDviMKaf-7@v3lw$U%W=%=x}G##rg?#3OQQzWu8BN=-veoyv7>m$K>`s<8T*D)a@Zga@$ON36 z;E^TuX`C!Gd6yGygp+K0E2|`KtX}~hS;W+KmC77aCV#oSJ-JKbcD$Y)Zbct=g~rTF zKYA~D14IH5Dp!*v8qmR|WBRsmsgYgv!!u5{;6ut+SL&(VG%ea|+!|Y!1tA)}Yh@{D z5&vVEU7|(%Vl?8oAgbPFZKS)cJGRXj+rMFlgITT`*&7~|HO>hp{a7AjEAr}YMjz^5K;jD?h;Hu9*{m_Xt23H|r zpDC;!!W|~7@D^#*7CO0xoXS`|7NXy+AC<{GvqnMghP=>V*Ugbd2XNQ}Tq3L0PAlks zKMnI$kXl+N-OvdC^n&4ikUW3mUY_xsEW#!~R|+&@9`30;O;;CNy(`a4fTw7U6^rVz z?K2h$uJeU9BA@xnu$nkxT@bM^;b^%o9}|)w(zKBEuJKOm;bx5yYe3DnM0Hw=ne+!b z+#D9+oDRSZ^=k}d2Jp@TfHArk2F4!X0YGDkR8)_pG(j1LrpmfGtRs-e?w*8rYi_&k zn=QtWuPx&aHM#cCWu$A{$dyXbI0?D#213IoL1#duhChj;IzXu8v))p>qcxxt>Fx3| zd7Rp`Fi{*QtJ6A5!+EU^5()ZMEc)+!`<2rY@LD99-}5RFn2&GO!Kolxuz4<6{8=Pl ze_In^AU#sQZFu=dB(bV{B7hJZcb6y#G!aIsFbhMa=E<4I3vgOS@yxC6J8ZV~KXbc< z?t>@@fMpXX8_@$1me?juZ96e#*5k0%0)|x&rdC4wTw(?*|5{j$o4scpde8P|^4Lq+ zIaEv~Ows(5dJnCOI_p-uFYX5tRex^z#mA=?xIwf?)gvM}ifK|6){cpR56nmuq=bWm zlQkfH=e*}tQjG91Wsdc+YCYvTK|aSTU(8yvHQ7+^c6f1)%@g6%>jWzG?~4l8uY?t3 z@&b$ym49w{f~XmLB9>Nqb+rGyx4P9;=UkY4#a<<6Edq<|9Q>NOt7B}UL7+u4k}l(1 zuJ~QbOL+_`Js+Ncex2o7rRadRR!YPwaZe^4o2ut-!OJP7hELw^^IVcYD^?j7mw8#fQZHOfExs^pV3=6qqM%I| znHKH8d0lV~Cucp*%*e4Lipi?%>kL+S$DNX>d=(BD@EKH6s)8-S%Dn*X{MALl=Vsyl zSDi4P9C^2RCmv5)XGKk{a<>o0Wb3KY>K|6&-eBN8fd&1XRTZv5*c0}!WyOE}14(ZD zLBsmutO?VVu?-Wp4EfEPJoOzD*~YOyXuuyR{Cy@L-U}1zp}kXMY=Xah_4y|is(!a_MJLXNl=#K-jH~1| z+>7^$oX(HW(MfeBp~2{%_*o$W^(>Ro`}YEl+AI&?_Uo~)&I32)v#He6jchd9Q~SQy zkl}rwv{{n4ll_OV~qK5B~wKBz~=8WmaBKDW!*M0PtrG=w#W|E zkeCI%K*13{Us;n&Gm$Uo=Uq{s`|rEdaccDK1DX=9|0jgr@*W@t$kk4sI&NY`eK&1d z*|+%e%pyY7%YV; zVQ#AV&$ed;CrnASjGpFCmfYA1_~xrZW|%hv|2Cg*emc%`Nk)^raZBvf2}8fJ`~AQA z5{0RUc57oIVm#8}ALoOd{9)Y|Cq;lmdY zD&Xj&5>>wl`NO^>EqH`B9tJk_+bDR|T;6dUpgE9+Xp7 z>RvPfJH!}`wwXxXRohcNDQGBghQ#PP9Bg>m68-c@AsDka{cFL;n~6tcCTyK%x}_&h zONORa!nIcE-n9n1lkU`e>V-cEyQ;7u{d)V2nB%04@;ZGrLEBux0cWo@n0eiG(WdqB zX8MU721{)qUYP~ja_!3veQRXatxIu$XuIn|E#2h?1vcne%hVX@FS8YIRC*nl%H6t&*MD$A#jDHl=45kfcZSv93xp^T#$H1Le{BHQnL^}-6@?0 z;e%_<>Nv@+t`>?!TJhE9deRof{E2BptwzlT8!A0S$>K$qq1EjykBTI89WOskQ?~M| zLWx^U(@V%PN}9bx#uc{qlKd+OiEDGFl{8QAV1C{hz8tHMu0GVojx+ho+2d-gn|mL! zq+YV%eBtR9aIG8X_`SZX%)w*8n*;>3G&!);N;kgg?%liRAUQ6l7T#4BLst#h?tW>( zY$R&&X05#)_4Qct7ttCJp~;%omv2-TqA{e~U7DbCfv8_2&=#c|355*}iQS z4D5ycG)H{Q8=7b zigrfIf9WE?jZl9Vo>(^`Vc(al(fAbF2_7m5Z4lvfMa`NWGS$6R*JJtGk<8h7Th^WD za~X~C%~HZyKtfOp+U+LP`MBu~R9IgMzE7VL5~1g7iv+yH9sTFls%Q+38t!jaaG%Mx zd1KKL90N5Pj31Fy>vLG86PQ9y3N*(=C(4E6x&Cql8|1Zoo|wZOVKm4Pu%OW?2I6VX zIQ2z1`_@ltncZMc^Ho(6{1T$zsDj!?Xgd-cmn$1%7yz;!W7^NVpenP`_ir3!y{hV*q z%u3{9cUbW)*;6lsztCeY+3Y~-5o$@u6bxvY*D7AB%-S4g-RGh)xGc59)#wo#Ij>Zz zS2|l8Y*IM^~&<(dj_gt|Ws4Q+)gJEdFqOn2zr zvPPL(Q^wzokCTxlH3k(9 zOf=O=J$RUQ+M)e^+LA;*b?IIAsOitu#=YdU7?Nc|aD(C)N*@rW-^F%1r>j~;;;?Ft zPMqtt(Fzx)WSobZ#&DO!R|=2##sc)|UyUTTqSt$7x3K{87uTWkq7*f+tK}{0r)ylY za!lNwf^(N~g1Yc63=v+X?;YQy@gL;%JTx)n-Wv1xh3jd+EpYpQ(zob-FMclCZsjbc zknvyTs2C#RxaU2FxYNdy=>#JJR%mqQ`o`^k8!71NQF=Z_MMlyH`WGVA4nC-&jkiP` z`{9tg#jnDfuy3G&MNwS@B=N?(h>LUCBelsZ!nud_ErrD#_d-;u>9S06My6-T%}V$A zq1GZL^~$X?c8AFZ#~IUNaC93#)C%9C)yR{@tTahV}}T?oFWE$w`ibMBgP(j~ zy*beS34g@fPpdnu`M2ri@#bMNP5x@+3>Q2+mr?!t$a(kGwyrwo@h4%Z2$ki$RR2DE z`t}hVml3c(dipaq8rtENXwY;brQX|uq@ZwjplTNe@%mhbM|vDet>ce7yB8M33vYpx zm6CI5u3fuE$?kxjx+rLsbfqC!15_2dX?3xIsTQA;%WofKY=`y2%{x0>{BVi-gib%H zHI9-E)z#PKhuziaN)_a6A>e9UBBvmyhA_^kCfWKhms%vqFW2o)qt<)$Fra?zE)Khko6$|RoegbV@Hp(6Ce;o}%5k#xBzwo4>XzT{< zqF8OIj4o7LUx%r{MAmffI8D&=n&24W2rR%lQVM%&^^EiThr(QhD#mTpF6b2tRj=+( z3Rvqo(xWj6b7dXcnkFMqLJn-bY@d({WiN4qoGy&!YB5K2xr+8fi6m`pwoxG&;P(QP zGlXiVW6iIQ1hT3KhH{M!bl)428}wuZj~4npX2}yXfD(wXF;rbL71H`k=5MvNY+EvE zG}{5!i)0MFgG+YGzfq3`2)vsvCEr&#sU~FP{n>4gh>`_lk#kN@Lb0*uEvjlM1Jc`5 z--P6#2v+*C$xd$Ooe~N?g}J!N?q0#WB^wtZ_X}wl&jb|N{qd^8pCse+CCn-VAA>eNz}VL zUd)4=j+SQKNh2>FX^6Gn+}OxLb9niC5&=`PJ>|oa@LP32pm{6{JlAk1zP)7$#ZE0S z0YbGdABEN0BehvZ<4cBzx2?Q zlz+Hix<{mHzkpOJ8>kh*O0sso_P2RUmKZ;pQ*u}WMOQ1wf~_OFpT~4IuJqFXdtmn? z2oJs)wpq-tuNZLbn17^UZciTTkGsKHPBWuww)3*9W!JYFr45-AHiCJTaduqG8SGHW zl{DLWGiK8bCr5@&C+=Smfnc+l7F0+sGfz)|Q$OyQ%%mM|#nj(-B;UrH>}jeF9No2# zgA3Ul&F1de9uw14Nd$Qn)U6JmG_dVSs&xg9p9M^KlIEde7txl22v~Elc-xRnb)9mVjx7PgZC}xA+?7)| zyPQXI5<#St!OorbLp43A?kWj96eqG2E>bI=ZXUAYMVsXI$?{e6MEAAW) zaM>E3Hr!v8BYWESo{F!06v^u9KvFWO4o)tcH*a1?zLEU~`|c18z6U8SuuXM1?=SCk zhxF>8M&{^u0>KewVsj|d-KElNY>CWs+dA3NNaMw%z0N$NPG5c}sH^X~^m7RL|m5B2(2d^FRE zSG>8Y;i^pVNvq6?-9vCVF|FD3vEO{_`R z3v$_|Nd8PL-|^(?>>c=U1AJU=28H{n{#{HStlR8uQSO!ZCVdE9HNI^F6=kW+|CZAt zONHh9laMC~N(jC>C5Y;u76>P?ZTGCAVDXIDw5wXvy)!8j_q9vsqvvI z7vZ0+TM}ro4ayw}1=!-~b`Z;^d~X=Oyf1ar^tBMB3OnP)+(F`ju$xg3g;_0~9#M!S z#H}g#gGv5}ryn*XWi681b|5q~^aAqA2K%WkhCAIyu?VOo7}sbA+uPrWmtIP4 zcJ(wyL23W}?Q@SNQ~SmARM2m9h?MDpceuLJVXEPo{-8`Bt5){eakVOUFJLn zNn1dY7Ho<9M|Wt2P<#GO7AQn*>S1Zy(e27ba>0x=eSx@{Jzr4VAET|+3XW%-thTg7 z?py@zTLK?dh0Aj=xbLtsbBpPc>))i6T7PNhtn=Wbr>VS{KnaC)UXpk_8jGnrBP^IVtYB%mx zd32|sViAEMDyrH@aP(`Z>`Z0XSQi0*bJ^T?A=nv)e}r6rt4-HSgfM&dzDl_{_ zTB-z&cPG$In8F>oF7SipL)NMVv_72;77Dn#J5n}NMsGr0SI{$l)I@%*a3zh|Nh=-t za#GKfRt%4IyCSifqiCN6-2U+}1s1x-Krb-%6`IvqMz89(&+k^#BZYC_WAqiNdUOGW zD*5%;c7|6Z)#a9?0$RvI+ja=IiAM9sDDA_@+Vs>ne}cSA;7m%GV9S4;yKjEtSju!a z>0k{?%C(*m1q0zYlW8C}hn21|*660g?T0a)H&2px&QU?;mi(sn?F41)6I8G1&u28w zM1V|$W=CBLK8ioWGD?(Rou{{6!kVS9*!U9lqO4=4izmWfBE<#w!C@cz5^3Y!6e7^b3MTF z3dBVI$soRU08+>z(I?rrGv=>jM~#(!tIXYlKqEWwo0(upF|z7MZYOX^ z6qp7g?%Zm0!neH1JkX(PG4F)b{x7EOS9{^8fg^Fs027yxh!V<|!hi`Dkia9%Fd)pq z2m$y564pS#@;n+@N`ntL4|0vpBqrA_DM{Jmp9-IWwAbOxH+x!OlMJw&b(B; zh!lQ;-yyWLD5*~+xlQ^)+E9=9sq7`An|<8Db8KXWjF^aFY!c2#;bXBBt9;CFx)#nt z0t9x|6A}Icx}|{@gP>%XghC1`zD`X}jjr4W)SD<|Si!gW?8W~|i?D0e>i`KR3#ion ztbuBbhU0M-WMf}d!`3ffhb+fqvze}Tf93Ow_JDN64IYw!{2S9Sy3UWv6JlvLU~C|5 zaYswd`Q+_sI9|u$fU4d7zPfp%Ah$wl=QT^564YE>0|aT$0Bsl8W&_KXXv}HZkAKq7mbwG&^8zNL7H{p+pwjC}Sp@!L`^}Xj9`w*jBgj+_& zS8^i_*LL03ogJYrIy+eHkUWr z1foz9dP8G^KC%e8o7^O+Xo?1sJ<}U+6A2tcmyl=+y2tqso1n2)2aki4>cQ>A z@Wv-2!|fw;kA-v8VeMhMf}itWenWr5z^2l@8aJm59~?n_z0!cM)fU& zFPGnL?iW^$rGK~N&x2lOMQ+U4yc+{ga>o8{-nO9Q(7xlu4`S`(jWo-iLJc!$+J z{j+T5=NKgfml8;u!0~-3#N1SQ!hL!>JsSuid0_!PfZKx$xi0T;)DcNW%fW+}!W<9C zxfPF4M)Cpcq|KGsqUvR3qcgG_o^94Sh=z>bpBgnCiolzTg19c?NX5X-9v0;z18>R? zR!%l}HnaVw?uxpS76;(+ii=b}0b3?Yvo;k4i)}LEgU4 zQd>U3sQVqIETn59MKe-lMGLblTnKaPeA7?^LSw7Y=aKkK>sMSrMsx5c+Hs92|E{fH zIZXCTlgHp&7qIr1v&0miKG@f_+)g{s zV-C(mq~D%W=NnPl;-jgqr)$H4hw4N|-C!X#UX0_{LQB|!O}uE|_LWjnQX=G7$8&I= z%zP*P)TIu%jgq{mH>M*we{qU+JaV?<4jNMRG%G>dRY(EY6qm%w%c8MI1l^EYFf~zN zG3(FT7cn~eR8a(m>(@*D-0c6mLj3|M<}khl3NeXzfvn~>5MHjKeXWd-uco8)cM#gB zH=0Z;iejLy`3#ReU&!(p+16)fv3cI(eYZ8w|!Idm^?YV3as!8Po9(sLLfwiK<;io;g==P zw3_hh|MrwPIT7`JEj<8ZtB)UiMxSX=jk>PAo%!iEw)!Vg4K)P7ET4}J(mM*P5?H1g ziPGV#%Z%MSy%(Zp@dCq>TjTwX_umQq$rVO#cSx3y;#V1>1%<+@1}KnRX0*!wYI;k< zVW~aX7|e4R^7Q7&yN-_};}@rGPrg3F?XkteFvA_{VIu;EAH_CsBiOD>G%B*HQ`pYzyTdhp)%-;m`roi=*VoxFO&6)S5Um44t>&vBvQNp zV~;-kKW*c+qqWnt!1d_B(FIvJ@Nxl8I#(lEm7Z-jSnpaPVR6p*@upFh^4;hIH@8Yj zMH%WX2)tBFG9gm=k6EwoUk_2n3+P_Y!f_#mFMIY?-1!KWt22_M6iFFlz;%tO?dEW$ zPCWt8+^#g}a2x4$qqOgxSKIg0;`q?sjG`U87uLi7*8MHU&0#7ggvR1gKFVx|-hT+4 zhrR}F)stx&))cmNZS$ZXiP)78JYQh!O{o$uugXZACy9#1@RiD8fw*$>NejL=Qq(8( zwu8f=f&+z{OhvgSO=9|M@2>5#YRBt^n(p2vl|j|zA`SpuL0m=^-5HJxZ%0#(b7n3M zS0*S(l3|Pan+iwe#dXy^G5KJoGeEptLVM|9wU4s7MW}9D`$}eHiYC}gfR>fo(XsO)p(V3Uf zxEW>sq@&>s zygOkO^f{!FGw-~N??9EXaD9l|7XrbYe<3jm(}}|g(xXD zMwU*HSK`n>n+$!RkdW4wy<4b@5GYKvRb-qYP+|aSE3~b#<;8t1P^(JH8ce07{^|-l z?rEg;IdVFxKH0&`Q2jvIPjk{wTknvn=1EuU-6LurANQ{IEFFSz;sT&s79%Po{&{oy zU7&<|C}dqRdOOY|byJYLvy6Q7njUrN)u3XEuG|o-@`KlRZjP)QexJ^k5Kky}Q)kRC zd}tI}ZM)C`tucBmiC+k8_iTWrb!#iw)L4pT)LCE-fBpglC{SHtCH* zr~mG#Lp#&u<6d~IN|_+I8QanXqCup3=$7e~ahBURUqyq2?Cxq+G?r(7^X1Q?$;amq zor|vACon;<^LfbGSxFrH`z1aP$S*$po{3-jk*}@L@8$G;RQU5P`+GV4UQWMsKfnFN z&s^J&AC5VqWUg1QZYlh&82}Refl_0oW&Lh;(X=mV6bLDr>gNwce(p2%TqcPc&rol3 zvG2XD7C&~J7jCARH;+GEmrcj$OSPa71*w&_$-c^CY53Kv>4c0+D7AZCpJ@JIsg&lF qqi9YVrCN=mZ?1X-jY-4X`U($bxxgp@Rh0Z0*Km-KHg4zStsSjh%-yW5m@K@Qp18R^m*C}nZg1}B z=I&t6W9j5T#wSh>cj&j%)^q#cKR+;+B9!!x$yirxjthxb9zL z!f>)sKKO9!{$SgU<_|XUYp*%Z>YveVDP?1ST1Nd@=b!BPUY$d%+s3nX`RJU+i*)X6 zg=^7xYz>X(mxZk~8((Q96DB9v>SQ^VkWcuYeYlj65LZ9y+gtSSz_O3|pD>Mh0A&^5 zk1rai+G#DZR#s%I%3Hqs(U*}or?@QRlwW#XmUHf>(xE$jA|JD`%NE3yVx4b>z8WT+ z`V=7S?*%fb=HdzBQA#lMzs#3u5hv(|;LH$9MC zb@O(Xykj#q$P=DrT#?o2Hl9Ldx5w_@Gq!CYlK9=IkYBTUb^EUVJYw(nM24z2*OdB% z8LOMo%&Zvc)6e7bRcarxYNBoh1*xtxiv*8$YN1g`{T z#89^zjV+k=iRu{-@6j54%fAzNLB^V0H0%5myEvcCf}e6IdBfTytsxKI8*TAuJ&P+I zT-pA6hJNRy3l(BEKgb*StPF+`Xsy;s<B*7I>3&vf*yXqH#=bhlFsjI67ZNewms`VWzC0a_-uih(S9jR&Xtz`Co-Fn! z{Fg$H^*=7;$=I10*S$641O3oYdK$rg#Wa}!Y14XN7oxTt(+2-d3NkWr9-Hi#r9X8w z^e=5XGGxxOw?rl#WOdMT)>*<={VFt07-B(j!=i@W=5zrKI) zrb|s;7W)n!x6pw>x@;$Xa-ILaIRH21u*nv*fF((KjaWqQn{bg~#Nn#YjM1CS0{HMA z8#Rowvd(ZbPLl^OLpfA?6y{r>^^uV!wV~ZiYIDWOFm^o(d2N$z%*+CTh{ctCx^7w7 zHa_IynXJ4#uU^SJudTV+t~ghB_noaR!Yfy<5D-ZCA6JgYhIZKTAr<3Um8q*jLpwP6 zk&10-7H0B93=3{=uJ$NI^CMBAmuy%%6EU)~7X+iNdK8$M0}+Y>HY{YAZ)g^TV05U0 znOrm)p(x7&xBCBo{r~gQ(cHLERL^Cdt*tDJl}yBBr%3x9242LEtyx0Lia(93k(E^q zMkrP`DuMvu8S{05H_M>H}C*0ck*BoOx zH10df%3@U#G21dV9_u{n@6Or8bSOAEIgMW-B#fbhki|W+(5f?9|BtJyYfK?3G?hp& z`t*xcC%J4^M+d)UTgM>WI|S|>77;;(NJ7e!jK}}aWzsJfEr&kp-*I1J(Y;0{&S=Bp z$0Q*k;q<3=Z*3xmD>O8fR8W%!fk2Rx3#jmhzIw%niVaVtB0)hI8`r#8ov88HbbcVK z`mI3F<-IdXkqdn7Vw?)XkSxZRfo7qL|dmILzg#Pat zQzvr>G2QOp#)}76kj(AVMu^d3(+2sd8=Z9wtdVy-*38sh;8ov{GIqJ|uFv(RWXVND zNAWScaI3~*G&D4{a#b)j5;eh!Du>&Ph82#VVm&=Qt-4|r5tlCEM zN=iw^k-zucn9k&T5JJ@XCDb4X0h`EdT8|b-rZ+R>jB5i&Z(k=OORo z588MHl-pkWc}eGfFHzlU}NifPD&1O@ju6-(H@ZV{@FW_oE{Vy^E_C90dh= zLTjVtc?#S;tFiYv3_d@ZY6^C?YcHB3fS5d3HPViyU*%{Qj)?zn>mS%YT0jyFzb4}1)`;{L!Mkivgeq;F?pMFA=AhQb-EN=4~(gYu|I~6Zh4YK<(ABI2o z`S$X>so&1yO>F1bmuGKkAjs|y!n(*Rvrw<8Ci2~cz0fbWd3^So&m6HhI~ylp-DOne z^6=rq)_j4@t~jpHRd`|{BRquw^M9TaLL386fj~yRTl!T%;iwBC0`V10K()EE(>l@k z8sD}v`k~$EXS;#z#epop6cLAOHqVAWYJ4D%$2>|FTI|muOx{_WxFZ*b8LMz=kAQOU z0iLm6%D~*-hW_jn%EQRWIKDp}&da8nI#TPkr6zrV{Zr>d#ie8a^IhN*=r3tR2mzs| zzphkxtc(N_9c{ET4*qysf^Hdr^%I0=u&bqO3%LBL^{RxWCEBrMpcRbnDCI}4j{T51 zLl$l2+51tyTwTonc;C`H(KJ^%fy7lwBjqo;CE{_R z&U@C}5+yl{kT5!=e5AI_i>9EflL2RS)h*_HNEAJtV1NB><7&#JUnSVgw99!sLTZ&X3E?J9FK%dIE0lu$YgIKh$c)RRH@MdhkB(*>VY6B$?!CTzGoz(K zfD%6J;Z!gojfJ!X(!4)gQAw_CVe;ied)Ps1NP?-UsVj>wU!H@uIEu8%o}gfSJW=aa zUO85%%RBy18dU?E{z1E-zv0u){rmTSvT<-+sW>@4&PJ#5TV8%z;V_oVqb~iivUp&uXT(hX>TQgUwlr#;bM%xjVbNI=}Cb+pu6PE#)*Vs^Ie@8Sbd2OD?`0 zentfiIx+&G82cPLGz15WlGuMQBxj}n?~bC#BN2+&5xDMZ`+pZOGYGo8xCnb!NA9DP z%Vhf6;ncUWGw4wIPzr07d5o2FsyzH>8y1ZwKmo9G(Hv9%=P7Igo1HQ2Tsj{|DxGIi zM4hk_%w-fk3YkHIJql#FQ27DqsLZ-M+km-@7x!~50rI{|Xguo;XVN~qEBa+toa*ns zK{Croo%KW(Td>W zUeeU=>KJ^HTHLM2U+qUB#bTHrhS5uUsy~fUi1trNDgpFJFYaQ7wDKa2QOM5q#gbtr zT$a!(8PX>UeOXcT;^fz^{mVEz#xEx>2+V|ii?}Wuo_=-C_j<(xkMDD|XM8TWR$jwhTY8p701h zI+hXO<|g7tIYcJ9d3dZ37SdRdtHp8Y7D3g8b@zkjlc$>Iy|WbOt4@w_aNR}A;)n4N zY4Ce(T4^N0MnSs^9YYA(qzXS9N)ohHis#mcMw@oW;YUZklKmYp;phh@3Uc8u14{gu!2i@XG9+RZY2x-y}Wwt*e9cd2U>_RN} z*;8kkjzeD~vq?`+&%9Ke@3z?A_B#t9;V5}i^QQaKFE)Yx!9jP(ZOy6iDpw2!%Ei)s z`J1n(}4{5m(Sa9OkS7G@yj6d?6VIz*tGuma?|2b?Qq!lldT^zG!(*Lpi@rU0emaqX%XRs%g{qZ14a>^ zU$m7EjctBI3JkW>ZqlAdjbisVW(H@Q!fAL<50`mYw1}SEdi)`%qec6McpbEE$++?4 zQ2UqVwpb`CnVFftzdD5b?=}S!@^36Yhu#xHBD(IwsuX*TSoR5OjGVg^0>H98@}c@C z;~E{xr_w)KP!t;Zr?qICa@xV^@$qrKMuP@_zu%wjkj%_NW0usR4=3wJ*atm(Id%DQ?3chPCFX$nmF7%NSoE` z^jKU@5QZ3;Jo6P3N@p@G*vn!+Jlhy8AZ5>-dAt9N3EG)8|xR^2+ ze|i2QpRnCX$rRk-$;T6blj@$+EmxgI15S_I1j>L2On*`4qf$;1u!bavCBG!DWYd#K zmi1*vNEc~xdk|Nh{=u66{cCn0Hc;b#BC(rh^prlDiee83m!Blqpoa%ju(`@C0BIsBAa_RWNQ0F&xb|&h4L@n%wi;RbQ1ZPj|n7t|hOQEsJM!*>2}2jcre&#<9G5d2=uz13?Jk&S+NUGzs@oi&ok9C|+(0 z6wn5m3jX5Oe%((7RF+sT=m48L!=_mg0!{<=xhC`k4F_{6kRhm=`~|m6q;P3EMYbL@-+C%;r4*q1~$WQ7cs4`ZHM~^zJ?rw{&fKgxrpn*GfL9GxL4aE z=-$77-*B>PSfH6xTUW>5U{r4Ni0CXpF_wj12FYt&9dwFE!Qf_l@iLM6X7i;U$dOE} z<_up#wcpWKqw4|5KU_DaAF7=GVomN<;j@ogr1Um%M_r;A7voiY?KJ{m?x!iBP+~7! z62|4ke23&nL2d(Z6!jjCUj0J1CWM>P*b^8{(7 zefQx4tR+uDOIsT-2z_C~AW@2Y1boqvs-75u78RlJi(|FkmT3v3Q zx~#JSv)&K=5Ah0|o$YADAk{Vk+vttY?xlC}yx zzh4WBX3>xjNJhmbb$rwDHB!u5(2*0ID{tDIYX*UcMD-uhT>| zE2Gfv3W#UVhKn2qKTzTBT~fjq+Yu3}@Z(fKKtiG#dildJO8qZSYhfIT>R!-WUhq12!A8nvBE5~yKUWzWf-P_$wNcaH)Q$}!+c5R|Y)ML$vsKnRTmoIScp#_Ta zMGOYW^zPo?+0+}xrsn2Z30o>UI*6F*)zvg9pIvV6#A{GsyH>eBK@+ubzH#G*vwv9P zN(U?(KJoRS2?N0V@R>4xhuV(!uvRNf$P6i;p>kU_^mC|PT*KmpM|f{k*DtZ& z8+M{;nYG=*cFrs>8-6nQ@;&X&4}j2sbeT(^{>r~8!$f9=*K$-1sFo@Kie<~5F@u_$ z+cuzA<+xk3>+22Ar|zS5W~pT(zrPUN94ypr4k6y!+*HcWU@W^sJHdG81yRf*G=B3L zj#*l%cQg-lZdOq9ntb$@wLnOD3&lSMdah!~Kh}|UM>O6fR|QeOzLXEJbPzI2RI~!H zc7{xVNfDcikw`K|j1+nUplCw>NpV#u4{HFyG;aayQ4}0Ior#ipi-D*DXq3Lc8eURT z^6lHVS9pXxhF?`2A4M_?2ndLYjf{;Q)vVVy>k+>eslvlFm$u?)Pe@J85foc2fdC%} z0KlD8xLQ?Ii&W{S-`qAfHdafMcnn(3?3g<#qjajc>m0=WL4D!H2SSeHm8B3u_4V}w zd1`9O<_OG}5gj=ksc1Mm;gvXnrR;LI`up?!11L{qWMq{QXnNtNvE$6nsghpg;m`im ziaS~s$poDG7Mu^r?nIac{Q_|oUV3+Z@(fC_i!kOv$$NCI_s&zuOaSD!PLiqY!otEf zfq?n{VFBeuF>BpY+KJ3%e^N zDM`(($E5oe%_VxQGTV2pYOi@$G9ruB@q#k_T%Un?~_B} z$Y#i$p?nR?<)KgTISgeka`m1YnUGUrSV7o(=UVxGe*UUHtj}_2HPm)o;*|{Cs_510MVih19`S zc^=mJkOG#F2B_tR2V*lyjJDRC3wM3dRKhYob?b2uLh}^3W!Z&3RPdxJi~gX;rL( z(@a|g5c=ZBg+o)#Z)PQ!>1=}0wY~=~An5c>bW>UNL)GQiEg$90d?+tpQ&lxpY;-Ss z52zgc77Y+rXkW0Cm_n4jrlu_xxF2xA=N~%Y7XdCn*`WgwUw0%L>P)!u02yKnS`dh6 znG{f6XI955W}hpV4^wnCFqaRZqF?59m{m zOUxQUVEOm*reVAr!VBIVn90b#N{0x8xJwJ<2XHc%;MKlbAqGq?to|3L$v?xx9XK6Of)(&lIQUUN}nH>JVD(6lmd~&tvkZfBK|^%_mTWuGrty;Tu44Bp@v1svai`4 z9XM^LK$BHWOs|MZ5Q@h<5X*RF2R)dVh&qmQB#DOA9WEC`qQw@XKC<@- z0&)BbEwavMFP^J|2!Pqv#s&(7!f@Hs!o#kHF zmY7b&)5{AF56}6&q7H@wfuN&@=Dw$etJ;9X>Vl`iT=HB_#Btmc#3>ifq)!27r+_(Pl~<`@ zZBQUl5kfFECt0L4cKO~RDhlYj@cth=oS^gvF zY*!uS6_}U;F!32&JAIbcZ(OqlO8Cb6N3J4v{pvc4NYg>o{ElNA&M z;KP2SW!CP8T+}DIul{NzzkhwV6Xc{=@`*Ra3{l2k?USl?@&dGQl3LdUbY;f=Ni2?ion{VA2jrXSBP1n&O z1fa$#ydPv8!IdlDUML(+o~D7ACxUe8OMO%g+@<&8Seb2VnUZFe`(EsO$R$WKUi~uJ zBEF`uWv7*%Lj^#i(BmVFt~0jnerZY~6%V&&5s5kM%3MHf&34bv&51n!d)G}0I$h>* zNqWCZjJQJ&1_lQ@pA0&4zJ7rH0=Zu!f$4s1z#1S9QNSR?lUjRMh_4HM3mnW=q{xxo zn|ju6NnA{n0O}~cYu5yld1g^`!HG|r;gCdhjI+d+5GHmsjyh+fz(F6 z&l@pOyN&7AK9gHQFWOiWOG&!Je7X{0FJo^#ehPHhC77D4sG(GF85zf8e26R_Hn%tB zN$Rn}@hfoxlTZD99K3YJ<)C6I2|k+p%>RbL8v4N{HVi;lT^c2_OoU*f zNA8evipZzKvH->;40PPS#fAbD77E5IO~-vn=NAhSGYPpdChznXN-f*}1?4uFj=g_? zFF7<~-1tvLFxRFxd7(U(>j?+~dnr!!jaQw%3nmW8nP-+BAP`hk!HyU3(b|qH=z-d2 zBoqwsUv^`!j&OspPA}n>Z)E=MKRZa?6L15Bn|JW5J36F>As`6DoFxLYGG9`Kt`o2yu8KGegZ~@y7-7|BFO9d*0|@=kr2~y4w+i&1skL6U#EJA-7lozl zN~RC#?vx8<%nyAsgo)ePW;d_%D@)Wg-F))xQrQh^N}GI$D2m{h?$PyP zCphi~1tk!aHvfCYub?X(8`$dO>3QkWC9{RVQj{uV5zuDaAL*@xZG7tGk6^YKSNy;% z!4h3Oa3*jrG9A9oxXzm@Q-s%59~%0LCc5{!}8wvqkD+fiZ{ork7gu8da+$}M-50rrI# z6(st^S4pRPiYavu!>}Sx4rnWmu3g+<777eESCE*j!T1fg}tZ+ZF*m+kBP; zvZSX+Yl5*+E^Pt$JayURK7^iZvPreu)xtpM^tr5_@!?l7j4sq23iJsbR?V-;xq|v0 z8PvUfdrc$%K>Aktdnh=Gcfx8k>3SUkR}*g=il7};jwcnm6lMwXY4^?Iq@O%}td{}y zi|(AuWSgV58B{;HjH^F$jD!3`!s$FHVb46SBXM|Jf(Dp|*@%hnv-8PJ#v$$K%&v7I5vy%TgLSa#+)LhYdS6ZoMzIs62a%*@iH^)D9XW}@!{jo#aOw%PF**kaxI zN|l}t{noPa2C*cD?Gel|$>`{~h8OjnPlSJP_s)|AFA4tAQ%<{umgI6J9mXlO7xym9#vK#tb*W+8psw*gvts;$qOSMGp#yV0ePc8X_t zc{P)<^@)F;dY6JT?cz3#Pk9=;r3CNI=9g!~Sc2DA_4p8-oM(e=*r_q|sp;(f$kcX#7O7w|Q$Y=u4$ zB-1vGou-BKs@*t;@ZZE7`9NA!laikM0@__>-65A~^&YR1ucw|X1NwIBaoaRys~mMi zZ%@ag6cN9Zo#BwQ(Bwn(fYImg9gAibalbx($?JI&SqZEmRIxd*=KF``VlNvz=_n5E zfX#6|<%u`Svbtz5a!stv*#S;^jgac<@%uD$(-wnnv4GCcp6~%iIp>~j5mn!h2yQu*<=?T4e(5-0ZLhTUOsU|^OZy4%P+ zfH?Tu_!=hsObqgMfH?VkNPw2-3L=qYx+W$jUB>7YzQ5Nh;-K+nJ{-9>V)UQFxA2o# z5m)#W@{Mc0j@)Z|QHL71OGMS$m}|2lTGm0&Dnv<8!>^bK|rQMe( z380B`uHht%MFtgnO`>O~N0Vn=IhSJvRbBfeka@3Bk2TAO(!*$4SlS{X?&7#UR-Y!@ z#?NhqO6B`9DF3uCIC_rqw6UUMD}dPw#aUp#Z*0<$LHmR6%m|bTa5_iLDZs^i9N)&z zpuRRhrDxCZWtJWaEr=>CEZn~|2eq=a4d%dr!PI~P@!h?4@~WCRmP?n!n3kV!IVBJlP&fU=4xEz8SFzZR=AE5*y-16_jfDyf} zm=Rzjo~OdYjU$@VgJSZL^kOT}xTES`I;Z#FNgT=c#JvnwQ>s_+`$%R)8cCauVsDtw zEt8)Qp`_FLXSRg>H_}K6O5btomvI|a{sX8F>QifD!Kmim6uI-c@b%$ac@2<~<;4#L z*=4ZYZ!xZOJ^ZO{y=ix7QiuxEZ#};CF@B-a{cuVS*fi+Ks72(^$mArW1K(Rx0)nP* z?Y+H^p1!UD=LSsvsk}>Z^Q5(LeS1P8%(aUgEt)W{B}X6%4EE2=R6lJWC5lXyPVa)2 zUivX$O#cVyQy+9b-Abspl|Yux@ZZ)-VDc$(Zkez7RV-D!)WD?v?(X?C|LX>zGmbw> zmlQv>SS#}VYUsx{*$}`u^92T>@7poyc?uY2i5P}zww;{CY#NSq>Y94UHX0tIpNP?& zpFnqZSoEsHW2ouQs|DlRfc4`zvf%I>pOEu(3r=eI>Dm`Cs(sbPa`{~qbYmDF^LrCe zPJe+qJ;7Rp#tCr0>HKr=^1Xn<_j_c~%pQ`uCT|)K-wU8Du-^in&;Qep*(D{%fBaDU z_!L;r+gORM_|P~v4L{cAk*uE4VM(kTb!P{lF~u`OYVZoYrg>eEt{wU4<^5SxJaDQ^ zH?=HKT3A>Jje%&Qbh!5JWmWFxHJ@$ZdK~M5wD*I|Uilwx+f_BWlx#Tjz+imfU!@Q} zNhJ*7E1$S8wB_?Yvi(jd^mTbA=pxc2q5B?3I-uNtQ_UbW{74lS3@OBo2w-aP9V`WSKGcdC! z*{M~OtEOpkBnKzV2fxBhmVO|{j{18Cu$G$_RgTw6W9WcamYQzAP+bCvhqV-n%$85J zRdTSPX5QItLK&Hc?1rB?#vB@%L6s^ZoKOzRIc+oy zBI7u<L$& zMxoKMTpj0d_x}P=9@OT4y+oQU#&QHOQQz9xasTiv%3-t&Zva^p`xzp`%AGa`1}Z8% zthRB#5CuMGTTFsBJ#V?_e*uP)fca2WEc!19I@OVkGHWw4&Ck+e%!1*`4T68bzyJ#H zo#Wv)kZoqx*8E`ipw1?%RuWdrVn1MA!U`uxaX7=VHGfILe?{v_?~`HPp)40m*RSYvS80V{k+ zd_z(XR8-4Zc#%oN=F)}5#VXj$s_&=fm!8k{AgW@gaWUimP!5Q)7or%i;MSuo2_Vy+#oHC4Tot_RC)mgTaRK@nV!n6%&i$vQK z)Cy&8G)y7iDt9K07|9U;yM#fRm<>6gC(QDStcnV{uy7fG`YeF}9d6~QsHkRFS9{Ax zl186ETsqZ3l_~(K99Bi{PsgB$6HJ7_j)qa@l)m=1R+dbE2#lw=AtaO*n9|`TP3=tv zB!qM0FXK`UD2e(GBds5_pi4OucGIO(OlKf~Y`%n5qXK|#I5J~ea! zZCK?cRx?ZnCu#lx&m5meEJY{VM5QzM#%~-K*p8X2Avn!g_D}XE!LH^F3Z2N&`*x5h zHw+o$VY~agwvYktthe2kJQtghT5v?8~cHudv6Z6!4|TSE6p0tfMJmIOc;4xv8AVGJgfZX;ky#6Ce}VrFHO-y30%l z=HKAA2r@eCgIOK_^>3zCO>7TkWmAVh(n~W+U=ne$lUQC0hDHQ3BH?R3extW*zZrVA zTBy!$`+xoh!3D^Yll{jVrC1J(5idj!*n)HdisTD4q0GqtU*_0*Cpb@zm#3#ns+dMW zljiqysX`%Xn23T839KDiu?iq8c5zMVr_ESpUt?g1XhhD@!_*NRC@FYq;#+u^FSE4; zZ~x2e&r>t~YOkMmy0`lL^yuhF^w|&*d-Ri+8uQQw;&!1*ua8v}yX^w6g3p*0bt{^BM0grvz8E-QuG;Hb-X>__~PH+dpQJSFTN6pBy8R#YBAo1TzE&> zRvYjO7p3Zs!$lLirhdU9AScK^2HC(7w$#YZ2nq&J(#-C|y$!~ucjmyiHVLz`XP+QA zA%;LEss%}9;V}S9L`=}xbzi`I;4>hfnSQ*G#{MWdd*H{7k}EJ^1RrbWYb}2R7N|%I z4spAHpIYpA9bxDw4fW&6Pnfg({reXnHi&doDIIQ9s%F~4zD_XpNDd$3{Q9_B6-A2OkGVAba5fi7Ie-U6JjK~rKb8})s;_3ZWc-xW(aT>4OMC*CLJ@F7} z3SPTDP(=V6zk8rI-7U<4C{PZ{vWB0!%+cP>HvhoxXc_yGNdz+-CER0WDS2Uo9zzV3~XX3aSq2B1vxJTh0uOIty&UxC8EeA3_+?VsC2wQ z13(i0kB5N$f(o)8wyWwFdF&rV%)?Y;C6C;mxJOnjA%tKH83nc%XR!TgnplG3u~;4K zbV2Mgn%kgUJ>klKKK45wk{_)u%^Uv`Z9kAp>mR;DfpXzthl*>$Mes&CL5NE)O8`kK9k4eSbeR(J%H1yi+Qzf}+PvvyUDo;z| za$;*TknMR*>m?m8;o+H|LB>jeMMdmec8$cz*$mib#&9A*d0Ylp`}wFv4R{$qo5iPI zFQHUee#vR1H^C#=TN%v~EF+OXDx-8QYx{xpfv@Z<3_oCqQVzNW5zI-aN0ho`7&LC z429PDoj3AmYb?;?pR|^GIZEc4N_p#zF!dLfCv7&@$gg_Rdp~^7yPA~uQJ(!4X$lJu zCz3yDAN&qKmr+rRTnNv^#Ye;OG1{vR?WlB86>L`MvJ3LZ-Mr_dIgm*F4wxamgAM{l5uOSfp^V9tSZ z3F1&Kgf2U^3;KuA_SXHKEF#;C5hf5?r$r?2SI8tkKnrF3+7I4#3HB}pypW(oox}Zo z5CwvQf}WT#kj0#%UxrYN<@y}@{Sb;gh$qhiFW^n5=CPrxJ>>9(pt^nb_Pm<;Q%{b0 z>bYuWq2>olwhwNHHzXmU2Dh(^I&u>T(|po@vSFf@S1puQ)?4Gg93RVXmxzJZbOQNJ zNOg;nj;_!O3yt1L`=*e?Z=rGAJaJR6W+p|8Pv z24I;R2j@i(Vc$(j&wqD~XP1_|*QBidQ6(+j7S+Bgq@x);#u7c8aqGYO(vyKq0 z8$?T_mC4^=scd@`&QBb|WZT&r=SKn+l6F$@OsvuFWl*BHYi{+=w+kQn0Q|v1@75ng+vuNCOZgn?*A_$(&KEDfNR5GxuN2oL8>hNlrxX17zY*62 zE=~YenSbUK5iubM6dhpBZ(Iy~W-p^LIP=fduP>jV+**uCy6W@Z53VPgN0QUJM1D7a|~uWJ=%^Fe`Y zsW9<>V5PK5d{I*&o5yf5tyG7$0;G){z<-Hf{b4*cUFcpJAwGV5u%%J&v*!qot<;F= z($|-Xo9s}!f%4$jumCTdp6h3R$Ag$>B2@ehZY4q9VJr9|;)WnfP5lM&a#9Rp4 znnjLoy8AgZ5)MwHn0U2viK_elt1jH%qPyoA0x&6SzLg#)DRLNB3lYE}&o`&nqn3Vu z;Y$CRiuT31R}6_zxZ!)w-%^WPPTatFi(RIlAjDm;V5TUUB(oWDR*L$Fix~3aHu&i` zo6&{<84_(GPJ0&Qd9JrG#R8C#pU&3v#qn>&V` ztYx05q*hD8ffPQZHPG@_z0Cwu|Hj3L&hy`GRak*opR86)PM7E;BM234@>kpEc(i3- znn0)u68ZEIbLwU^zI%LJc+r;o6nLHH0XM73FPH%Fxj*k~CPrUuF*ITOu({MQ_6|lk zp>vtSgzl)H%d96NqAb=}5X<3|N7O%WjKnmL=6NlG(nY=o8L!Rke$DsxQ!uXq>_dIR zP0-xbbgkk_$^S@`ogEMZg_G=W*DTPQ^}b$`R5ubiwb&$4s%JwN((l=_aSsl6AtXIZx{rz_GnH1ZQLsU`hLB{@TpyeIahaeiJ@qMAKgnC_f6xV5fTox{fwF z_>srZtJWI(?eCsV&~cZy8B=5fym1HVFsI=>0Me_xwsNPAnmO)OxC4`ICe=&MkAA}Q zyX4vr=)4zbx_7*FM(09)`83i)5q|WIHy&ifTjs?V=x%}-*tjMQx-4K_@ZM#>B&)|7 z*p>g%FV3`1cRnMf+UxCYZAz0trTcxEg1krvM#282M2y_(Na;mEc2QAL4CZB{^yO&4 zLlNcW)ZAm%I3F*UdX5qm&<*$wuDtZpNz1FGq~IT@PNHj1eM!k((@Q)$Y!XVd!r8;k zujc*lZ=g{^$F!sYQLEQ6AF`7<5p$jIDja3#fg_bJr2rlP3PIfg^D)dLMt8u4!NJ%q z$MPbuuhfgQ_+^;z99`K1XYljpJtqC~4j69Ru;^bB+`I@r)$20; zzC}h=1T;M8^X@R1s(!J0ot~baoV*MG5u8_cU-;R0{N2DT!Qn!+xV;1VA)mD=&I!VB z_L8!)H|+%;de=vjgffb7O#EJI5A8K=u_@4*9@*Ge(7)T&k7=jbmeU z{0F_FlOK($H2;Kd1Uc}?+!3z^2!b0xC2E1wLQ9%yh4??4Xw%pjmZ*Jp&C3^PVQAo| z<6qeWI9=yhrv%I(U{-_?I-G0p0gVRU=1t|0JoU-K2e=m)JH`A#6{EB|gN0{nFif>79$NM0oq6I7Q-=Quc(c(^}x_MdIuxEAw{ zCnfF6RRA457$m;UIhY8?`-j{Qof2W6d9nV-VP)U^Kg&GB&X#U0a_1REi@dx4(P{xb$g>3%@S@V*Jg+w{m&)SwW?tTL>1zG9N%Z&AQY(^(JG;|g4OmfhT^H3 z9aJ~qd>dTOrjG7}XS-YAo>k8OpZB>+W0~D;W1Hq#+1shoqfmCm1}l%^Unm>ZXBWY3 zh+s7LE5t#mg*H5AIlIw86%LK#g5Wlj+@v*_qcLgj(QvncM2r<#k3x57pT{Ww%Ey>% z72-*7m>V8Sj=A{X-#~So2OZ0Rg#M0@Maz|gV2yq_ppLm{0HhU8dtiG?xnN462U5~; z6Neof59>IOGuVRFERvx{0IZlW=IZ1{M^nS$I(jX2b#*tlbTmcWN`asV7aV{Uf? z5CZ3NIyx=cNp48eUcY{;fknv$j<31sH8wVa=ilXY@u9Z6EB0Q!S>q3SfmB+EE!xDZ+cn(D()5NEy&9|A@aMO zt$YAD0Bh$yzcBJz^bb(j=TWt4fcbDX!~#0z=7*TaxG&Q`2H(TId-p)# zm4YLW(2wCT7B~Cj{w4|VYOa9K6o?f835oyyzxTCmRt~r?;0etEFRWQgDQGz(BYIx9 pJ4N7Gp`o8~=js3NKTiTqOE30Es-`}H|DVP=#fPf0Mfc5K{Vy)deXsxk literal 0 HcmV?d00001 diff --git a/Svc/ComQueue/docs/img/state-machine.puml b/Svc/ComQueue/docs/img/state-machine.puml new file mode 100644 index 0000000000..710e7228aa --- /dev/null +++ b/Svc/ComQueue/docs/img/state-machine.puml @@ -0,0 +1,20 @@ +@startuml +' If/choice check states for handling statuses +state status_check <> +' If/choice check for queue availability +state queue_check <> + +' State definitions to capture self transitions +state WAITING: Buffer Received / Queue Buffer + +[*] -down-> WAITING +' Status In transitions +WAITING -down-> status_check: Status In +status_check -right-> queue_check: [SUCCESS] +status_check -up-> WAITING: [FAILURE] + +queue_check -up-> WAITING: [Buffer Queued] / Send Buffer +queue_check -right-> READY: [No Buffer Queued] +READY -up-> WAITING: Buffer Received / Send Buffer +@enduml + diff --git a/Svc/ComQueue/docs/sdd.md b/Svc/ComQueue/docs/sdd.md new file mode 100644 index 0000000000..8a8eeb3652 --- /dev/null +++ b/Svc/ComQueue/docs/sdd.md @@ -0,0 +1,165 @@ +\page SvcComQueueComponent Svc::ComQueue Component +# Svc::ComQueue (Active Component) + +## 1. Introduction + +`Svc::ComQueue` is an F´ active component that functions as a priority queue of buffer types. Messages are dequeued and +forwarded when a `Fw::Success::SUCCESS` signal is received in order of priority. `Fw::Success::FAILURE` signals result +in the queues being paused until a following `Fw::Success::SUCCESS` signal. + +`Svc::ComQueue` is configured with a queue depth and queue priority for each incoming `Fw::Com` and `Fw::Buffer` port by +passing in a configuration table at initialization. Queued messages from the highest priority source port are serviced +first and a round-robin algorithm is used to balance between ports of shared priority. + +`Svc::ComQueue` is designed to follow the +[communication adapter interface](https://nasa.github.io/fprime/Design/communications-adapter-interface.html). + +## 2. Assumptions + +1. Incoming buffers to a given port are in priority order +2. Data is considered to be successfully sent when a `Fw::Success::SUCCESS` signal was received +3. The com adapter is responsible for any retransmission of failed data +4. The system includes a downstream + [communications adapter](https://nasa.github.io/fprime/Design/communications-adapter-interface.html) + + +## 3. Requirements + + +| Requirement | Description | Rationale | Verification Method | +|------------------|-----------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------|---------------------| +| SVC-COMQUEUE-001 | `Svc::ComQueue` shall queue `Fw::Buffer` and `Fw::ComBuffer` received on incoming ports. | The purpose of the queue is to store messages. | Unit Test | +| SVC-COMQUEUE-002 | `Svc::ComQueue` shall output exactly one `Fw::Buffer` or `Fw::ComBuffer` message on a received `Fw::Success::SUCCESS` signal. | `Svc::ComQueue` obeys the communication adapter interface protocol. | Unit Test | +| SVC-COMQUEUE-003 | `Svc::ComQueue` shall pause sending on the `Fw::Success::FAILURE` and restart on the next `Fw::Success::SUCCESS` signal. | `Svc::ComQueue` should not sent to a failing communication adapter. | Unit Test | +| SVC-COMQUEUE-004 | `Svc::ComQueue` shall have a configurable number of `Fw::Com` and `Fw::Buffer` input ports. | `Svc::ComQueue` should be adaptable for a number of projects. | Inspection | +| SVC-COMQUEUE-005 | `Svc::ComQueue` shall select and send the next priority `Fw::Buffer` and `Fw::ComBuffer` message in response to `Fw::Success::SUCCESS`. | `Svc::ComQueue` obeys the communication adapter interface protocol. | Unit test | +| SVC-COMQUEUE-006 | `Svc::ComQueue` shall periodically telemeter the number of queued messages per-port in response to a `run` port invocation. | `Svc::ComQueue` should provide useful telemetry. | Unit Test | +| SVC-COMQUEUE-007 | `Svc::ComQueue` shall emit a queue overflow event for a given port when the configured depth is exceeded. Messages shall be discarded. | `Svc::ComQueue` needs to indicate off-nominal events. | Unit Test | +| SVC-COMQUEUE-008 | `Svc::ComQueue` shall implement a round robin approach to balance between ports of the same priority. | Allows projects to balance between a set of queues of similar priority. | Unit Test | +| SVC-COMQUEUE-009 | `Svc::ComQueue` shall keep track and throttle queue overflow events per port. | Prevents a flood of queue overflow events. | Unit test | + +## 4. Design +The diagram below shows the `Svc::ComQueue` component. + +![Svc::ComQueue](./img/ComQueue.png) + +### 4.1. Ports +`Svc::ComQueue` has the following ports: + +| Kind | Name | Port Type | Usage | +|---------------|-------------------|---------------------------------------|--------------------------------------------------------| +| `output` | `comQueueSend` | `Fw.Com` | Fw::ComBuffer output port | +| `output` | `buffQueueSend` | `Fw.BufferSend` | Fw::Buffer output port | +| `async input` | `comStatusIn` | `Fw.SuccessCondition` | Port for receiving the status signal | +| `async input` | `comQueueIn` | `[ComQueueComPorts] Fw.Com` | Port array for receiving Fw::ComBuffers | +| `async input` | `buffQueueIn` | `[ComQueueBufferPorts] Fw.BufferSend` | Port array for receiving Fw::Buffers | +| `async input` | `run` | `Svc.Sched` | Port for scheduling telemetry output | +| `event` | `Log` | `Fw.Log` | Port for emitting events | +| `text event` | `LogText` | `Fw.LogText` | Port for emitting text events | +| `time get` | `Time` | `Fw.Time` | Port for getting the time | +| `telemetry` | `Tlm` | `Fw.Tlm` | Port for emitting telemetry | + + +### 4.2. State +`Svc::ComQueue` maintains the following state: +1. `m_queues`: An array of `Types::Queue` used to queue per-port messages. +2. `m_prioritizedList`: An instance of `Svc::ComQueue::QueueMetadata` storing the priority-order queue metadata. +3. `m_state`: Instance of `Svc::ComQueue::SendState` representing the state of the component. See: 4.3.1 State Machine +4. `m_throttle`: An array of flags that throttle the per-port queue overflow messages. + +### 4.2.1 State Machine + +The `Svc::ComQueue` component runs the following state machine. It has two states: + +| State | Description | +|---------|-----------------------------------------------------------------------------------------------| +| WAITING | `Svc::ComQueue` is waiting on `SUCCESS` before attempting to send an available buffer | +| READY | `Svc::ComQueue` had no queued buffers and will send the next buffer immediately when received | + +The state machine will transition between states when a status is received and will transition from `READY` when a new +buffer is received. `FAILURE` statuses keep the `Svc::ComQueue` in `WAITING` state whereas a `SUCCESS` status will +either send a buffer and transition to `WAITING` or will have no buffers to send and will transition into `READY` state. +Buffers are queued when in `WAITING` state. + +![`Svc::ComQueue` Functional State Machine](./img/state-machine.png) + +### 4.3 Model Configuration +`Svc::ComQueue` has the following constants, that are configured in `AcConstants.fpp`: +1. `ComQueueComPorts`: number of ports of `Fw.Com` type in the `comQueueIn` port array. +2. `ComQueueBufferPorts`: number of ports of `Fw.BufferSend` type in the `buffQueueIn` port array. + +### 4.4 Runtime Setup +To set up an instance of `ComQueue`, the following needs to be done: +1. Call the constructor and the init method in the usual way for an F Prime active component. +2. Call the `configure` method, passing in an array of `QueueConfiguration` type, the size of the array, +and an allocator of `Fw::MemAllocator`. The `configure` method foes the following: + + 1. Ensures that the total size and config size are the same value + 2. Ensures that priority values range from 0 to the total size value + 3. Ensures that every entry in the queue containing the prioritized order of the com buffer and buffer data have been + initialized. + 4. Ensures that there is enough memory for the com buffer and buffer data we want to process + +### 4.5 Port Handlers + +#### 4.5.1 buffQueueIn +The `buffQueueIn` port handler receives an `Fw::Buffer` data type and a port number. +It does the following: +1. Ensures that the port number is between zero and the value of the buffer size +2. Enqueue the buffer onto the `m_queues` instance +3. Returns a warning if `m_queues` is full + +In the case where the component is already in `READY` state, this will process the queue immediately after the buffer +is added to the queue. + +#### 4.5.2 comQueueIn +The `comQueueIn` port handler receives an `Fw::ComBuffer` data type and a port number. +It does the following: +1. Ensures that the port number is between zero and the value of the com buffer size +2. Enqueue the com buffer onto the `m_queues` instance +3. Returns a warning if `m_queues` is full + +In the case where the component is already in `READY` state, this will process the +queue immediately after the buffer is added to the queue. + +#### 4.5.3 comStatusIn +The `comStatusIn` port handler receives a `Fw::Success` status. This triggers the component's state machine to change +state. For a full description see [4.2.1 State Machine](#4.2.1-State-Machine). + +#### 4.5.4 run +The `run` port handler does the following: +1. Report the high-water mark for each queue since last `run` invocation via telemetry +2. Clear each queue's high-water mark + +### 4.6 Telemetry + +| Name | Type | Description | +|----------------|--------------------|-----------------------------------------------------------| +| comQueueDepth | Svc.ComQueueDepth | High-water mark depths of queues handling `Fw::ComBuffer` | +| buffQueueDepth | Svc.BuffQueueDepth | High-water mark depths of queues handling `Fw::Buffer` | + +### 4.7 Events + +| Name | Description | +|----------------|---------------------------------------------------------------------------------| +| QueueOverflow | WARNING_HI event triggered when a queue can no longer hold the incoming message | + +### 4.8 Helper Functions + +#### 4.8.1 sendComBuffer +Stores the com buffer message, sends the com buffer message on the output port, and then sets the send state to waiting. + +#### 4.8.2 sendBuffer +Stores the buffer message, sends the buffer message on the output port, and then sets the send state to waiting. + +#### 4.8.3 processQueue +In a bounded loop that is constrained by the total size of the queue that contains both +buffer and com buffer data, do: + + 1. Check if there are any items on the queue, and continue with the loop if there are none. + 2. Store the entry point of the queue based on the index of the array that contains the prioritized data. + 3. Compare the entry index with the value of the size of the queue that contains com buffer data. + 1. If it is less than the size value, then invoke the sendComBuffer function. + 2. If it is greater than the size value, then invoke the sendBuffer function. + 4. Break out of the loop, but enter a new loop that starts at the next entry and linearly swap the remaining items in +the prioritized list. diff --git a/Svc/ComQueue/test/ut/TestMain.cpp b/Svc/ComQueue/test/ut/TestMain.cpp new file mode 100644 index 0000000000..eadb4fc105 --- /dev/null +++ b/Svc/ComQueue/test/ut/TestMain.cpp @@ -0,0 +1,35 @@ +// ---------------------------------------------------------------------- +// TestMain.cpp +// ---------------------------------------------------------------------- + +#include "Svc/ComQueue/test/ut/Tester.hpp" + +TEST(Nominal, Send) { + Svc::Tester tester; + tester.testQueueSend(); +} + +TEST(Nominal, Pause) { + Svc::Tester tester; + tester.testQueuePause(); +} + +TEST(Nominal, Priority) { + Svc::Tester tester; + tester.testPrioritySend(); +} + +TEST(Nominal, Full) { + Svc::Tester tester; + tester.testQueueOverflow(); +} + +TEST(Nominal, ReadyFirst) { + Svc::Tester tester; + tester.testReadyFirst(); +} + +int main(int argc, char **argv) { + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/Svc/ComQueue/test/ut/Tester.cpp b/Svc/ComQueue/test/ut/Tester.cpp new file mode 100644 index 0000000000..34d56028a3 --- /dev/null +++ b/Svc/ComQueue/test/ut/Tester.cpp @@ -0,0 +1,327 @@ +// ====================================================================== +// \title ComQueue.hpp +// \author vbai +// \brief cpp file for ComQueue test harness implementation class +// ====================================================================== + +#include "Tester.hpp" +#include "Fw/Types/MallocAllocator.hpp" +using namespace std; + +Fw::MallocAllocator mallocAllocator; +#define INSTANCE 0 +#define MAX_HISTORY_SIZE 100 +#define QUEUE_DEPTH 100 + +namespace Svc { + +// ---------------------------------------------------------------------- +// Construction and destruction +// ---------------------------------------------------------------------- + +Tester ::Tester() : ComQueueGTestBase("Tester", MAX_HISTORY_SIZE), component("ComQueue") { + this->initComponents(); + this->connectPorts(); +} + +Tester ::~Tester() {} + +void Tester ::dispatchAll() { + while (this->component.m_queue.getNumMsgs() > 0) { + this->component.doDispatch(); + } +} + +void Tester ::configure() { + ComQueue::QueueConfigurationTable configurationTable; + for (NATIVE_UINT_TYPE i = 0; i < ComQueue::TOTAL_PORT_COUNT; i++){ + configurationTable.entries[i].priority = i; + configurationTable.entries[i].depth = 3; + } + component.configure(configurationTable, 0, mallocAllocator); +} + +void Tester ::sendByQueueNumber(NATIVE_INT_TYPE queueNum, NATIVE_INT_TYPE& portNum, QueueType& queueType) { + U8 data[BUFFER_LENGTH] = {0xde, 0xad, 0xbe}; + Fw::ComBuffer comBuffer(&data[0], sizeof(data)); + Fw::Buffer buffer(&data[0], sizeof(data)); + if (queueNum < ComQueue::COM_PORT_COUNT) { + portNum = queueNum; + queueType = QueueType::COM_QUEUE; + invoke_to_comQueueIn(portNum, comBuffer, 0); + } else { + portNum = queueNum - ComQueue::COM_PORT_COUNT; + queueType = QueueType::BUFFER_QUEUE; + invoke_to_buffQueueIn(portNum, buffer); + } +} + +void Tester ::emitOne() { + Fw::Success state = Fw::Success::SUCCESS; + invoke_to_comStatusIn(0, state); + dispatchAll(); +} + +void Tester ::emitOneAndCheck(NATIVE_UINT_TYPE expectedIndex, + QueueType expectedType, + Fw::ComBuffer& expectedCom, + Fw::Buffer& expectedBuff) { + emitOne(); + + if (expectedType == QueueType::COM_QUEUE) { + ASSERT_from_comQueueSend(expectedIndex, expectedCom, 0); + } else { + ASSERT_from_buffQueueSend(expectedIndex, expectedBuff); + } +} + +// ---------------------------------------------------------------------- +// Tests +// ---------------------------------------------------------------------- + +void Tester ::testQueueSend() { + U8 data[BUFFER_LENGTH] = {0xde, 0xad, 0xbe}; + Fw::ComBuffer comBuffer(&data[0], sizeof(data)); + Fw::Buffer buffer(&data[0], sizeof(data)); + configure(); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::COM_PORT_COUNT; portNum++){ + invoke_to_comQueueIn(portNum, comBuffer, 0); + emitOneAndCheck(portNum, QueueType::COM_QUEUE, comBuffer, buffer); + } + clearFromPortHistory(); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::BUFFER_PORT_COUNT; portNum++){ + invoke_to_buffQueueIn(portNum, buffer); + emitOneAndCheck(portNum, QueueType::BUFFER_QUEUE, comBuffer, buffer); + } + clearFromPortHistory(); + component.cleanup(); +} + +void Tester ::testQueuePause() { + U8 data[BUFFER_LENGTH] = {0xde, 0xad, 0xbe}; + Fw::ComBuffer comBuffer(&data[0], sizeof(data)); + Fw::Buffer buffer(&data[0], sizeof(data)); + configure(); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::COM_PORT_COUNT; portNum++){ + invoke_to_comQueueIn(portNum, comBuffer, 0); + // Send a bunch of failures + Fw::Success state = Fw::Success::FAILURE; + invoke_to_comStatusIn(0, state); + invoke_to_comStatusIn(0, state); + invoke_to_comStatusIn(0, state); + emitOneAndCheck(portNum, QueueType::COM_QUEUE, comBuffer, buffer); + } + clearFromPortHistory(); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::BUFFER_PORT_COUNT; portNum++){ + invoke_to_buffQueueIn(portNum, buffer); + // Send a bunch of failures + Fw::Success state = Fw::Success::FAILURE; + invoke_to_comStatusIn(0, state); + invoke_to_comStatusIn(0, state); + invoke_to_comStatusIn(0, state); + emitOneAndCheck(portNum, QueueType::BUFFER_QUEUE, comBuffer, buffer); + } + clearFromPortHistory(); + component.cleanup(); +} + +void Tester ::testPrioritySend() { + U8 data[ComQueue::TOTAL_PORT_COUNT][BUFFER_LENGTH]; + + ComQueue::QueueConfigurationTable configurationTable; + + for (NATIVE_UINT_TYPE i = 0; i < ComQueue::TOTAL_PORT_COUNT; i++) { + configurationTable.entries[i].priority = ComQueue::TOTAL_PORT_COUNT - i - 1; + configurationTable.entries[i].depth = 3; + data[i][0] = ComQueue::TOTAL_PORT_COUNT - i - 1; + } + + // Make the last message have the same priority as the second message + configurationTable.entries[ComQueue::TOTAL_PORT_COUNT - 1].priority = 1; + data[ComQueue::TOTAL_PORT_COUNT - 2][0] = 0; + data[ComQueue::TOTAL_PORT_COUNT - 1][0] = 1; + + component.configure(configurationTable, 0, mallocAllocator); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::COM_PORT_COUNT; portNum++){ + Fw::ComBuffer comBuffer(&data[portNum][0], BUFFER_LENGTH); + invoke_to_comQueueIn(portNum, comBuffer, 0); + } + + for (NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::BUFFER_PORT_COUNT; portNum++) { + Fw::Buffer buffer(&data[portNum + ComQueue::COM_PORT_COUNT][0], BUFFER_LENGTH); + invoke_to_buffQueueIn(portNum, buffer); + } + + // Check that nothing has yet been sent + ASSERT_from_buffQueueSend_SIZE(0); + ASSERT_from_comQueueSend_SIZE(0); + + for (NATIVE_INT_TYPE index = 0; index < ComQueue::TOTAL_PORT_COUNT; index++) { + U8 orderKey; + U32 previousComSize = fromPortHistory_comQueueSend->size(); + U32 previousBufSize = fromPortHistory_buffQueueSend->size(); + emitOne(); + ASSERT_EQ(fromPortHistory_comQueueSend->size() + fromPortHistory_buffQueueSend->size(), (index + 1)); + + // Check that the sizes changed by exactly one + ASSERT_TRUE((previousComSize == fromPortHistory_comQueueSend->size()) ^ + (previousBufSize == fromPortHistory_buffQueueSend->size())); + + // Look for which type had arrived + if (fromPortHistory_comQueueSend->size() > previousComSize) { + orderKey = fromPortHistory_comQueueSend->at(fromPortHistory_comQueueSend->size() - 1).data.getBuffAddr()[0]; + } else { + orderKey = + fromPortHistory_buffQueueSend->at(fromPortHistory_buffQueueSend->size() - 1).fwBuffer.getData()[0]; + + } + ASSERT_EQ(orderKey, index); + } + clearFromPortHistory(); + component.cleanup(); +} + +void Tester::testQueueOverflow(){ + ComQueue::QueueConfigurationTable configurationTable; + ComQueueDepth expectedComDepth; + BuffQueueDepth expectedBuffDepth; + + for (NATIVE_UINT_TYPE i = 0; i < ComQueue::TOTAL_PORT_COUNT; i++){ + configurationTable.entries[i].priority = i; + configurationTable.entries[i].depth = 2; + + // Expected depths + if (i < ComQueue::COM_PORT_COUNT) { + expectedComDepth[i] = configurationTable.entries[i].depth; + } else { + expectedBuffDepth[i - ComQueue::COM_PORT_COUNT] = configurationTable.entries[i].depth; + } + } + + component.configure(configurationTable, 0, mallocAllocator); + + for(NATIVE_INT_TYPE queueNum = 0; queueNum < ComQueue::TOTAL_PORT_COUNT; queueNum++) { + QueueType overflow_type; + NATIVE_INT_TYPE portNum; + // queue[portNum].depth + 2 to deliberately cause overflow and check throttle of exactly 1 + for (NATIVE_UINT_TYPE msgCount = 0; msgCount < configurationTable.entries[queueNum].depth + 2; msgCount++) { + sendByQueueNumber(queueNum, portNum, overflow_type); + dispatchAll(); + } + ASSERT_EVENTS_QueueOverflow_SIZE(1); + ASSERT_EVENTS_QueueOverflow(0, overflow_type, portNum); + + // Drain a message, and see if throttle resets + emitOne(); + + // Force another overflow by filling then deliberately overflowing the queue + sendByQueueNumber(queueNum, portNum, overflow_type); + sendByQueueNumber(queueNum, portNum, overflow_type); + dispatchAll(); + + ASSERT_EVENTS_QueueOverflow_SIZE(2); + ASSERT_EVENTS_QueueOverflow(1, overflow_type, portNum); + + // Drain the queue again such that we have a clean slate before the next queue + for (NATIVE_UINT_TYPE msgCount = 0; msgCount < configurationTable.entries[queueNum].depth; msgCount++) { + emitOne(); + } + clearEvents(); + } + // Check max seen queue-depths + invoke_to_run(0, 0); + dispatchAll(); + ASSERT_TLM_comQueueDepth_SIZE(1); + ASSERT_TLM_buffQueueDepth_SIZE(1); + ASSERT_TLM_comQueueDepth(0, expectedComDepth); + ASSERT_TLM_buffQueueDepth(0, expectedBuffDepth); + component.cleanup(); +} + +void Tester ::testReadyFirst() { + U8 data[BUFFER_LENGTH] = {0xde, 0xad, 0xbe}; + Fw::ComBuffer comBuffer(&data[0], sizeof(data)); + Fw::Buffer buffer(&data[0], sizeof(data)); + configure(); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::COM_PORT_COUNT; portNum++){ + emitOne(); + invoke_to_comQueueIn(portNum, comBuffer, 0); + dispatchAll(); + ASSERT_from_comQueueSend(portNum, comBuffer, 0); + } + clearFromPortHistory(); + + for(NATIVE_INT_TYPE portNum = 0; portNum < ComQueue::BUFFER_PORT_COUNT; portNum++){ + emitOne(); + invoke_to_buffQueueIn(portNum, buffer); + dispatchAll(); + ASSERT_from_buffQueueSend(portNum, buffer); + } + clearFromPortHistory(); + component.cleanup(); +} + +// ---------------------------------------------------------------------- +// Handlers for typed from ports +// ---------------------------------------------------------------------- + +void Tester ::from_buffQueueSend_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { + this->pushFromPortEntry_buffQueueSend(fwBuffer); +} + +void Tester ::from_comQueueSend_handler(const NATIVE_INT_TYPE portNum, Fw::ComBuffer& data, U32 context) { + this->pushFromPortEntry_comQueueSend(data, context); +} + +// ---------------------------------------------------------------------- +// Helper methods +// ---------------------------------------------------------------------- + +void Tester ::connectPorts() { + // buffQueueIn + for (NATIVE_INT_TYPE i = 0; i < ComQueue::BUFFER_PORT_COUNT; ++i) { + this->connect_to_buffQueueIn(i, this->component.get_buffQueueIn_InputPort(i)); + } + + // comQueueIn + for (NATIVE_INT_TYPE i = 0; i < ComQueue::COM_PORT_COUNT; ++i) { + this->connect_to_comQueueIn(i, this->component.get_comQueueIn_InputPort(i)); + } + + // comStatusIn + this->connect_to_comStatusIn(0, this->component.get_comStatusIn_InputPort(0)); + + // run + this->connect_to_run(0, this->component.get_run_InputPort(0)); + + // Log + this->component.set_Log_OutputPort(0, this->get_from_Log(0)); + + // LogText + this->component.set_LogText_OutputPort(0, this->get_from_LogText(0)); + + // Time + this->component.set_Time_OutputPort(0, this->get_from_Time(0)); + + // Tlm + this->component.set_Tlm_OutputPort(0, this->get_from_Tlm(0)); + + // buffQueueSend + this->component.set_buffQueueSend_OutputPort(0, this->get_from_buffQueueSend(0)); + + // comQueueSend + this->component.set_comQueueSend_OutputPort(0, this->get_from_comQueueSend(0)); +} + +void Tester ::initComponents() { + this->init(); + this->component.init(QUEUE_DEPTH, INSTANCE); +} + +} // end namespace Svc diff --git a/Svc/ComQueue/test/ut/Tester.hpp b/Svc/ComQueue/test/ut/Tester.hpp new file mode 100644 index 0000000000..8b06126396 --- /dev/null +++ b/Svc/ComQueue/test/ut/Tester.hpp @@ -0,0 +1,106 @@ +// ====================================================================== +// \title ComQueue/test/ut/Tester.hpp +// \author vbai +// \brief hpp file for ComQueue test harness implementation class +// ====================================================================== + +#ifndef TESTER_HPP +#define TESTER_HPP + +#include "GTestBase.hpp" +#include "Svc/ComQueue/ComQueue.hpp" +#define BUFFER_LENGTH 3u + +namespace Svc { + +class Tester : public ComQueueGTestBase { + private: + // ---------------------------------------------------------------------- + // Construction and destruction + // ---------------------------------------------------------------------- + + public: + //! Construct object Tester + //! + Tester(); + + //! Destroy object Tester + //! + ~Tester(); + + //! Dispatch all component messages + //! + void dispatchAll(); + + public: + // ---------------------------------------------------------------------- + // Helpers + // ---------------------------------------------------------------------- + void configure(); + + void sendByQueueNumber(NATIVE_INT_TYPE queueNumber, NATIVE_INT_TYPE& portNum, QueueType& queueType); + + void emitOne(); + + void emitOneAndCheck(NATIVE_UINT_TYPE expectedIndex, + QueueType expectedType, + Fw::ComBuffer& expectedCom, + Fw::Buffer& expectedBuff); + + // ---------------------------------------------------------------------- + // Tests + // ---------------------------------------------------------------------- + + void testQueueSend(); + + void testQueuePause(); + + void testPrioritySend(); + + void testQueueOverflow(); + + void testReadyFirst(); + + private: + // ---------------------------------------------------------------------- + // Handlers for typed from ports + // ---------------------------------------------------------------------- + + //! Handler for from_buffQueueSend + //! + void from_buffQueueSend_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& fwBuffer); + + //! Handler for from_comQueueSend + //! + void from_comQueueSend_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::ComBuffer& data, /*!< Buffer containing packet data*/ + U32 context /*!< Call context value; meaning chosen by user*/ + ); + + private: + // ---------------------------------------------------------------------- + // Helper methods + // ---------------------------------------------------------------------- + + //! Connect ports + //! + void connectPorts(); + + //! Initialize components + //! + void initComponents(); + + private: + // ---------------------------------------------------------------------- + // Variables + // ---------------------------------------------------------------------- + + //! The component under test + //! + ComQueue component; +}; + +} // end namespace Svc + +#endif diff --git a/Utils/Types/CMakeLists.txt b/Utils/Types/CMakeLists.txt index 297c1cdbbd..66051527a8 100644 --- a/Utils/Types/CMakeLists.txt +++ b/Utils/Types/CMakeLists.txt @@ -7,6 +7,7 @@ #### set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/CircularBuffer.cpp" + "${CMAKE_CURRENT_LIST_DIR}/Queue.cpp" ) set(MOD_DEPS "Fw/Types" diff --git a/Utils/Types/CircularBuffer.cpp b/Utils/Types/CircularBuffer.cpp index 594f55ca04..b835f58585 100644 --- a/Utils/Types/CircularBuffer.cpp +++ b/Utils/Types/CircularBuffer.cpp @@ -22,13 +22,37 @@ namespace Types { +CircularBuffer :: CircularBuffer() : + m_store(nullptr), + m_store_size(0), + m_head_idx(0), + m_allocated_size(0), + m_high_water_mark(0) +{ + +} + CircularBuffer :: CircularBuffer(U8* const buffer, const NATIVE_UINT_TYPE size) : - m_store(buffer), - m_store_size(size), + m_store(nullptr), + m_store_size(0), m_head_idx(0), - m_allocated_size(0) + m_allocated_size(0), + m_high_water_mark(0) { - FW_ASSERT(m_store_size > 0); + setup(buffer, size); +} + +void CircularBuffer :: setup(U8* const buffer, const NATIVE_UINT_TYPE size) { + FW_ASSERT(size > 0); + FW_ASSERT(buffer != nullptr); + FW_ASSERT(m_store == nullptr && m_store_size == 0); // Not already setup + + // Initialize buffer data + m_store = buffer; + m_store_size = size; + m_head_idx = 0; + m_allocated_size = 0; + m_high_water_mark = 0; } NATIVE_UINT_TYPE CircularBuffer :: get_allocated_size() const { @@ -36,6 +60,7 @@ NATIVE_UINT_TYPE CircularBuffer :: get_allocated_size() const { } NATIVE_UINT_TYPE CircularBuffer :: get_free_size() const { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called FW_ASSERT(m_allocated_size <= m_store_size, m_allocated_size); return m_store_size - m_allocated_size; } @@ -46,6 +71,7 @@ NATIVE_UINT_TYPE CircularBuffer :: advance_idx(NATIVE_UINT_TYPE idx, NATIVE_UINT } Fw::SerializeStatus CircularBuffer :: serialize(const U8* const buffer, const NATIVE_UINT_TYPE size) { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called FW_ASSERT(buffer != nullptr); // Check there is sufficient space if (size > get_free_size()) { @@ -60,14 +86,17 @@ Fw::SerializeStatus CircularBuffer :: serialize(const U8* const buffer, const NA } m_allocated_size += size; FW_ASSERT(m_allocated_size <= this->get_capacity(), m_allocated_size); + m_high_water_mark = (m_high_water_mark > m_allocated_size) ? m_high_water_mark : m_allocated_size; return Fw::FW_SERIALIZE_OK; } Fw::SerializeStatus CircularBuffer :: peek(char& value, NATIVE_UINT_TYPE offset) const { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called return peek(reinterpret_cast(value), offset); } Fw::SerializeStatus CircularBuffer :: peek(U8& value, NATIVE_UINT_TYPE offset) const { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called // Check there is sufficient data if ((sizeof(U8) + offset) > m_allocated_size) { return Fw::FW_DESERIALIZE_BUFFER_EMPTY; @@ -79,6 +108,7 @@ Fw::SerializeStatus CircularBuffer :: peek(U8& value, NATIVE_UINT_TYPE offset) c } Fw::SerializeStatus CircularBuffer :: peek(U32& value, NATIVE_UINT_TYPE offset) const { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called // Check there is sufficient data if ((sizeof(U32) + offset) > m_allocated_size) { return Fw::FW_DESERIALIZE_BUFFER_EMPTY; @@ -96,6 +126,7 @@ Fw::SerializeStatus CircularBuffer :: peek(U32& value, NATIVE_UINT_TYPE offset) } Fw::SerializeStatus CircularBuffer :: peek(U8* buffer, NATIVE_UINT_TYPE size, NATIVE_UINT_TYPE offset) const { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called FW_ASSERT(buffer != nullptr); // Check there is sufficient data if ((size + offset) > m_allocated_size) { @@ -112,6 +143,7 @@ Fw::SerializeStatus CircularBuffer :: peek(U8* buffer, NATIVE_UINT_TYPE size, NA } Fw::SerializeStatus CircularBuffer :: rotate(NATIVE_UINT_TYPE amount) { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called // Check there is sufficient data if (amount > m_allocated_size) { return Fw::FW_DESERIALIZE_BUFFER_EMPTY; @@ -122,9 +154,18 @@ Fw::SerializeStatus CircularBuffer :: rotate(NATIVE_UINT_TYPE amount) { } NATIVE_UINT_TYPE CircularBuffer ::get_capacity() const { + FW_ASSERT(m_store != nullptr && m_store_size != 0); // setup method was called return m_store_size; } +NATIVE_UINT_TYPE CircularBuffer ::get_high_water_mark() const { + return m_high_water_mark; +} + +void CircularBuffer ::clear_high_water_mark() { + m_high_water_mark = 0; +} + #ifdef CIRCULAR_DEBUG void CircularBuffer :: print() { NATIVE_UINT_TYPE idx = m_head_idx; diff --git a/Utils/Types/CircularBuffer.hpp b/Utils/Types/CircularBuffer.hpp index 38720e839e..b885dc168c 100644 --- a/Utils/Types/CircularBuffer.hpp +++ b/Utils/Types/CircularBuffer.hpp @@ -30,6 +30,15 @@ class CircularBuffer { * Circular buffer constructor. Wraps the supplied buffer as the new data store. Buffer * size is supplied in the 'size' argument. * + * Note: specification of storage buffer must be done using `setup` before use. + */ + CircularBuffer(); + + /** + * Circular buffer constructor. Wraps the supplied buffer as the new data store. Buffer + * size is supplied in the 'size' argument. This is equivalent to calling the no-argument constructor followed + * by setup(buffer, size). + * * Note: ownership of the supplied buffer is held until the circular buffer is deallocated * * \param buffer: supplied buffer used as a data store. @@ -37,6 +46,17 @@ class CircularBuffer { */ CircularBuffer(U8* const buffer, const NATIVE_UINT_TYPE size); + /** + * Wraps the supplied buffer as the new data store. Buffer size is supplied in the 'size' argument. Cannot be + * called after successful setup. + * + * Note: ownership of the supplied buffer is held until the circular buffer is deallocated + * + * \param buffer: supplied buffer used as a data store. + * \param size: the of the supplied data store. + */ + void setup(U8* const buffer, const NATIVE_UINT_TYPE size); + /** * Serialize a given buffer into this circular buffer. Will not accept more data than * space available. This means it will not overwrite existing data. @@ -104,6 +124,16 @@ class CircularBuffer { */ NATIVE_UINT_TYPE get_capacity() const; + /** + * Return the largest tracked allocated size + */ + NATIVE_UINT_TYPE get_high_water_mark() const; + + /** + * Clear tracking of the largest allocated size + */ + void clear_high_water_mark(); + #ifdef CIRCULAR_DEBUG void print(); #endif @@ -116,14 +146,16 @@ class CircularBuffer { */ NATIVE_UINT_TYPE advance_idx(NATIVE_UINT_TYPE idx, NATIVE_UINT_TYPE amount = 1) const; //! Physical store backing this circular buffer - U8* const m_store; + U8* m_store; //! Size of the physical store - const NATIVE_UINT_TYPE m_store_size; + NATIVE_UINT_TYPE m_store_size; //! Index into m_store of byte zero in the logical store. //! When memory is deallocated, this index moves forward and wraps around. NATIVE_UINT_TYPE m_head_idx; //! Allocated size (size of the logical store) NATIVE_UINT_TYPE m_allocated_size; + //! Maximum allocated size + NATIVE_UINT_TYPE m_high_water_mark; }; } //End Namespace Types #endif diff --git a/Utils/Types/Queue.cpp b/Utils/Types/Queue.cpp new file mode 100644 index 0000000000..ef41ee90bb --- /dev/null +++ b/Utils/Types/Queue.cpp @@ -0,0 +1,56 @@ +/* + * Queue.cpp: + * + * Implementation of the queue data type. + * + * Created on: July 5th, 2022 + * Author: lestarch + * + */ +#include "Queue.hpp" +#include + +namespace Types { + +Queue::Queue() : m_internal(), m_message_size(0) {} + +void Queue::setup(U8* const storage, const FwSizeType storage_size, const FwSizeType depth, const FwSizeType message_size) { + // Ensure that enough storage was supplied + const FwSizeType total_needed_size = depth * message_size; + FW_ASSERT(storage_size >= total_needed_size, storage_size, depth, message_size); + m_internal.setup(storage, total_needed_size); + m_message_size = message_size; +} + +Fw::SerializeStatus Queue::enqueue(const U8* const message, const FwSizeType size) { + FW_ASSERT(m_message_size > 0, m_message_size); // Ensure initialization + FW_ASSERT(m_message_size == size, size, m_message_size); // Message size is as expected + return m_internal.serialize(message, static_cast(m_message_size)); +} + +Fw::SerializeStatus Queue::dequeue(U8* const message, const FwSizeType size) { + FW_ASSERT(m_message_size > 0); // Ensure initialization + FW_ASSERT(m_message_size <= size, size, m_message_size); // Sufficient storage space for read message + Fw::SerializeStatus result = m_internal.peek(message, static_cast(m_message_size), 0); + if (result != Fw::FW_SERIALIZE_OK) { + return result; + } + return m_internal.rotate(m_message_size); +} + +NATIVE_UINT_TYPE Queue::get_high_water_mark() const { + FW_ASSERT(m_message_size > 0, m_message_size); + return m_internal.get_high_water_mark() / m_message_size; +} + +void Queue::clear_high_water_mark() { + m_internal.clear_high_water_mark(); +} + +NATIVE_UINT_TYPE Queue::getQueueSize() const { + FW_ASSERT(m_message_size > 0, m_message_size); + return m_internal.get_allocated_size()/m_message_size; +} + + +}; // namespace Types \ No newline at end of file diff --git a/Utils/Types/Queue.hpp b/Utils/Types/Queue.hpp new file mode 100644 index 0000000000..625c6316cd --- /dev/null +++ b/Utils/Types/Queue.hpp @@ -0,0 +1,92 @@ +/* + * Queue.hpp: + * + * FIFO queue of fixed size messages. For use generally where non-concurrent, non-OS backed based FIFO queues are + * necessary. Message size is defined at construction time and all messages enqueued and dequeued must be of that fixed + * size. Wraps circular buffer to perform actual storage of messages. This implementation is not thread safe and the + * expectation is that the user will wrap it in concurrency constructs where necessary. + * + * Created on: July 5th, 2022 + * Author: lestarch + * + */ +#ifndef _UTILS_TYPES_QUEUE_HPP +#define _UTILS_TYPES_QUEUE_HPP +#include +#include +#include +#include + +typedef U32 FwSizeType; // TODO: replace with refactored types when available + +namespace Types { + +class Queue { + public: + /** + * \brief constructs an uninitialized queue + */ + Queue(); + + /** + * \brief setup the queue object to setup storage + * + * The queue must be configured before use to setup storage parameters. This function supplies those parameters + * including depth, and message size. Storage size must be greater than or equal to the depth x message size. + * + * \param storage: storage memory allocation + * \param storage_size: size of the provided allocation + * \param depth: depth of the queue + * \param message_size: size of individual messages + */ + void setup(U8* const storage, const FwSizeType storage_size, const FwSizeType depth, const FwSizeType message_size); + + /** + * \brief pushes a fixed-size message onto the back of the queue + * + * Pushes a fixed-size message onto the queue. This performs a copy of the data onto the queue so the user is free + * to dispose the message data as soon as the call returns. Note: message is required to be of the size message_size + * as defined by the construction of the queue. Size is provided as a safety check to ensure the sent size is + * consistent with the expected size of the queue. + * + * This will return a non-Fw::SERIALIZE_OK status when the queue is full. + * + * \param message: message of size m_message_size to enqueue + * \param size: size of the message being sent. Must be equivalent to queue's message size. + * \return: Fw::SERIALIZE_OK on success, something else on failure + */ + Fw::SerializeStatus enqueue(const U8* const message, const FwSizeType size); + + /** + * \brief pops a fixed-size message off the front of the queue + * + * Pops a fixed-size message off the front of the queue. This performs a copy of the data into the provided message + * buffer. Note: message is required to be of the size message_size as defined by the construction of the queue. The + * size must be greater or equal to message size, although only message size bytes will be used. + * + * This will return a non-Fw::SERIALIZE_OK status when the queue is empty. + * + * \param message: message of size m_message_size to dequeue + * \param size: size of the buffer being supplied. + * \return: Fw::SERIALIZE_OK on success, something else on failure + */ + Fw::SerializeStatus dequeue(U8* const message, const FwSizeType size); + + /** + * Return the largest tracked allocated size + */ + NATIVE_UINT_TYPE get_high_water_mark() const; + + /** + * Clear tracking of the largest allocated size + */ + void clear_high_water_mark(); + + NATIVE_UINT_TYPE getQueueSize() const; + + private: + CircularBuffer m_internal; + FwSizeType m_message_size; +}; +} // namespace Types +#endif // _UTILS_TYPES_QUEUE_HPP diff --git a/config/AcConstants.fpp b/config/AcConstants.fpp index f3febe1e45..20199faebe 100644 --- a/config/AcConstants.fpp +++ b/config/AcConstants.fpp @@ -27,6 +27,12 @@ constant HealthPingPorts = 25 @ Used for broadcasting completed file downlinks constant FileDownCompletePorts = 1 +@ Used for number of Fw::Com type ports supported by Svc::ComQueue +constant ComQueueComPorts = 2 + +@ Used for number of Fw::Buffer type ports supported by Svc::ComQueue +constant ComQueueBufferPorts = 1 + # ---------------------------------------------------------------------- # Hub connections. Connections on all deployments should mirror these settings. # ---------------------------------------------------------------------- From ab382832872cae8927f45914adf156dc30694056 Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 7 Nov 2022 17:19:30 -0800 Subject: [PATCH 091/169] lestarch: updating Ref app to remove phases (#1748) * lestarch: updating Ref app to remove phases * lestarch: fixing CI errors * lestarch: sp * lestarch: fixing review comments and formatting code * lestarch: renaming ambiguous files * lestarch: sp --- .github/actions/spelling/expect.txt | 5 + RPI/Top/instances.fpp | 6 +- Ref/CMakeLists.txt | 2 +- Ref/ComponentReport.txt | 51 - Ref/LINUX_SlocReport.csv | 67 -- Ref/Main.cpp | 95 ++ Ref/Top/CMakeLists.txt | 2 +- Ref/Top/FppConstantsAc.cpp | 20 - Ref/Top/FppConstantsAc.hpp | 33 - Ref/Top/ISFApp.pdf | Bin 69908 -> 0 bytes Ref/Top/Main.cpp | 95 -- Ref/Top/RefTopology.cpp | 184 ++++ Ref/Top/RefTopology.hpp | 91 ++ Ref/Top/RefTopologyAc.cpp | 1349 ----------------------- Ref/Top/RefTopologyAc.hpp | 249 ----- Ref/Top/RefTopologyAppAi.xml | 896 --------------- Ref/Top/RefTopologyDefs.cpp | 11 - Ref/Top/RefTopologyDefs.hpp | 133 ++- Ref/Top/instances.fpp | 294 +---- Svc/ActiveRateGroup/ActiveRateGroup.hpp | 3 +- Svc/PrmDb/PrmDbImpl.cpp | 9 +- Svc/PrmDb/PrmDbImpl.hpp | 11 +- Svc/PrmDb/test/ut/PrmDbTester.cpp | 21 +- 23 files changed, 538 insertions(+), 3089 deletions(-) delete mode 100644 Ref/ComponentReport.txt delete mode 100644 Ref/LINUX_SlocReport.csv create mode 100644 Ref/Main.cpp delete mode 100644 Ref/Top/FppConstantsAc.cpp delete mode 100644 Ref/Top/FppConstantsAc.hpp delete mode 100644 Ref/Top/ISFApp.pdf delete mode 100644 Ref/Top/Main.cpp create mode 100644 Ref/Top/RefTopology.cpp create mode 100644 Ref/Top/RefTopology.hpp delete mode 100644 Ref/Top/RefTopologyAc.cpp delete mode 100644 Ref/Top/RefTopologyAc.hpp delete mode 100644 Ref/Top/RefTopologyAppAi.xml delete mode 100644 Ref/Top/RefTopologyDefs.cpp diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index c709f4d699..a175684166 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -215,6 +215,7 @@ config configparser configs configurability +constexpr cookiecutter cooldown coor @@ -660,6 +661,7 @@ initfiles inits initstate inkscape +inlined inode INOUT INPCK @@ -874,6 +876,7 @@ mycompany myfile myproject mytype +namespaced nano nanosleep nargs @@ -1123,6 +1126,8 @@ reder refactor refactoring refspec +REFTOPOLOGY +REFTOPOLOGYDEFS regexp regexs relaxng diff --git a/RPI/Top/instances.fpp b/RPI/Top/instances.fpp index 8157c439fe..3ed9f5b002 100644 --- a/RPI/Top/instances.fpp +++ b/RPI/Top/instances.fpp @@ -50,12 +50,8 @@ module RPI { stack size Default.stackSize \ priority 20 \ { - - phase Fpp.ToCpp.Phases.instances """ - Svc::PrmDb prmDb(FW_OPTIONAL_NAME("prmDb"), "PrmDb.dat"); - """ - phase Fpp.ToCpp.Phases.readParameters """ + prmDb.configure("PrmDb.dat"); prmDb.readParamFile(); """ diff --git a/Ref/CMakeLists.txt b/Ref/CMakeLists.txt index 1fc6ca4e41..cb843b7e23 100644 --- a/Ref/CMakeLists.txt +++ b/Ref/CMakeLists.txt @@ -47,7 +47,7 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/SignalGen/") # Add Topology subdirectory add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Top/") -set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Top/Main.cpp") +set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/Main.cpp") set(MOD_DEPS ${PROJECT_NAME}/Top) register_fprime_deployment() diff --git a/Ref/ComponentReport.txt b/Ref/ComponentReport.txt deleted file mode 100644 index 5ae06642df..0000000000 --- a/Ref/ComponentReport.txt +++ /dev/null @@ -1,51 +0,0 @@ - -Component Interface Report: ---------- --------- ------ -Input Ports: 113 -Output Ports: 163 -Commands: 49 -Channels: 39 -Events: 136 -Parameters: 4 - -Use the below to tune the lookup algorithms. - -Command Opcodes: 0,1,2,3,0,1,2,3,10,11,12,13,0x00,1,2,0,0x00,0x00,0x01,0x02,0x03,0,1,2,3,0,1,2,3,4,5,6,0x0,0,1,2,3,4,0,0x0,0x1,0x2,0,1,0x0,0x1,0x2,0x3,0x4 -Telemetry IDs: 0,1,2,3,4,5,0,1,2,3,4,0,0,0,0,0,1,0,1,0,1,2,3,4,0,1,0x0,0,1,2,0,1,2,0x0,0x1,0,0,1,0 -Event IDs: 0,1,2,0,1,2,3,0,0,1,0x00,0x01,0x00,0x01,0x02,0x03,0x04,0x05,0x06,0,1,2,3,0,1,2,3,4,5,6,7,8,9,0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,0,1,2,3,0,1,0x0,0x1,0x2,0x3,0,1,2,0,1,2,3,4,5,6,0,1,2,3,4,5,6,7,0x0,0x1,0x2,0x3,0x4,0x5,0x6,0x7,0,1,2,3,4,5,6,7,0,1,2,3,0,1,2,3,4,5,6,7,0x0,0x1,0x2,0x3,0x4,0x5,0,1,2,3,4,5,6,0,1,2,3,4,5,6,0,1,2,4, -Parameter IDs: 0,1,0,1, - -Stats: - -Component,InputPorts,OutputPorts,Commands,Channels,Events,Parameters - -/Ref/RecvBuffApp/RecvBuff,1,0,4,6,3,2 -/Ref/SendBuffApp/SendBuff,1,1,8,5,4,2 -/Ref/SignalGen/SignalGen,2,6,3,1,1,0 -/Ref/PingReceiver/PingReceiver,1,1,1,1,2,0 -/Svc/BufferAccumulator/BufferAccumulator,5,9,1,1,2,0 -/Svc/BufferLogger/BufferLogger,5,8,4,1,7,0 -/Svc/BufferManager/BufferManager,2,3,0,2,4,0 -/Svc/CmdDispatcher/CommandDispatcher,27,26,4,2,10,0 -/Svc/CmdSequencer/CmdSequencer,5,9,7,5,23,0 -/Svc/GndIf/GndIf,3,7,0,0,4,0 -/Svc/ActiveRateGroup/ActiveRateGroup,2,11,0,2,2,0 -/Svc/RateGroupDriver/RateGroupDriver,1,3,0,0,0,0 -/Svc/ComLogger/ComLogger,3,5,1,0,4,0 -/Svc/BuffGndSockIf/BuffGndSockIf,1,6,0,0,3,0 -/Svc/TlmChan/TlmChan,4,2,0,0,0,0 -/Svc/PassiveTextLogger/PassiveTextLogger,1,0,0,0,0,0 -/Svc/Time/Time,1,0,0,0,0,0 -/Svc/ActiveLogger/ActiveLogger,2,3,5,0,7,0 -/Svc/PolyDb/PolyDb,2,0,0,0,0,0 -/Svc/PrmDb/PrmDb,3,1,1,0,8,0 -/Svc/Health/Health,26,26,3,1,8,0 -/Svc/FileUplink/FileUplink,2,5,0,3,8,0 -/Svc/FileDownlink/FileDownlink,2,8,2,3,4,0 -/Svc/AssertFatalAdapter/AssertFatalAdapter,0,0,0,0,8,0 -/Svc/FatalHandler/FatalHandler,1,0,0,0,0,0 -/Svc/FileManager/FileManager,2,6,5,2,6,0 -/Drv/BlockDriver/BlockDriver,3,3,0,1,0,0 -/Drv/LinuxGpioDriver/LinuxGpioDriver,2,5,0,0,7,0 -/Drv/LinuxSerialDriver/LinuxSerialDriver,2,5,0,2,7,0 -/Drv/LinuxSpiDriver/LinuxSpiDriver,1,4,0,1,4,0 diff --git a/Ref/LINUX_SlocReport.csv b/Ref/LINUX_SlocReport.csv deleted file mode 100644 index b808eb2b11..0000000000 --- a/Ref/LINUX_SlocReport.csv +++ /dev/null @@ -1,67 +0,0 @@ -make[1]: Entering directory '/home/ablack/fprime-sw/Ref' -/usr/bin/gcc -o /home/ablack/fprime-sw/mk/bin/ncsl /home/ablack/fprime-sw/mk/tools/ncsl/ncsl.c -Module, HAND, AC, XML, TOTAL -Ref/Top, 342, 279, 780, 1401 -Ref/RecvBuffApp, 111, 1535, 90, 1736 -Ref/SendBuffApp, 176, 2354, 165, 2695 -Ref/SignalGen, 171, 1290, 32, 1493 -Ref/PingReceiver, 80, 1192, 51, 1323 -Svc/BufferAccumulator, 280, 1757, 33, 2070 -Svc/BufferLogger, 447, 2445, 33, 2925 -Svc/BufferManager, 327, 893, 23, 1243 -Svc/CmdDispatcher, 237, 2910, 232, 3379 -Svc/CmdSequencer, 1820, 4322, 47, 6189 -Svc/Seq, 0, 138, 13, 151 -Svc/GndIf, 0, 1312, 48, 1360 -Svc/ActiveRateGroup, 92, 1121, 61, 1274 -Svc/RateGroupDriver, 69, 231, 25, 325 -Svc/Sched, 0, 137, 12, 149 -Svc/ComLogger, 261, 1462, 30, 1753 -Svc/SocketGndIf, 401, 0, 0, 401 -Svc/BuffGndSockIf, 270, 860, 25, 1155 -Svc/TlmChan, 213, 766, 41, 1020 -Svc/PassiveTextLogger, 0, 152, 19, 171 -Svc/PassiveConsoleTextLogger, 76, 0, 0, 76 -Svc/Time, 0, 140, 13, 153 -Svc/Cycle, 68, 138, 13, 219 -Svc/LinuxTime, 47, 0, 0, 47 -Svc/ActiveLogger, 513, 2358, 254, 3125 -Svc/Fatal, 0, 137, 12, 149 -Svc/PolyIf, 0, 161, 28, 189 -Svc/PolyDb, 66, 255, 18, 339 -Svc/PrmDb, 301, 1921, 155, 2377 -Svc/Ping, 0, 137, 12, 149 -Svc/Health, 201, 2210, 194, 2605 -Svc/WatchDog, 0, 137, 12, 149 -Svc/FileUplink, 389, 1600, 27, 2016 -Svc/FileDownlink, 411, 1626, 44, 2081 -Svc/AssertFatalAdapter, 206, 1406, 6, 1618 -Svc/FatalHandler, 69, 139, 13, 221 -Svc/FileManager, 256, 2117, 24, 2397 -Drv/DataTypes, 55, 138, 13, 206 -Drv/BlockDriver, 73, 1029, 70, 1172 -Drv/GpioDriverPorts, 0, 274, 16, 290 -Drv/LinuxGpioDriver, 317, 1169, 25, 1511 -Drv/LinuxSerialDriver, 352, 1284, 29, 1665 -Drv/LinuxSpiDriver, 163, 924, 23, 1110 -Drv/SerialDriverPorts, 0, 290, 29, 319 -Drv/SpiDriverPorts, 0, 143, 11, 154 -Fw/FilePacket, 632, 0, 0, 632 -Fw/Cfg, 226, 0, 0, 226 -Fw/Buffer, 0, 456, 52, 508 -Fw/Comp, 265, 0, 0, 265 -Fw/Obj, 172, 0, 0, 172 -Fw/Port, 367, 0, 0, 367 -Fw/Cmd, 199, 442, 57, 698 -Fw/Tlm, 275, 149, 20, 444 -Fw/Prm, 143, 267, 40, 450 -Fw/Log, 485, 330, 64, 879 -Fw/Time, 277, 138, 13, 428 -Fw/Com, 95, 143, 16, 254 -Fw/ComFile, 84, 0, 0, 84 -Fw/SerializableFile, 91, 0, 0, 91 -Fw/Types, 2191, 0, 0, 2191 -Os, 2245, 0, 0, 2245 -CFDP/Checksum, 139, 0, 0, 139 -Utils/Hash, 330, 0, 0, 330 -make[1]: Leaving directory '/home/ablack/fprime-sw/Ref' diff --git a/Ref/Main.cpp b/Ref/Main.cpp new file mode 100644 index 0000000000..568ff89682 --- /dev/null +++ b/Ref/Main.cpp @@ -0,0 +1,95 @@ +// ====================================================================== +// \title Main.cpp +// \author mstarch +// \brief main program for reference application. Intended for CLI-based systems (Linux, macOS) +// +// \copyright +// Copyright 2009-2022, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// ====================================================================== +// Used to access topology functions +#include +// Used for signal handling shutdown +#include +// Used for command line argument processing +#include +// Used for printf functions +#include + +/** + * \brief print commandline help message + * + * This will print a command line help message including the available command line arguments. + * + * @param app: name of application + */ +void print_usage(const char* app) { + (void)printf("Usage: ./%s [options]\n-a\thostname/IP address\n-p\tport_number\n", app); +} + +/** + * \brief shutdown topology cycling on signal + * + * The reference topology allows for a simulated cycling of the rate groups. This simulated cycling needs to be stopped + * in order for the program to shutdown. This is done via handling signals such that it is performed via Ctrl-C + * + * @param signum + */ +static void signalHandler(int signum) { + Ref::stopSimulatedCycle(); +} + +/** + * \brief execute the program + * + * This F´ program is designed to run in standard environments (e.g. Linux/macOs running on a laptop). Thus it uses + * command line inputs to specify how to connect. + * + * @param argc: argument count supplied to program + * @param argv: argument values supplied to program + * @return: 0 on success, something else on failure + */ +int main(int argc, char* argv[]) { + U32 port_number = 0; + I32 option = 0; + char* hostname = nullptr; + + // Loop while reading the getopt supplied options + while ((option = getopt(argc, argv, "hp:a:")) != -1) { + switch (option) { + // Handle the -a argument for address/hostname + case 'a': + hostname = optarg; + break; + // Handle the -p port number argument + case 'p': + port_number = static_cast(atoi(optarg)); + break; + // Cascade intended: help output + case 'h': + // Cascade intended: help output + case '?': + // Default case: output help and exit + default: + print_usage(argv[0]); + return (option == 'h') ? 0 : 1; + } + } + // Object for communicating state to the reference topology + Ref::TopologyState inputs; + inputs.hostname = hostname; + inputs.port = port_number; + + // Setup program shutdown via Ctrl-C + signal(SIGINT, signalHandler); + signal(SIGTERM, signalHandler); + (void)printf("Hit Ctrl-C to quit\n"); + + // Setup, cycle, and teardown topology + Ref::setupTopology(inputs); + Ref::startSimulatedCycle(1000); // Program loop cycling rate groups at 1Hz + Ref::teardownTopology(inputs); + (void)printf("Exiting...\n"); + return 0; +} diff --git a/Ref/Top/CMakeLists.txt b/Ref/Top/CMakeLists.txt index 499f256bd4..1399d95ebd 100644 --- a/Ref/Top/CMakeLists.txt +++ b/Ref/Top/CMakeLists.txt @@ -8,7 +8,7 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/instances.fpp" "${CMAKE_CURRENT_LIST_DIR}/topology.fpp" - "${CMAKE_CURRENT_LIST_DIR}/RefTopologyDefs.cpp" + "${CMAKE_CURRENT_LIST_DIR}/RefTopology.cpp" ) set(MOD_DEPS Fw/Logger diff --git a/Ref/Top/FppConstantsAc.cpp b/Ref/Top/FppConstantsAc.cpp deleted file mode 100644 index 92d79cfe4f..0000000000 --- a/Ref/Top/FppConstantsAc.cpp +++ /dev/null @@ -1,20 +0,0 @@ -// ====================================================================== -// \title FppConstantsAc.cpp -// \author Generated by fpp-to-cpp -// \brief cpp file for FPP constants -// -// \copyright -// Copyright (c) 2021 California Institute of Technology. -// U.S. Government sponsorship acknowledged. -// All rights reserved. -// ====================================================================== - -#include "Ref/Top/FppConstantsAc.hpp" - -namespace Ref { - - namespace Default { - - } - -} diff --git a/Ref/Top/FppConstantsAc.hpp b/Ref/Top/FppConstantsAc.hpp deleted file mode 100644 index 436a4edefd..0000000000 --- a/Ref/Top/FppConstantsAc.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// ====================================================================== -// \title FppConstantsAc.hpp -// \author Generated by fpp-to-cpp -// \brief hpp file for FPP constants -// -// \copyright -// Copyright (c) 2021 California Institute of Technology. -// U.S. Government sponsorship acknowledged. -// All rights reserved. -// ====================================================================== - -#ifndef Ref_Top_FppConstantsAc_HPP -#define Ref_Top_FppConstantsAc_HPP - -#include - -namespace Ref { - - namespace Default { - - enum FppConstant_queueSize { - queueSize = 10 - }; - - enum FppConstant_stackSize { - stackSize = 16384 - }; - - } - -} - -#endif diff --git a/Ref/Top/ISFApp.pdf b/Ref/Top/ISFApp.pdf deleted file mode 100644 index 9b161d0426f90f32429c40cff24df3296e0874b0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 69908 zcmagGV{~Le*ET#!Cg#M}#I|kQwrv{|+cqY))v;}(GqIga-pu{n&-cFnzSV2>IaRez z)$Zz3wfA+^-kVfGM2wb^jv0n@@aXpFtn4m-c5oPmg^+>J-pC4uhlh|}#?;Q-#e$Ia zt4fKGUd+Tw#|Pu=;$&)Q3*!NDk+YRZGvc^&^+pN2#SO2^ zK8ee)+)Bu&Nh%dWcEs(;M}>jnDW(AV4jrF-h*69`(d(~jruHB=Bd2~P)L@Fz&&=8%qcUtuw zZYV!q#!eXU7j)IP9){Gn5czOp&vL8@Dmr0C%_XP!1HP94KNz6`!aJC`mhx!T?**@ zy!p#;pZ_xU1_+(uA5(a{`HsYr=P=UjZN78fdUXW3{;_ilC3ch0AAKVLwx061IkV%A zeRb70=HU;I4q^QCLA~RVyLAnCf{fYrdjtE~IoL{n=k52=lht>Nb9pdci%GY04k2ud z$dt{$&sXO&oU(bX|6+h}-m2ey#p2F(s(-Ehey`lazyRoaJ`w(VVjZR~cH8}wqh|bI zY2DT{Qw5xQNNS#a_30=b4%6{bu6Z>$PJU3D-{dTUw2TGQX5H^2@)-~02mIf23a-|GXw(_dV(_oLPfO8$?@^xH;x>(ckb zXBV!iJ2-+Id2)@$w|#2IQ8wxuLEn?+nkXHtP%|09aZGjVwB&XIAOgp!`--W#yKDu9bqIA@&H{rvdI;6V;3IQ zA8k)2*USJyeL~C zYOq=bNL~uX?3fD{BWngz7RJb+Lq@DE2Q|NeZaC_}Et4Epv_56Bh>094~sSHGLwc#|h8jD`C6EoeM*{aK?^lhLU*R*Mqc)~0Ahd~`)QL`izs?mCS`iIXBPTWt$ zn5(y>{?Y^LS>RDdEOL-!c2xm55XE@qD8f;5cFS-OYidECeAM0#d&WV@OeCcL$C>cs zekMZzcVqoCCGG;?{W{_qnp$G=muitcLjvD9y9S~liQHni@4?@ij-7n|iIx0fSN?TP z0{@LcbqsVD9wR}ygXfU^UDlbjpUVVnH=cY`E0gNITcz|&cMPJ$-95Ex#EeSd8-lSb zlN8cT5Lpew8%1Hb7bYD<6=cQX+kJ-IVrNOa6d}uo5$jKsvNZWD4gHv;F>J8Ex4)XA zGLq)hkPn@L(Q__VPMEiMLGE;RPtV{eWl@$FSvIZeAvf@WLd6BO+cvB7-pi+SV(G(l(dE))A)Nn=^82aF@X2tv%9%6o?%gI# z-SMX2>Ci1`;v+9MOuA-6?n`0XbGbXcLjA%|Z58L>2$vsg}fvX|%kX}oh;YkIuh z>U)=a`@R^*tixRgZL0qZBvg}o*xXFd7Ps{h_05Ln0m_6qRgT#^rs|%l%9@ygmW@Kj zlxCJpV}<;vHQW<+eX!0_-#c^dxNHu)O7`w}4k#(015wyXn|uNT@*1;F#ODm3q2TNt%CFX~(RRHJV|xvNI0VUK zA%S(?-<_pnT&;n-4JncVhoUI>n&Z+uG%k5BnblgT>pNWELJ(tj(1DMVSpj9+u9u{o zK{WuB?JCZ;rS?|QBQslL7;D_1hS!B9H)RCtQW^!5ajimDjrDs7G+UK+&!$*5TQA)s zGZ02Dn-L3NWL!}tBTbi>F_0GLrZsmqveer-V6{=-V>H`D5~JjBr-fp>+tz%Te_wNh z@!J`+`wZRTpCqG)2;h*D3cKvnOa3kLqjK4(2n1;nR>uyd%6PL}jm%2%w zMK4)C;!qD&{PMqmhJ3x5Xu|SvzN9g-fe=+0IzkKJkx~^10HJ*LIwQd>7m30Fh5TTE zTl8|WY5uGQUYK@=62EK_Yc(4Q+Evk%6srNZSQg1)XukHjqp-TVg<^ijSvcQ@pqVC* zfv6}|EOX0Rh(Gj9#Fb+`+nZ&VwQU&ahk(H^^_0ql8>oi~YuJY~K#%H5l>$F-C+3(% zGp=if11T)K^v04aCu*%t{fD5u87W>2N%Qp>UH`e`YAhO8*2^CXWUb%`*C@^f5&76h z71}OOBk%AF%xd|dB8je3l*as=(m6TJ9|g#_u&~vDSRurWb4=UY_A9c*_EN2C^Tiy%%!<-YQ+l_PCrFRR8fk9mdK7GywzxeV!sdA02 z$;)hvS}r-ywsf?d4f1??Bb9bVcy$?BuWqy&^S}{p*sgqk3nZ94&NIEDI3Hc(Cl*LX_fQQn>#>KYogQ&gWs;LCJ zeqH%CSS3YBw(Feg&AR!Y?232%JC&`dS+~#_BvZ~Sq|W0<`g5}4g(DxV)vO`|h!%xI z4!$3(grmZfkp2VhGh7g1_k+TJE0GavKNej3E*KKQw(`cJy!?8}CAuXm3m~0KO@5Wc zPyVT42yebnYMw9RjOh?iG&o;GPhPAmb8E_n3XOlDzsIRF(;Gd(Wre9KV`4;xd;i+o zx2TnUNoTG^m^N;LriSQpMmq+l!v09xn0!8GLG}J(LrY~Cv6F5f+TOg8m_INaYy^Q` z+CDr71kKzNzwBh+XprOh6}gyoeH-_Z2sRMU>G|Z$lNsu?H%O63<$mdIfPV=Io zNiI6W3Hyk+%^u~HcjpSTPmU<3#s%|hkUwN4lO{Hd7c9fMNiPw9b026q>4_0OL;Y!m zt5r>}Zqz=GIPDp|PMA{)TLZ(?Fa92qc4tWzn7~h8oLYaDIw~zW(K`!aNt;x^kvo>o zF~0Db%w?OJHR9P3z?$GEbQXv%9+-pGkHINOHNP`j&bodn)A2iQ8BYzw8oOG<^8U-j zK(le$D8j2Q(M&4Q6XV9*fULr+?(Ci+Z(Lz*ZM7J2%JHPXEz()s95dlbSmVQSawis(6JYb+|EEST@}gamNZv(pFh{l@9UuqWxsw8MqFAs%>* z?;k}Gb4l1IVal8FT3GQS^zrBQY~XgW6|$DDa1i1~j98^cW%|}n zUu}}?!iQDm+r$SQC}aVjRrtUyF3slNad%!L(;Zl^+_x^Cm005O#)^m|x0V-^4s+xCDxj){K>=~l_~p}@+9NqM zsf}oaFiF#w)T%Y0IcrH>dgK(Bmbl;W+$%A&y{P~#aEXFt7}g@#R4~hMstYFxi6VrJ zZ20e}h3?80<8SC!e%YT7zL8gnM2&; z6n~H?M?E6QdT6aM}GAomgQtxRKm>X#<-Z9}A*cyE`?qkSM4Ll%$CziiEX zp80|Ix8;s&7Y#*EtMxqL4eNL({@Htw)G@1e3D>UOtAP-e=s>CR)aquC&OkPVEGce( zFn=i|)z$$VAY)?|g-!dju^4+cG2Pn6uD%vYDJK*$;gfy|H`ML(%Z3NFhk=XNvl z%1YzSg0T)al=+4=#ycXla<#1{FoN=utUtX$@xxJ3&VX&N)hpA#tH;!` zAO&9TCGp|nq1&cmcPg;@&@o@gPxZ;p<&|dC=@B`3AS*nec_Hr3EMMcgG-c#c9QI}u zRd!L&W5M9U0@hy5B8L4qSsrxlO2B$N*$yT{ngx0|3&dLdj3J@`r=-yk4-}%Qvy4kC7u%SUEFtrP{mo|ZrH|KBCCleBx%xTdIZLr@ z(=%Nd97|!P*$ud7GwTx?1#OXSq^O(rZZmZmkHvWnxR5=XWo1w1?n1*D3J_b5=(EH} zZqw$tZ~tsMgY!yvR_SsjNMniYpy1}z?dGERI-7b`J)Ka{JGyBkS7-OHW0cx#P&L)3 zWLf_%7Nm#R$&QuukY4yc2U+FWv_zs}0SN1`+T?C=61<w!Z;CI1j+!5=}rH!c|q6(cc(3g9GYe_T3r|kWG*QxH9AdCE( zjp4!7x()HO4{fuq8%s78EsPob-y4B!z`3xt*vC^Rn@0shzeTVLc{~j0Hx7xL-bs@f zlY-u@l=_+3+i)gj@k+$0X|MamYxO>tr}Q&l>G>%UymtqpAu;T*T<}52*}#=RFT4Sz za`^#*3JDZbB1G_yUb+wo<-)rV4s3ByDBhQskA&D@_NN}pfhktk;r7`u8t%T7RnMl6 z7Qp%=q?WZpu`Jva%v7zO0mtq&;9LnJR*k|Z$z^=ff$~c=eiK!rm2SdvlXXQVLdw3p z5`mED>N^n0V*B~7hU}9Sjl)S;hVSghAlJ6n3yH4sak#He7Tcp9t@;3>Z6u4f7{+Q$&XKMJQaNXHfBc)z zIY?rdndnWBk0PbMhN`3W<~Xm0QXXFJ7K!i2v2|s2l>xWKLLr!R(;9la7a&GGpY|oS zOOS28<{#1`?^m=y#sx}3dCy`qm!<|mrGzZ7CJ1EE6VC!nbm|X(N^hl%jet#KZVZDkH2rRXhnQ7 zLB|$`T^vKxQ+0G;(8~rn*4>Te&T+}7Ya8Iv-sP||z)Ll1c0`a*Yb2y!18^8a&E=BV zZUe9i;kT_g2LQ8kSjWJW&u%<>gN?CYwJyT-U3&dEhQyrSroq$8R_yj1>zV8xU_a5w z&&{l;zu+|sG$SMOwV@|#8%MdmYhd*cGG9f5PERn@84JCl2XVBfJ{?xp8;CWRJG4j- zoY24v62RGK2ytlI9i2t5jN4kM0#^MRxzAU`!uAcrer?ec>#eG1 z)*tf(T~~v#=#HjuB#l#iQZ8;q?Wr9zb(PHZq&(o1Mz0XiV;)xX$h)Xhx5^zmJgp$s z`fHpSQ0oON7LAAjwC-xewF1(kEb!VzvO_~WU74@{7zWn-joUu?OQ zMXpb(_L8jdv==?Ue;R#M7fngW=aUwzm^y=tq`^zGz-vicgW$tj1XAd* zcD04)$66M}PbBgUm8OY!PnjDNmOiDcV%e78M-yLkfwhEVST(VjQ+WT1PeQOh-uxxW z6+JC_C@NAkqPGX$C&~2F2CF)!Eq6;S^7EYJK zX!@_eO0=30ItjKi%C|B1bpFk09Ht@*|FB95R!8?qTJ-F1U9OTOSE16PR z{ljNO)rU7L<#STi2ka4#9I#2k>iu`piXggM)dyq7Pu-}&4QAH6Z#`mDnIB9v_ft^SXFhLn zTKP?8$5L)76z|knIxE~qZW~7~$p9$b_XRkQ1fX$i3u1@|qA;jz zjf`R=ilwoSQ{kSwIT@F59N#~wdN{J&y7MJ6Y9rX2*UxkE?##TcJg-Y3X+-%;zm3&T z4KB&?PltcO1z7?e9=%tXrraDlGN$cfY?rGqrWrSMwj*Va^XcMigSgq3ow-;h;jrhj zfz&#lav~nUULVMs;0@Eha7VS-lXWW%5vc6yutgJndrAVzwrc}UKYohc+S8+y;qflW zOf3?mE^&JDYE+JQ!D-yVgyLaRP~F{TXH$Bc_~v(eFfXomxoF&d4T^5zj2n38eGzBY zWGI!Z%;lB2!N3XD0#;4gt0t7{~EL_w8#eEyhI$Z3%~{emSbdI$1l@yH0}m$#}&N3L0L zn;l0)nIRrQSHCCDQr6FOC+#jNV~jM%vRU9CYkic9vmnNmS#=2NHb~rW0?VN7U){B3 z-22_j?E(tvH$Q4qUl_yZ1ktO{KOR7rWfVEBqf8OL(3wfC@+=B`7pUzxiq!t)KK9{x zomrD9GVYN2Y}t>~wGWUfi-@TIXV({a{8|1o zr}zf3o>hr)n62SVUzn^$2Rm;GVT^V_Q-g!oJ_p#E09V^3OZ{CcftGmiyg|BDRsuwS zMa@MBA2Dx^St^SE5`r_U9$`^5M7X4{u07*oisSNA4aX!-mopT!P&bf7iGN6Bhsig;kOnmmWuG^kGY0b7wtmx1 zXxKk`B-mcS-;{ha#_eTnsncB z4zE9Q%h!4vqB8-AtFd$Io$^QNRjf@^ezIU?6#^d+bgGv&e~hJrwep@^jy%tL+@EV+ zCC$lZPa{H%u2zbQS3aeAfy+;H*w+Bh+WYjZzq6h$H5%PlU%L>LtP+pcCMS&NWcLob z@4Hpu`sg65*0d@DS?o9We;QkNgAbZjE4-bz4y@WaL42A8nhpndId<9GTDF984txDi zHLIud)q6Rl46baA7`ErUT&a_cO=az~f6rCUbksp#*owNNhuEm$?Nsca5!F<{`U&~- ztm0zVN#ZA(#YZ~Etk(`Vo@TQ=%0Jpp=&Y;#4QkjyQ@)32<=<+n@^>E|(`S{S?HV}y&WyaO%`L&aw!6-8+r~r@tqQJwh z7YYp&aeQ^tBqtVF$V5M~l}TySb80j3Z&4XH0o`$R4=kEm3~OhJp&M8*b%Sk-{6G-_ znj_nU=I| z))e8*amy8cfy<$d1W@y_%k0d`oUSaR%wI?>CzJdMTunv40KU@S?31r+F)hS9vBl zonhC3!=N^5qaHLM0*B!x*EzpOEt2EtzY9_0rKFfI%p@B8D67S`BA$HMiz_Q|GnEMqzWH0Q-m{= zPls}V9vckg!$iv5@L~c6gIc?J6AO;Ovn-8h6x61aaY)c>!9M4BX?YN-J zlYIH{2$c#7kb89#c4a!D#E*AffmPm4&s#;yd|G)S0{s?vY}F_`c;f9#@v)B@aoYD7#KkXNg4-?(C+Zw? zTdzB8=6x2|sg;{LBGs)7AemZs5}QC=oK>``42!L7c#w}xkZ{1m0#WZ?NciD$C3l>D z>h%g!a<;Up_{7Vf`hzn8n}41XoJUtDulFb3CBFtckJ;zZOIh}?D4g`UJOy^Wd)aAG zsI|g+1X4NC7%pf(oZ1pjof{W!RS>%ZNmD7gyZsARMgc`9YI54Sz+ePmT^#4j{KvHI z+q7*4vz6K~Gr3fiNy_K-2j2*0i;5ldbvm=i!0fdnddI)!D8obnna_oZ3|P%XN!ada zDZ-vjaE7ccQ@ixn*l>*N)NgZ?wcMFV$CKok>U_?woZlo(QkBY_tyJ9wa7 zBCkbbdWQ$Qvlvbsl|`WG4~&%~ao&Bc(mRPUaYRtA)1cI2IMdhBP}Svcmyp?Cf~kC zW?w-=Is(gzL-8NhSpPj25;{ZqNw+n0AI#ca%<914+oywcj#>RM)up2QU41qeVxx1= zbt64Dc4uYr)th|bs$n=qKOwKfn`LX~6*gPq;p=pPR>1)kV1LqeM87`_;LH z$%c-xo%M*#j$Yf%BkG}x-feeqDvsOc(BZH3@ajZIyvT**oNXYdiEaK*LFNR?nj-ZP}JN#>Zy(_BW6wJelH=B6rbY$ z&l-|Bk+9Sg$02)K+c@}QQk1q0oer4DtBXC=KZe^4H9np8skZpBP+VtzrQPZT4f%g( zZ`A&a$4AH4)Xt`kk(a}^BEZQkn1=iJ{(64Nl3K4uk86U*5(hw4W`3o0Qerwjf8*ZqO`wtp7$8p5-iTcd0wGXC}-* z;h3%Crua<{`7@F$f9erSRPKS|Tp&uwS;aF3f#KFCsprXzP#0y3tjTwMX<`b+3chJf zqu7~^e1%@ElOiYME5}^U!&DQ#-L9qCdGTzQ#9_O z&-3*V80mwUc=E11$D9L@VV{AdPw}dx)zlFnSm7H%KpcC=;k%MStQ2!gKPFm@B1Iu1 z5licPT8#WrlO%QDDMy7Bcvg(;E3d8hE>#hBgQ7|*SD>;A3Ki5>};q(On1{~=aeIb%gO8x1s+0^vsO%IRrtJ4XdlaXa)k7!Mf(^5KVX*VGCd5*vFX5ulM__8f^ z($GX;t9xDb)?jrC;3vRkIg}+l)2K6X#1tX3Qmkcrd>@lsL9F*9O?K~3W^E1|97E4b z11|O>v1zNTii_+1gs@?8*D8Vh1D@&WTRMUUQ(w+S-t!jlEqTZ6=q*&N4D889BZFR+~_8DKL^1})F8ZA}Gx_G@~hH2Z|}XwK!;d-mxw81|t3 zgRl6+1{Yns;!qrsUWkrsrYYol3{6`@)cLGh8^YhKESsWuMgAdgG8aSuLetnW!kpIz zAY^&46X2FFdk3i{-=QZyF^IWQa;Ioa{VXAjG|oYsWN9f?=9)u~=l$!dLvR7C6{7~x zrCN@|!~~aWtMLcmMSvS@+I68NK)os0v%6O|JUANeBSJg5C*ojtn)dlVskW*a|MifP zz*#ezD5C(5%wWoT@&%x|3>jG)FAKr#SSp=Z|27vyyush*&C5#iKdv?478760B(oM1 zUb>Z&X~~AacVCw4`I>Gd#m5zj-a+63!+RBZy@j&z&Q8e2v$kjG^(}?)kFr^U$&CA( z9V`E{R|<>oj@dU3LyTwr5S){5gr7=uMtCU`io~zaTk?tOn6+qp`i1N__8nEy&>7Ln zRKaol%`?4TaVWrii5iD%rloMb2mD%Yi6U+0=09%lEb~m^FCymSK_nJo zQ(l>f*;+n57IAhmZR-WCOCu>h9oNX=o+eYVb&Z%I)9_<;WRbFwgTM80L+_OXOMsp+ zwA6>- zSa*5$5g$(2%0xAb;6Z>tN1|91-r*03q&Ul;C#9n)?R5SQg=cjXgx*v{Ev5Y{8JYK2 z_Fi>AlI$iyIhBKqF_rddvKsu=*dI!--&!LRT!HbXX5+mvT?!J=fdvF#A`!TS56DM5 zE=|g`lGA(k@aE{X-j=VoUi=_KH>N!mX~594eLyrC5$ISKc_qkWSq~r1Giy*U>q1MS z)4d=NfpX4%AzixN8^*S0Y&+*TP}h&+4crWtElkERlF!aeg{p_0q9nDl><6(fwV%cw zy~q1PHwJGL%+#nYFG3MsGc;bzN9JsC%jAJoBQVt$Q;YYtFvuLoTMHBE9F1KQD1`)h zI(WPv?$NwsJRAsAY-Vm8TQ!&MdEJ|cDtBqUQjqfi6Bwq5wOw9JN=~-tN9v*EWK>z? z=4a^w6302iqo8IN$u;&50q=}OzNi6yP!W=r zGzcE=_eNu6oA^k-OldL=$}dBE>l;>gi&RlFW%X=joRJq*&%Rerj_=j?aEU$=Hu>ks zQ|uh*mkiy;jtN)DrQRkNVQPld(I*&986~}!{uD0&x>=qtB51ez84ULPHx`0 zamSjR^`q+@cO+6w1f$wY#Pq`u)c7Tllg-Ib1{Vj+GNCaN{=TaqcVOt~JNAVG2V=$? z8to-C&f6HP^mk8tuOdVoTT3IH44psc$0pufrs{rQRB1!X9BkydoGa?;JjhvEs5_3R zP)y62^i%Je_SwHzG?C>$9FU{PDYo#|TzK%jM$>EZ$^!Bde6M(z#q1TqPQHu+3CGNL z3G#78&a$x$%QQhAg)oB8Yeq}q`z#y13(|VLq#otSP^`SiwUU{*>jb&n{_Erq%7^le z^RuTHDeZQ5eGaZRm9&q&17v%t2%TMw?aVj)?+_4{IJV!({?w{p8I5x}fud}VdKvKd zCJ2S%bIa_@;B=d-32;!Z5U?R?aPz(fCV%lKF>v+7R$iNR*U2_vD7uVu^pftF(_;rKo`lK!9LR*^j2I9ZgR{=ut&g?2$M^O>< zhqATsJ*hXx0EE46mIAzl`R^uz2vL%^vf&;AU*)R7D(FxxNAEpfJBx$0qVZf6v>p=FN`t6hj~8vcJ6(XZwSSDsWETgJQbJ>vGkx( z-fYy#O6EC}xcz&xU(+@6(j59XQbANLT92QdTEkJ*q!dv=D;56)d>H#fW3d@tnRME3 zgIg~ka9l)1*%YqMjj5njOzW=zNCt;ZZ(fPekIaPPkN0wi#HP4qGQ&M{$JIKX#Nmf= zyiO(7**3WA#$AVYBh$#CEKovw0}U&B|DloKM##d>Tzl9ne9Tn+cd$WvvggfT%6aCI&p{ zibUlYV~7M{eERlf;9OTy?Z$3m0(b<=)UAy|5iol!P@W=cA)r}V4+ySd8^{I;u5y%w z-%MbO-|W~dDhB$+X2}ZWBdL!Jb{RF1(Y)JyvF_B%Iu&j55Tx8`?XJ@Pc(nF}hJ|O7 ziBl*C*?uFWMY(P)5(6LsVamLsC6z6j@%A_qvmSpAeu+kz<#PU5A(;VcKunIaL^X>q z;BFeIT$w1G{)UtCE#w*cJ0rCR6Nd5Pk>N%!zUsr1WGjD!Ut;6V^BexHOxd2Z ztj#emGlj@8JVMY(1qqa1j4@)hmVs?)gvCU zl?8>M^lLSbjOf0;iukRH=^<;T1N{RcDSl}UtXEh_z_UsvJCX|8x; zBw8b#NPnCgCgFgoSCWZtXI-E3^0cKpnJ$9Y7#Cb+hh7dO#(3Wmm3FPQRDNQzJx~bZ z$vz5Z6OEs~tJlrCq{g9-E5XLyQ_eWc;u7j=+L@#!!oOmV8hQNdcc+IL3||6-uSWdw zFjxRRlHkN!B+pxSwIMpOC50Qak_8{MS^J%FdeHc4yM%Z#YgaV*CR+zrWr1{=Pn9>k z>x-ONr`*D+0EfXGHB4Tgu4v%m$Yz|AiZA)hbfq15Q6G-l@?T_u|6XO(+X~8ZjcwsH)ulO zekpZ8T(`MgrkiDaK=(<3RT*27L|37kMQfrd(l49A0rs@kF22~9#8NSFT5&f`1)}25 zvd7*}JabPcU$=?3s4l<1pZSMHB(;zKRmkYdt$318o%_wfzgz1FR$@@RDa`O;HM_42 zcz9rLt>TQjbbKh5yT7fJ3js0MXJ;_Hi;%&%?V7v-ney7%{_+K=din#83SEsdFC^V$ z6M<*jb`Z)2j%%lLFKe+tS0_Z&gy1bpFmFS@J3Wz|MApwz2XLFLZe}l$yCQ9xgJ`xt z7p_b?y8)A3jGyB^Q6nhyFIl_mZNH$WDsi}^Ls2uIS~V`XX|I)Cl^yQ8@^=QLT@#Ey z)o#1j0;LgS@?)Ihi8Sggr@$AP> z{}WnwgxQ6E_72LHx&_dq-wCHo!7?YH)Z)}fyy~Hklf&D6U-G6xZ!lLgKy;_VAQW|Y zM#Ye>0Cugu>xwmI!bqP~%8`b1JIA5v*5=Z@CMRime2VNes?pUHJ)CBpZv9wud0|Wf z=`>r&eZ|=pT<+OcX_r#<&Tzg2Ez&DN4s-t4VaLUo<}6d z$-il!t_O4^ZDX)mcx%4Z%~96N00zDH*l!H>K9fx&n#bqim{ufXV-PJKz5Nif$XXu#sqVfM5|>t9k$ zOS7A*{{3x|wbAdth|<^>)WU_!$2V@RK#ZqLGl-cC_`o29U?D6vifM9pSI^Z9JF#>! zxy43`yTvdh#fE5xqQ5z7Ga5{m0;WyLbDo#~(LMp`8?(DuzNDj%)4 z1{l#bWW5_c$r9iQ{?hv%E$n|Pv4Q#{7@s!8xwU(n`ItXFT>TiMZ#bIg!HsxC(wXJYM%54RTngl0e1<)9^e zTsskumzv8wJ4oDJBM&mu9=IhZ*vh5)S4TGQptGC3lutGf{XV6N68tb}ehDR$JQ11} zMKnS#_i)pLM;2e~PFLeNs^8!Pt6l(B;{k4@)yW=fhisYVyPQ4TI_U~{LM;;tKW1>| z%QIRHI^!RG(A1@}{fc!e7waodTt2$<4!aB0+I$hV7867Iu0?0U=%4g9CdE~1avXIu zAslfK^@T2A5kHEfg6golLg3D`&v`O}G~izAexKv7)pC6=I+0b8@E*ec#lB_&v~BRg z6gN#H^(Iq|pO|Gm16JhT8t=F+gooVwlplvl!$g-;c3OE{Z%jDs z&ESiJj$_}2x4=82m|7E2ZH#MT(Je6A;OYw{ak=7uMgyoV##gsDAn z{T54bdB~>nKp+wvJURmwvybJB<3TSVa0Z)#&de7com%mFYg>D`HR30%tui-HyoI%u zlBu<~EjsaYd)Nlsi)8O7tXLEe$-2sD`(0A;_?Bu4HgyPIJW?B4Fj2f;JSpLhn%Hb8 zy>&3HLU-|WlQCv9?e(f}>lXT-O>yJ(Ji)7Ga1Q9}AbQaHB4-avzhIn$z}2}+TzHAu zpl4>)D`6*N11X&`sjTFck;qZZ>j^ahzhmb5#wm1$rBKJResxM20( z3x}-fJ5e4=8^cUS1i3aKv0TTqJGTuD;JCxdx)vifX%A1mAb6Q&#f080&b2!fTUpYt zwnvorocp9;V)@;Z_8sx*rTvNPZW;$%*U?$5lV*L5&D$g{Fs2KTdreipR}WS6Zpz3r zZcsv^*-+@19avhRQuYbc6i)sp94o))p<3wy`OqrwkERA}%81|Lg%BxjFFQ_jLyq=_ zJZicdIt)$DnEQ>hk8t|thSsQ&$U-rSAZKxP8bd)?`G~NfL0sqJ4H(4T84O(G+e>%n zV8pp_=9)=l>@=#=Ma1c<0WkXaA;zz>Wdpz3sHCjD8>>k~K#g9Sx^p@Z&R^GWiwB&; z(#`;}v_vLF?np|x^2FJPT3Ji?$xJ&cogxo)`Qa1=yN({V%F08LOfQf@EdZLfE*ZJi zmyx9Py}id`z`b$z%g&l*A0}{=k5f*0_0C4626=PPeFpCL9)C|Qab~HsbH8FNk5Z4s z_FDWqkOpKBt!kyz7)#&2qw_T`t@G^jioz(a^JEi{w`SPvt1>XQZZ1xGS6qr9C|6Si zXvl%QB$obxC_0mSje6(_WOT_KKhFDoMwRY#vp5^fEBtzpS!Hn3GqQ;{pRh@XNY&`& zfQf`cz@Y}O9Jtyxs$VXNh1?lE>eWVHZ%b_6M6)7B0H%c@X z&C38@936ODG=y2~3`?`K27;9r143`vGh-gcSe_xl3qk0?e99O=NoWeU&9ZtdXiULC z(CzhY1CkGA&s`#5|y8c<2fo3DB936di#ilne=&SpD@NNxstu4g!|Q+_gvt zVB{Pe?(-GTatFo>FV=R?BCv+UA9$u@mg)ztOFBhxa& zS$hGPk09zACR$_B)10kmnKOEj#d4IL~!@f{!s?Q{{U zF1v{u3zBV{ZtuEvg~A9`Wzv5GK*q3(hE0%gf?b+f+PAy$g8_6Ee)K1E^P4?=O_v1+ z+X7cF%pDx4QXLFq(?f!a;KQ**)vR~uE1WVN=*hHdHbo^~WbY$^L~450#82m~BRI_vjvMVJhTRZ|9x^p;zL`NDPGY zG`NathEnmjJeST=U;0mQb?g z#y;x-3ajAozMvSNlVA`e6W!QJf;MnQ zL>T=Kn4qP8YL;+xsjzPB!gz@e8Jc?xSlE2?eTPVS;Zihjm`H{=gSWqKvS}ULN3C%eWsLW7R!7Vfo#8W9M{uYXlI0VWwD8 z<=+k>eYdc7T2Ca9OUzmg)GhN>WdPuOaaiL;gMnV?T8n0>oQ`_SJkg?g_zBkziBfBl zsg@1NR>mmnTH^W^&8f?zc5wM=R2G#d8bN z3%ft9gSQPOtinb4(`c6b!dN9$?meD8Ba3ix&hfelSy3|th-u;dT>Y1`ZL(R8J-69T z8bg+iU~xXCGF4lz6?a1u0t7l`sPFf-CPWZ&IAHS!Q_YR2igDInyAKN_Mhe z-0;qw-*Yp>-&Q_x-lTAxVNC5z{u_V)b@wl9|6i>Bzbhjf6ASCV=6?mI|0kwj#nZu* zkY2&i{6F7Lrgkob%>NVLuVm_M@9Jc1>P*P?KNZ6Eb}nD-&V>JR0(>O^kTo^2G!(M; zAk=2~s$l12B4lG^(uMiT0r1~({yq1Qz*j z=@h0AtaMZE~L;)PFAT%4!PJPDsUh-PFgDEy#v|*4{7fJ zomtZ@_;;*M(&?~c+qP}nwr$&XI=1a}Y}>ZgaVF{azV~~-x%WTwpPBWnI!{&YI=gn^ z*>zUd`R#zd0B|n>!3wkEK!fVKE!}t3iO2K(=u z4a%8p>TLcJ^(aZvO0`kk_g@>SRZSTM#Ea7JEF9bQ2J_~sD{m_T8JlKhqRT~_ ztSIJLu1HmpfqJD)VbhEnB(Z2s=#Ix4foXBf{xO0i+COzf=v8j$Y6Q2u2-2E~yd0gi zHhpRjisG`!)y7J-4~o8`F)ORvklQ76$j^@_iA140S1ihwC!I+f-`g(8$WA~z=pWEC zqC z7waz=5J+1KRz%Vn58}IrBvwi3>lbbh;$WHar3=)jv8cDe)G9HuTRf>r8hW)e zcx*6uV+W>b&O$RYu2UHHVbIox@v{yyGy4~tn~1eAivh+e%l?M$hsDZjiWdu6KsIgH z(8TQFOUG^qXFLoJb$}TH=o70=mC0q<-4rv5+J3h+HhJ;+{(J%~K0Ud2Q0Ra$Ug@ih`UVkkjaS})qO2o~KcwRGUuLN$!% z%(57WAp{w69#tI(!PC=E4&LDBga~`@r-dKw!LQGIOXj9TVaBTpACx%^}T`#l}!ux z9cjwohD+s(jq`u?<$pZQA7@TY&-AyC{dAU}bsv6JgpZF`$Id_>`;VKF#n$+{&8LU@ zcVGAE@9qA-Jou+mcKGnEG}u&PCi-?CF8kB%edzlP@A9`N{AXO4zx*ekj=he#mC;{^ ziQRvkBLBGK(?9>a6@NT9m7IgF{hvcf-qyk3FIAtz_)DlPC&9zROU7esqGL|MYh|u4 zA^+h|KRiFbft{YMiM73zEhNo<1f&tL{D?tgV)1aO!+35U7frgeEn@Y(<-`@DoFqxPkKdt;GLF_{d1-MI4nQUvd<4AU9zUMPf{YTrsE$-h>4WB3SUn}zOQ~uWyNa|R8oOA#E3YqH| zeQbe`ss6l?_v0Y}QjLOK{aI#gdZrJ7gpTu{667CC{@C~t&B%Zj`$O~RPXEWQ{pT~x z-zWZG4=Dc;4(VgkscER0KSuh$iHDTY2H`F*(7>gs;B@4%!3MFGA;~I6gpZHGiyez5 zjQh=}Dpe3q2f`N(qI3jYMh3fSGyIvB-v}5K-GtQ_Vg$uO{os)w1H-b#(Erm-kHk6R2<>?`7;53`b-$W>EC;%dG1lJM~23TV38 z_LM4{8RK9YfH!}DHr^WIj40+k0;^+FNVXRu1D*EkjvKm4F!em*KwJ~@ zZ`a2u=D%OxWzTGHlrq_z`+ct}c*N18(@N*rujuu#u9IraX+X?5C+Zl;R zFz7xO7H%5cw@S^KeF>o}EUPPw{7!NU;;YQB8)$!eU+;A;pK5lV4wNCdsZy=mqwuyz zts-TWZYpnsUo)YT5mm5T(7+*Oy>?){s65=KHt`&i$(K!+%G0P-^CtmWaS`C+&cVvW z1ORQXKAfeZX<*Ofk&yZ8q^n}8-%v!rXNIr=d(19Cm)HEWUF~Y@!$rIIIoq4NL!VYA zk1P%c8R?h8h!kcZb=%$=ID^uh-V*cr3bxmx$)gN#Jru13po*+1vU!87p&{bDs{pJK zHoteFclCA4>dHPB->Q@$t{GRt%$)!ulknQKZxSMUL;Ggw7thTTj-@!x6GDZNQEw0V zDwXTPiQ@;BsPe>>fdj)rg^IpVc(4LpY$WE*DcHz2DNKGNGIhvJB+_OfJ){|Mb-=fK zwl4@hyA#x*3}ivphxi$VAipmq&_o!5Jh$R6h?CYN3pkvP8zZxcMcb>Z^EeaB!Eq%0O3qzDTjPy`ch z0~}51q@OaZVL2GxoL|Z@PoZm<2mfMdY!T5~KmvDViLeNCM{ z?@jnN?C?8kVUd`ViT~`NXXJ5ao|9l%A*@+GDS?J(7EjRTbEj9 zUZd})uJV`q1)x^8HzX{i`hMTisad*<^2nl#V6n%3uy7N*MPTgk>sr-1J=oVWMekoa z;a%RrJ!Jhz#?&964fAd9+miNRdfW50^5V)&QXwzy5ZhZUnhhua&(5YCe3-WgnXt3v4S}-XB z5yClHBe_+0 zxfgdRc@-(bIQxM^j+V&+VZF_&d&bo}j1lg#U z6~Z00>wt1GP|ip}FRcDlAZgcq$pt~7AQgn7R`s3&3`auzEOr^o&>(0NcS(C^7ok8> z|H;aK1^LV(=AxtQbrFLJHiycd@CWcYwl$a!ThTTQ zpwqV|zb*`U8!#EWj~uBbAPR&wzITi?&G#i5ZM{h!OS7lGi(AywaW z2)beXJ-{b$jb|6pf<1zx4HZNyjHgCtPbW`j*h^#XO#XiW?MFZjizstAPyQ^^pIHjZ<8Trgs7@g-6vvwMvbO8s@M42oxoW`emnYn2 z#EU1Z))ZJ|{2O}03DA%$M`hHj&O5lcwKH}VotN3BPFvVM)>n2E6pW_YI<2r%w#kcf zQ~05-v0t7IN;bePKzlw6`9y%FKr?`0fVDstkAqU6l+fr~Yxp+H!yj*z)@=sJ(S*L} zZ+5%if@qjSsv}DSg7~Cv!bxh;MlwN5QgU>YaFf!OCwX`DJsNZTNLE^tvJkD_uQP1j z|2~F41}vc*SNbD=Xo|Vsv0TAy9<|=JT#?L7fMVu*c`X-59)EMjX1szO50VS7{ElM( zj`OAn${a0i1U@=1omnPb2qO__QuKb`uig}vEzgpydTg8kqACCO6#9vbcobxd^MyPk zqLSP(2#FDb@@JBEy2w@Fm1(J=)p^gQbF<8u)WtY>DfvrbR-*OvCKJia>3IM{or3;A0K5OaUldb8O4nEOFa1`y7Ald?sFclbAkcrx?Fi($L^axKW*z69eawu0f7iu` z%c-*(U52Kjcl1YF>50GqKMS!qNpyo>3-kN+iZ*}ktIZo+N2OVl-Xnk!Qoj`$*c)ig zXZ?t?qmBAp&x>7Q5niq+V@w{Sn%8S zJKyGCS~r&K&6FyC=~>t_;EaWAvy6pQ*G|GmfJ)Re^~Nwgsb^vrxjZ|x^uOI=L*^a= zYxJb;R1-(|`i5o>^7pvzX+rNP_NH=rN%jrrPNFg5cA*=d#90$u=G=KSKUO75=a-QJ z=~P_XPh*vELwU?`?@@CBA*zw!uG};xSyrBpT~M5rC(5{56VU>(Ju0S>uaHDDOwAnx z`y8e+2S-?5-D8Rw9uz_Uz80oOjjAXhZ6BX|$1Hgi_LNc%mw7E$)S5Udmqn4n1etOn z*~goCQqA1%6zA^)$xy)G%~2%GH@q77&6T%F%F16eR~4oo2Dhk;@3E~eTrQloX@Fic zfjzXvv#qn6gfA7#HOY&L?{TZPjk6(*g~37lCvfCY_UCe8=r?^`t<2ez_{%2DWj$$dUBu=r=p|fqrqo(sO&1vWb zwyq+sAoO|a(>*yyPBU2DVMs)s*it!CGOWasI5@Th%?a$>9^GQWYhs=vva^HB{zKEX z#wMgGQWZESBCtz*nz@e4xEM*2g;v5@z{sq^I8SxH?xLlK_V@nA;!@(BQj|DAyNKaQ z@6e%1!L4~>vJOW=GZQ^eo`J_la8K#-IBP8Ka!=K_a+gYigDBGapvx-amN*kJN<$k% zT#Nm;g0umnJR?-o=%{&c(k~kOdT5KFTNbpaxfXm@3$YmZJh8jqSi~cJ8NKlNcJYq$ zRP0eT#4ifowFMjE+i}>**(qK$^R_FwFQ|vWBIcus26?Wrb{(!k6E5Fumw79Hk{!L? z%CPo+KefBBFG93}>x2)=7d9on({L4hB3oSbw1sQVGzYfu;&~dJ+2tByyA*w6V&N;d zN7s4aFP*?EOywpNTz>q3-@HX2%Ses#e6b*!u5#r z43y#B>C&Q1>q4D87HxpEZ%KI#U-O&a*vy1sCgIff($j*7jV236Z1ErP_n)Lfhv!5p z*X2j2h=el=h3cg@EZ}XCPQ^P*yceAiE8J6cDPAS<%4t@q6?w+$>Fe>5jG4Wb$DIRP zpYx5Y03+~}+yn-ufQeh+o_gnx3K~pG2H}F90=#VvWSlZ&&CnF5%E!1hY)N^G=j6sJ zh?*&+1`PKxnfy&$YGk*FJO7KZdh8VDfi}}HXtDHEgIQiO`v4P%oIil3TVBVZ{f zzY4UXP2%V2S~unv^p?d|-erh2WbHnjP>5OINgr6B#`es1+O)v*+=H9Ct0HRrdi=Pk zkpbcJo_Vu)2k$z?y8xb9zo{y{8bjy8OJhTv;f(GrJNP=+yB=rRFBx-KyHKqfr{HYjL@|Xb6loKfaNw`tt=mGIzs-g?Zbe&CPxA{8 zon7(D3($rxQq+?9m|~W1cf|8pSrak|4*{A*)I}-Txct4)vKcPNy;7f=jlX*VKF&&= z_k?qbaOQR5Zpf0nvgD$jhjxOD08k~_2gl$*NB-WIY zjPr_>%IDiG5{WJ#k|XQQ3iFasDio{kt{NV+ENk7{LL(|*)JBWp1zAFu;z?K zs`)Zri-vP|E=e>Um1iZQm82=+3ASow0`Z!7uPbm1l#Aq9sZ=Gpp1V>7L-o?w^XxSy zPC?+eOLv_ASO<8r6<;U0OnDZQndphvP8kJI&lD5%Ysw3N>4e6YU{~V$$78A~4HKs< zukPUm^KE;Adf#@p3~kDj2+_Pb&hA5AOiWq7nkDER<}X*y(0UtG+ilrvw1)|lJ8gck z$qu9o6VMFg*g1V7!%L*)p!EFc<-T1jl*W`uKewO$#LhDw(W-ujGg*TJKOI%ilpuC_ zfij|;JR~Ry#iqKIr+I(tfx^V13eSUXadBU;n-atsQ@#>hE?4u8S$i%Bd*z46=NaY= zR3moFoYI)={?`3HjEg);dE4!4^A#RBL!?Bub}Fc`7@P1=&6EmLALD4O`)O8T*J)QN z8D2oW&;*;mIIDD4qV1<+_d}}9oI>?*D9xThu9#R(pFjXe%uAcKB{2$0LR`k)Zx;^B zq#2z?6$-<+sh|*&tRdI~ zYW_J`bMn%5OYcR+`lh4@X0m2giL;4`z-T?cdQYIYw7E2>q2~FwBLl73lbQ4T3rnxg zOjrG#iGlsKbDdoHsCicWB0>rrM%++W&_u-!J^egwoo$0U>ika^(7rKXCtmuq{g#{H zFA+>Gw0ZFqtRwtNvjxjUPw1}mbDM$Jb0;T1BvGY20$L?ox~&eMhlmP-O7dI9tKb}| ze$BEtZ)W;r(HO82cdJCS#jjTaKaR%VYD3%iMK&hRM>%3@@ZGp=ximUqIctIb2T$

    m&@P1o8HH%6!&1@FxATgDUhS4U_q{sY9zAv^>$>A zhul-XVyZnt7Vq2l*x!`eL+Uo)eOu_=qb!aHvf_YahL5tmj~@N$mc1@jPW~P|v?mJB}abG<1|((1zl zQE8SHQWOJ^2?7}+F*KwqA#Us14*$XvJ(VgzFV~&}+sQy+vHcWwBD)L*Zf^-~%=tPy&C=4&<7a@z!vFi60 z^0hnGh0-kvMyjoX0y!V{QuMhN!`NW@MupR}q`L%643JhVQA04+0x*clxU;~uIW@>e z3`AQ5Ag<2^<)*PV>#B-3v_VJ$9Tf~MyXnsF+xULE_|*2FzE}g4`mTYY(*-cXQoO%m zh@NF?S0K*{Ef1dUiu!ENv zWMNTTvNI5JWRj>(C%o50Xc3|*o2LTNnWDLmcUIj%j?uZJ6T}=wlQKJ=BVm*E`ScCQ zwg#ya;cz@8@U3WN4Z1N}A7uX;vO&+LDHFfo&!fQifl>veg-UykAmO|s*q&~vI8q<4 zs8T3`qT_r|#8(0v5CISdCT+wl-W@Je0TYV^qRE-=zyuG(c|b7ucE%y95|LS!#)B@Z z$cqnoQ}VF^a#7aXT<_t`@6um$gISmR;Eo& zIe|>E$?Ecgw11LftPgayvBvRE%YoXRSf;f)v@s%>GZmupqjsQ#h5>CSkKV>fh|otx#9~8fn%)eaT!+m< z9UMeMlW+pStlRIoLJ`8W0kbQ!^B>0QR^45e4UdzWA3N}pW;DfxR` zPZRV9>cS|UOmCi?gWBiD{fUnb+h9O*Or#w0L0v$dI@nij--AMdeLL%=+cOLwk%YMs z8NjGGI0QW%f@Brx8Sg=La@5`{Wo;5{yQ17o-|UPp2{J!|7M((6!6ylS&DOxh{w`4x z@_m}uy)^F%_M?7bK_=<$#P|4qI1(ivCi zAtOMTQpB@n?3pp0eLp%MB<d#s#|kbiW9UqJvC$GT7E;h@G{?ou*U3E(rS(G#$FhVoUr5uQGXPTY5L0@>)`34i7NX@D*gVJhOd8vi@NY{L0bm>mVj zasOa}YuSlHr~!8JL!?5-KheK?_t;W=Y{>9CG>8;eg`-XZ&RZLw!VjQim8FOU^k6k3 zBLbEnC1dlU6w3l@^SBAL03<#Y{{vJwWwL@c1I z>KS3jjL{JX0D6KgHFfLpV@H5uK6U1V5Gth3RjjL}}bSscbn7V&@`W`7^^KxJ^&Sq)D(0KpIQ7@##DvjUv$p+E6F zx(@c6E^LFz+g<=`E}>SN;6XY?=uvWdnQtN$LM3J)ct4exV+TdbRshwX)4i`%n^wJm zey-~y{7Tb#j9*cOFWpd6d^f)6^5DEmhyJx|0R(lW3wVGn1l(7bO~kc4X)>;nWu*&v z?xuSLz4Zi+FnZZKeI>KS%>~o7vcikmclt!`Nw34QozMml=Q2pQ4_wQ!8PWlitn#6y z?%_5W=s*r0^X8xKKAe_#Du3hQpi=7ZHz3OlnI_Y`yMXiZnq9RD!Q>eN%Fmd4iGK00 z;DoX2l(dzVn-Q7(?M5|Eyug?VqGdsML9U*I*5u;B{t`;w^xbAz#qm`1Gy8nkqgY_F zWjO`k42+dQTH~4??y?8iHvlK?xw`2AZ#_Ex(tbc|b2Y3h_~kQ>G~Hbt-XmzH{t~72 zu(E;P2XJk>f^&Zy>}C$QBfRoBHxH?>Rsg#fk-%gp&vcqG^1oQD;bez%IdIx^az|3% zzUgRTx~H}JXSLKKk2{1Xf#609)gPXfG>aXXGlMWTCwPo;4x(d`eLYJ^$#pu~B0N9> zLp*@Uwb4{jip3do-HXM8+!oC;>SgzLno|E_+O8)^5j?a4q>G<`-xAS6QOBd6tlGYT z@Y)0lBm}*;^z2y?UUG{#&HS7Uvvwj9Sm#_1vcp+DArKYA&b7`OG7@Vq_yy8h)Y3n) zea>l;odGx73eqcbn6*+h+w*hu<4^7gM<%60JpkZX$$^oyDhcZnc`$C)A)OGCBj8_U z8i>OOOd;(V`cTX96-Zih5KFLJU|$(2g~36lsI&Vc;&%n{l0FGsppysU!fCUZuAh7H z&j&36byakpP9&1RSFh}L%=4+z+4EXRaBZh%cZ)ey*ILK^rH+N}zbw&bPxyCm8}&e{ zm{yHTR_62H|Ai=z`ZY{CEiLj`CFD!n3Wveyg@hnm)98XvzS+6!~gK_rMxJB&7HdGmDMj7 zeBq8gv|Kj+%Io{<;jpyZfts$f^~_i&TszqC4B#{{(f$b z0~dr!8{d9@s4iYCKw>I@kkr0H2H+T44zO%?@D6ubYQ?mE$fu=|aAs;?7&u7JA#ldQEAS^jUc$@?P zoq*f&{LPNl0@tNcMB@g+%9gbZ*CjiyOHp^wFvNEaffz-B+_61}{=n&V*m>xc^73U% z`*YbJu#=PEL~(4o@*WF;+Y`cmAJwxolZuh$Xt zk7Pa0Yb$eOFx+LLsx#YKAH;ov)?D*64`zu&T9444rsiZ*FH@oSdblt5GTTA?4%DZy zM38ZwRNFQMOrAZ^Oi)VmIR4LF`$c>bsV4 zx{*K<{r1UQu4~CZsH_W-h!RZFTSbrAYbGpuu96(nAcBIh9F~_Kz5gQrwq3BZ9vmV; zI&8rc3K|GQj1dG#Ky|zktqn_;9EeSh!ql$R{))A^T=6byUYa`z*H@+2KygNIu~X62 z6%u(UfEH$J_JUARCY0e@XH?`tqrnMO6d}Tpc>88ZdVrQkz1eAc@CxLHh4H9^z{h!X zI?UqZAy2=*4vJJF$)a!VvH^5j&uI~^K6`#yFtSkvw%BuU|Xy{D_@|UVzr3_l> zfo3@zF{*UQUZ)ka&adZ2(|gy0Y_>7ThNMF_7Qp$?v^k}?<$x`q_g7*$&c~l~#OKcj zAd?d9AlX`UZ!FnZ2Wq8`oYbM6dmMAF@<4F-_tF0Grw7R-pcGAxa;4+A^imVV9Ku-6 z0S0CQ>L-Xwh4O(4=@Tq9B%s2QifB|ItznvTQ??KF4NZhY9T}Lm%;3 z6(mRjRh|mkWt8b{Dn={Zqx($aL>SD*h{U}&ZXIM1fN}TE0B!_#y(eQ(r?v?agm*p% zkl*Sfb((+L@xML5SD&y!6rX5M>~=%7rSf8vFT*7AYZ@IPiPr;I1qQ*rCn~U$OwtYl zppHNi6z5z4^@MR4#;a|lg^-x`kiN@1u7&i=LWoL??{NfivTP``B?G|O0>eQ@l;&zL zS21WhgpXL+j}i5NVD=o&Pjh6@bOE+G4HuogMnxqx>_O6;%{= z*;H0T^#Tu&d>Hb9w@|TS5;%^;<)MkMNBLEffTqugMZ5h}>LP2*> zBPV@ixn+wRA{1X~=M9Fylw7M38DJD?F7H8bYTQLPhk!EC$axlkZ zr_mhSkwnl+5rDc2Fr-$ZRDxjfCWZg)p1yL}XPnl15@=UZrY&3E-3+O6CVeCwrd{0J zyBqX6fKHjy0xXa2oN3Tx5yl*Q#WvlSdmX1G4&z1&GOu(ZVwIqHX`pydJhuJT*ud+Cjrt2|o!Lp%QM2qo2iwz*COdA0%i|2=w zY{bH63E*V&*dQyfkp)B)4oMvdZYxerz45i6S!hoLJmivIcH;K+oNkjlf928Lurl8C z``1`i_mT+H-r=908NnA4K@(dXkEqEhI&jb=AtW4~m*i78j|>oCykji;GN4Cz0FWSk zq&O-TdzFWD8;?{e{^oY;&ztc-z8TwwGHE4nXDV7qkeubBHl7#(h@XJ?-zf=%w*$8` zBNo!S0i+%Cf*t#xh1A`HEDDMoo2q)>ICTLKlnG$Zfsv0Y3?v~CcZwMb{a5Jomwf~W z)S79o@FY5ginNEP3oXMnaUA7>$dzL?r15m~IUo{oV{zLgqP7!K#{}Mq2`1gaH#%s8 zUH-&W_|TsF*wQhP0(%F(mGz^=FAyGCc9POohV8Y8LcQF!yi3?B$}r(Hz7aAHF0F#R zrtYj6doXvPw>Tu+2^3R3F6HEDv5@ndfb_|LkX8{2(z7R}YSedB!z|vh?Y#4I!+%{$ zf_${I5U6TnnK!i-fK&7wa5u13BiG~tj#1=vKw@PIV=<9(A|~zHeWWB_DY0Y%R0_-L ztTX26!ENA_Odv?B^w%5*4M~a-C5VO)F&SW6B?nuTbI{9DAFRzd?rYc%B7bQ>>-J>& zSg0Il0B{|$6+e;TAcbrM$rs=bJa9js$g3oN_DTSF5LFO)VMKs;46r(Nf>|-Ww43XR zAl+oJiE58UqgJxI@IVeRgs&q6>)i@yu3V@@yJag(hDd9Okls|{~#XZfW19- z8k7vSi1s%g2Aiy(*P03<7_}6x90zyA!;qNz46lIW_fShU)UVAUg<4o4&64lh3;;DRj9dn-sG)(a2p5`8FpCYgE3Ka{MK$Wi!HMUN39`R zMhb}^l-525_bwH{ES>J(4_X3yFFw%Vff&|O(qmX2iXoby><+VlAw4BI zC2WeLjjnnL#VhsLgX&op7p{MRXe9++Nu>m^N$z0ybL3~02jFKrrVpJcW3sKkcp1{U z>JK;bCA)8KXRQ>6R*Zq88tDcX^@H3_floBia+&m0?5iBPYMLL%7XkA!q2VAVR3H8B ztsI$DlJxpI;CMN3zv#rz405H*P~P+O84xGAyY02(F`sm>p=%YXwpaPuz`-^cq6b6|fk0Lf{b(8BgYiIaA|(J{%Cjn0l@vuixKF<(hD zlwG_#Bz2XI4~aS#!*SI}jG!o!cIFCaaAfsULgNVNheLAKkeoBj$zI=wUN4JfxGxNV zAM33GlBP)GI8+O;IJP&B-Fydhifgdvtm8VlJeu*C2pS>h*BSSF~n=FKZNF@+~R6G+FX-P7ugs)5Iqr5VhV`fM}^oq z)XD4&1G+-cQ4zV#sVEc3HXYQK=S#nQiBC3EODlJwKQOqf6#%eN&>x<*)gQ^_Y&682 zTFDz6NPr{JBGM_SB3;!+TIMn}!3d2j00(SV!1DhrrI#wFI4Bjta__ig4Ng9~t)j2j zBO^GN(~!(9Ugxp$WB0D+>L%Rr=ooEzsQmz6km)Eo&Z`lL)AgOpsyS8720SmXT^x*s zBNBs>!J0z(QXYi(mr*7-vnZ4n?j#*CU85af<2}SNcRaOUiB*myI-Ll7(zU0plxW#Y zQs=_cs{0cvX^G79nwX1=gr0fT&W#}mVbftA8fnM}ckUYi7ZM?z8yWZR^CZ~hy?-R@!6`GOI-C|!?H_{0 zWyK?f(s-VjF^W*PMMFiplr!9F23(iW0u{Tt@6Zhqg@qC7Cl|Czyi}9~5vG)0;*%Nd zCZ-f9n{bS(*ojQ1C3350%;?$$N*pB)U+g~Y+HO-P7os>g_t0FuYYsvU$B-8g{$B#O zplM{y{j*Ijqyqw(4p62X1^%NQrzpqkY6#WY$@?i^?KvzMcv~=H-91iSPd7*Iy*BED z&Yg~^_Xb>IXlJX|QH0a$K}d0G17K+7!x9WG#kQOyR%kBPk+$TbAD?Mo9H%x> zN1=5RX+=Sxm}*(!aa(S(=JdYa6I;dKGe>%179Hn-T^?*orJSVJXR@-xQ1rB?dHTwg zLvrf{Jqt)S2ofbO(xoe{Ka>(*-YUbOaTOLk9-*6KZ!hENSaZ8PC|NJNOl_@n+ACU- z4HaYe%o24J6OyfUGAtes%>YVeUsk!Fd4WN9?Jj{o&|Uaqsw9Rz%~JtsJH ztXjWcgzsEzV>N7zgOMd${ST?uQeZj7V(@V6C0wet#6|jdGt6tCI}OP9-GH|Js}88d z^*;+KFUc1v7oSE4D|H(}ja|T?nuVR*4iphZ=uF8y_E+hmJq6HCwbr%vWPW)>Knq4p z$YQDeICbNRwNR574YIDJ5S0nN0X5QBo%n1?sBI&}$r_x9VIt>6PXSLiCCArE9AVLX zk9>GlpTAVPf`gRO>_l(@sDcZ3(%q>gI0DDe%EP;0SPsWz2bFhG%tg)}{f)GncZ)fs zSf7y=B`Z=gl%>n_0k4WgMDeVDc$gtP_OztPRx7#p55}k30F07~28w2}SI${T=08W-8@U2W=DtIndezkyp**I$1@07^&%vhIra4SAAYE@ zPab!UVhO@UBQc@ivC&+Dw+jp=eX$6xW$fl!3DwC#17JoE)SOu#sS@IvPW@!S)7p}S z$j?SrXl2-;xMTgWXO(1)jw~a+IO7g7)WVg#zZGyZWk{b45$fEo_L!nqnkcutKJZo7r?2%K;W3! z)jOg*!-w}eM|_nEh1r7ei-pc)W3+j-{>qAHfDErEecO3vm~L8v7znvSATH05A8j>d zq#&_ywRtc4MlSG~OBN$-2eTa`^&3 z_eT~5z2iy1Dnuffc?Cb~ll~YrgEZg`PZy;JH=Oej$NruAffA-^r>PH3DpYb^wFT-Z zWB{dB>FdOEfd(Tq+6JIxd%DKe^q30|F>mE(_Ti-hTk~obKk;SuwrqKM_1d+Z%E-$0 zTzh9G7{`@#y%v&?X=&T|y zeX{|7F6GK3(QwyITba%eF2CV(w38folX9)`fhLJ(-H2T_=4TE|iY1$jmXvbyjr)6q zYg?Y+0Rcw(92NVb0FqJ#vfJaOQjizv zGEO{}d7BmYKG21%KscuN@AEyB^$y`zRmM-EbCdID z)dskpSkqn$kZ{dGvK(k>9B?|9?xm2-UK)Osjg5^e?P(f1yhLkJ?6yFr#QkSbXf~eU zymW`l=7UNn*SZ~Qeh5NsDK1VUY5b7n6vRwc8mG1O)2T0aH9O?{&nl5 zvlk(zE;ZG_&G$9Vj(3hXnjXFO&SDG?Sh`uOqD@=$`f?Q^l~KGz4Uh7sII2UVA1Vn+nm6i;?^$zBqCqwEw$8m#%G>#2e(G{hkNd$z0HwvPStjwO#EG8 z+)NZJE=}#}@erL5)<}VfyZi6<8a`Ilvr;==QdpI_Hty`UwR367d3DTw%&C1qXsM%V zC4YP=M>BLh$bGHDm4~DhMeebsvbGRtuo_1Zp>R;Dh~;S;NO* z)|Jisho>9y_zznXj?U9*WD=Qu0YzU5cN0cNUH4f>o>0+Z4kjxkv{}7X%Ss#0zkl2c z-8tqx*{t?FO^w`b#xq@?+JJ{;zM-uQO+rde%_4Pu-TH4oNTre>ecrBP&@8C9OT@-t zrEL=l=_R8T`>TA;$0$AILd1mS044zt#g&hD?^3pmJ|5g^3}j`o6>3yMUDrYXHZi^7 zGA3iE{YObGM5K0MVButLr>^cWnEvo&?qqDj7J=rlJ{zf3poNOpfy}=+h;*+tI&%Yj@>9!7Fldx1__->D1re@t0?i>O_e_usXBpl>XLD z>q(4nNkO>rHVaxE1T<`FWQL$?ieY&;w)WKNDB$5mLz7Xu^+McD)ApB@Iqaj1pzDVUu%CFYnMWCeM^f z=}V`C`J8dleCIjFlNI8 z64WdYYGIy_;>`kKBx(gFdw>Z-M>DAlr9$1?naQco3{AY)ssPw=M_3f~v|7I2T`H~A`?^cjwLYRBo&vNI%3A$?P+c2@ zM>%q0G9)*$&Nn1lH$s-!=5{V$V*H$bJh@2-s9E}r=kx~{Z#*<_3)RERm25nT6hOGH zkK*v~Cfx|jYrO73zQ>m>@WT%)94vzkp*ii&b|%p~+vAA03s_(7n{E()%V%t(Zdpn< zlwKz<3ytB1HrWcV1llZKln=B44(-?E%%LPDpAMEVZC0OS@zBJ(%_P)8yJ~H2 z$4s&fR3&4sxP?~&Y6nA*3Yt13vER@F^=w6xVn>LEo6LQaE++U;^5*d&^l-HQlBo-H1ZT)w zp?Mvk#j*}$0}^=VS{%}nbtfNfmlq1xI^pO_cp%SI@5iUf?rZT(s*n=whiEFpk8Q^1 zRS&Z#@zBhl+8vi0Nm;9^AKWlu3xT|`kXedam}*npxXXZOgP>jSIUD?9+kk|>&PWL` zYMRE|uH0rE4sCT;$+ptVft--Ib#6E>VQ=Ji1+l~YOEBZh+L_s+x>-u8+>V=u}|GG^--Q@IfspR$9S} z%{sCrasn+;FS4-xB!I}u_Aw-9_XpTOd0Sa?yxbEUPc-@a6`1dM7UDm-+l+Q9D}=$P zP+uEqsA_c=f)#DuI`ip<2N!Ltr8l7qxNnS5%Nw5Su*NryJp{w!D-e zczVh7QlNN3f>}k#McXl$brRQhIc=D!mvo~V?B=l2eBaN@`2*_=zZxSY%_m~7Iyp6I z*z*TDlAckse{3`#y~aE$KN#I&y*Nx99xX_R6W>HQl%)0+$PCC7Bpi<*qi-deW*RAP z8+D2TH@TJcNzeHE){a?1xjxeH>bfh%YeH4ocaRf?EIqxY<=fSLTXMPk*7}#X1Z{LD zpn27Gv0S;}l4Dti^LQ|VBbSdP@or`mNuMzcth!G)XFBD%UgU1)s-l88zm)mZE)wzW z)XT%q0(1Yx)%^9G)w=7Y@gHiCt?4It^16P?9)N!h`jn6zUT&Pks}3$9Nns>(ZDriO zNpkD^+nk+P)J^_Yfr)YVHD{t}W_vAk%6D=D6DDM=qt4wC=9PC>9volk6lW9zqdRBj@H^TI4pS}qshTRh=QX8iokv-_UVwkPcJ ztYB52>Em@5mU$g-^tSM+@yHl!WGg7FPwgtes}7`oFx$TXKAzv@^hoxx<>R@<WvW8s8owZi-R&F1y6k_9VeKG;PwP#c1uIh&q$nAhrkhIb}GC*?@!EQ$eG!`bH ztRqlVe0Zz- z{0Rl7X9whinx_lMBTh~X=60@_aUZe56#}hM@Zk9SlcF7yKJq8@%$@22YoQVavOz=#(mEYC z$)%Pmk(-sQujeYv-Hzr@-ZwvAL14N^rCf8xBq51#&K$g_@m@kQDYbq@fM1XO%ya+z z#20(mQl=mJy6j`Ld`U9|1+PJi{4^{%*Q;>^Sv8$+XilC~E?h)IAKaxEBf(oh;CbjT_c{PPFujn?LFdfi@&g|w^e2t^{r(4GIU+lVDct|0%L%)?++f!(A&ot|t zu-e+%jh@1;P`)e2Ib<{CNi??IS^KyKK;>C;$F~@xZV&P^Cm)2@Jh9Yp3ghLcy(51S z?>c6zh#rV1&x2{?hw?xA;Y}Re8(`-4Y(@+=gq(uWuK5Z&Q*e*(g)_?=13ZIvbUJcvt66nAq zfQ{3TlUX_*%eB6GzP)U`ux7GfuuvG8?{uH1;Z=|QHpcP@Ym97D0lA+B#KC^yspYq` zrNXw7*(?vAIPc5)qg3m&KM31{1(%sYe<}ya=f;?M@Mw0&wOrL#2Zy(}`{IskP3DmI zjRLAO6kwb@l)eFdQzc?|qdshPP<&?R4<0L%m`$baPJxzzP`SdUMIDo!O&=x0%)~qV zs#3YNZrbtbCHJUp6#hkxJn;rb$L$Dg6f4mkuNvM)wo0BRRCj6(xDt1Zj}_4{JH#b z)7b`rrU;Bm-V}@*u@9Vl^0=953OZI2$@a0mb_1ZOfl#`6X^==a<71(@y!y(QS&NcI z0OjhbY9mDH+i|l%N3+I{yQAeX8_C^Ny@3SH8JxWN);e;_S5N%VWxy9qfVb1zxq+s~ zn8MYw4p1iu{FN$7vDDR*#w>s2-}v+n68DlMtucg%xFzkC$=Li&1R18dp0RMXX}x9{ zUf!LvK z07=LJtxQ`4at`Cd8_gmF!P7R$h)_`-WUS4BW$D?1BwB~pK;upTs++iqjEpNd-B;CW3Dp zp!1?jxDnDt4XHA`8~ZHDH?Qd1KzR^XwBKL-kr_B7v)ctd3#r^!Nd8cQAlUm3%gOYPUS5cD6s#NvI87TOOEEzUh3kFlYOsSD@~enw2=)Fpgnr z42K;*eB)hhbQaKTGdol{USXJNj(Cfle85RqH&#yLle(n`nwE_;YMr(%dd;1zKA59X zO8=CG(};ozU2!GYwlUsz+-r_NwfEH=+nsdi(TZkX89Z$W5mAQPD9oje&kV;q*pUWD z=&G26!ukq8HFC#?SsJs+MBunJtWuraf#*G;bvWGO4mUSj6g{>O$5z15{tg13WCT_c znB@*nMj!)v9cXV6HQrnG)cj_)TC%dZ=qugU`gu{N@MIiYj_$nk*wE^~S6pSuwED^1#NQ~VZBCqvih=G-q0hY+OqO*vG$)SF4?j`V0|B-?e<701sXbqh3i9l_K=BTNgg8QR(>8AG$< zUYNR#m-m>sE?3k1(h49nDFYnY}Y0lf@MxY&Y6G4W!2=LeV`_ z{Uz3?O|1*rp;E@!j+sp+EBivf@zCFgyx1Hmn_XVqti7QjduU3YiP#z`m~r=q44$D| zOY~tQNQw=H-N>04-g)$z&B&7LOdm8Ki} z`AL-(JV@eMJoD|*_~spbi3D#bK=L`!@bcb&=W1WvShW(sLL9!{U;e;&p`Q}MU3pZ-Xy}R={B>2fH$&ry327Ju= z#kY$sW@nk_pEuGu_1`b)%d;79PCSZH*7%RbkE1-Kp2Y`!d2TaP{3|cOelnvSyy2^>hDk)+8aQ0O zJmhyDY-m-ClQL@c2bRUeXMEY~ym|AgCn;CNK0d~~?_KF1_BJ+G1?Ce`$D4a`;l3#| z^9ZxB)zwyM{V&f%N}gy3FjRvk$-h1}sTH-#T;B-(iDALC-izUJ4PepNLBqx;;P=ZO zzmR-AiRo=pzTdz9ov+X717y3!cpf$V>T$pR{g=P{=ZA9G{G6Gym*s!5%l>>WDdZ?V zqpwW=wat7`84N=k5hMKVi~8}GJwuVZ>8T0T9r)%Re|-C4>ae_4#^!xrE%|?(#H*Y@ zfimnqANWhh3Tp*>w*2>^fBWKoFZz#<)$g7D<74&Py!_CX{WdSZZTfFV`d!oo>;_pc2cO>&WQTl-q{+*qEu@PT?_zemC z7=QR3$$X0){OQ4eM>4-7ng8dJ%ol_7J9_yYz5I?|en&6A3mV@5Y`+o5Zx-aQ=;VJc zXiPjhKVVAyGv+HYqJKKq*IPGXdpfaS)j|B*h)27ELB+1K-FTHX>A~N28EXb?SKGjM zTR#1fFm)`5@H8^GkB^(hyU$|({&#=m^2-+>#ZXDc&8xef?fvw# z9mhzZJJB5!YMaBJ`QH7m4t8!^Gmy}c)`D|t&oj1t@s}*sC%e|x>BKW|SKm?ixDNhz NR!070@^NjC{{twIl1Bgl diff --git a/Svc/Framer/docs/sdd.md b/Svc/Framer/docs/sdd.md index 88efb84332..229c601e7e 100644 --- a/Svc/Framer/docs/sdd.md +++ b/Svc/Framer/docs/sdd.md @@ -20,6 +20,11 @@ in each frame; typically it is a frame header, a data packet, and a hash value. You can use the standard F Prime downlink protocol implementation. This implementation works with the F Prime ground data system (GDS). +`Svc::Framer` is designed to act alongside instances of the +[communication adapter interface](https://nasa.github.io/fprime/Design/communication-adapter-interface.html). In order +to work well with communication adapters, `Svc::Framer` implements the framer status +[protocol](https://nasa.github.io/fprime/Design/communication-adapter-interface.html#framer-status-protocol). + ## 2. Assumptions 1. For any deployment _D_ that uses an instance _I_ of `Framer`, the @@ -28,11 +33,13 @@ This implementation works with the F Prime ground data system (GDS). ## 3. Requirements -Requirement | Description | Rationale | Verification Method ------------ | ----------- | ----------| ------------------- -SVC-FRAMER-001 | `Svc::Framer` shall accept data packets of any type stored in `Fw::Com` buffers. | `Svc::ActiveLogger` and `Svc::ChanTlm` emit packets as `Fw::Com` buffers.| Unit test -SVC-FRAMER-002 | `Svc::Framer` shall accept file packets stored in `Fw::Buffer` objects. | `Svc::FileDownlink` emits packets as `Fw::Buffer` objects. | Unit test -SVC-FRAMER-003 | `Svc::Framer` shall use an instance of `Svc::FramingProtocol`, supplied when the component is instantiated, to wrap packets in frames. | The purpose of `Svc::Framer` is to frame data packets. Using the `Svc::FramingProtocol` interface allows the same Framer component to operate with different protocols. | Unit test +| Requirement | Description | Rationale | Verification Method | +|------------------|----------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------| +| SVC-FRAMER-001 | `Svc::Framer` shall accept data packets of any type stored in `Fw::Com` buffers. | `Svc::ActiveLogger` and `Svc::ChanTlm` emit packets as `Fw::Com` buffers. | Unit test | +| SVC-FRAMER-002 | `Svc::Framer` shall accept file packets stored in `Fw::Buffer` objects. | `Svc::FileDownlink` emits packets as `Fw::Buffer` objects. | Unit test | +| SVC-FRAMER-003 | `Svc::Framer` shall use an instance of `Svc::FramingProtocol`, supplied when the component is instantiated, to wrap packets in frames. | The purpose of `Svc::Framer` is to frame data packets. Using the `Svc::FramingProtocol` interface allows the same Framer component to operate with different protocols. | Unit test | +| SVC-FRAMER-004 | `Svc::Framer` shall emit a status of `Fw::Success::SUCCESS` when no framed packets were sent in response to incoming buffer. | `Svc::Framer` implements the framer status protocol. | Unit Test | +| SVC-FRAMER-005 | `Svc::Framer` shall forward `Fw::Success` status messages received | `Svc::Framer` implements the framer status protocol. | Unit Test | ## 4. Design @@ -40,19 +47,19 @@ SVC-FRAMER-003 | `Svc::Framer` shall use an instance of `Svc::FramingProtocol`, The diagram below shows the `Framer` component. -

    +![Framer Component](./img/Framer.png) ### 4.2. Ports -| Kind | Name | Port Type | Usage | -|------|------|-----------|-------| -| `guarded input` | `comIn` | `Fw.Com` | Port for receiving data packets of any type stored in statically-sized Fw::Com buffers | -| `guarded input` | `bufferIn` | `Fw.BufferSend` | Port for receiving file packets stored in dynamically-sized Fw::Buffer objects | -| `output` | `bufferDeallocate` | `Fw.BufferSend` | Port for deallocating buffers received on bufferIn, after copying packet data to the frame buffer | -| `output` | `framedAllocate` | `Fw.BufferGet` | Port for allocating buffers to hold framed data | -| `output` | `framedOut` | `Drv.ByteStreamSend` | Port for sending buffers containing framed data. Ownership of the buffer passes to the receiver. | +| Kind | Name | Port Type | Usage | +|-----------------|--------------------|-----------------------|---------------------------------------------------------------------------------------------------| +| `guarded input` | `comIn` | `Fw.Com` | Port for receiving data packets of any type stored in statically-sized Fw::Com buffers | +| `guarded input` | `bufferIn` | `Fw.BufferSend` | Port for receiving file packets stored in dynamically-sized Fw::Buffer objects | +| `guarded input` | `comStatusIn` | `Fw.SuccessCondition` | Port for receiving status of last send for implementing communication adapter interface protocol | +| `output` | `bufferDeallocate` | `Fw.BufferSend` | Port for deallocating buffers received on bufferIn, after copying packet data to the frame buffer | +| `output` | `framedAllocate` | `Fw.BufferGet` | Port for allocating buffers to hold framed data | +| `output` | `framedOut` | `Drv.ByteStreamSend` | Port for sending buffers containing framed data. Ownership of the buffer passes to the receiver. | +| `output` | `comStatusOut` | `Fw.SuccessCondition` | Port for sending communication adapter interface protocol status messages | ### 4.3. Derived Classes @@ -126,6 +133,10 @@ It calls the `frame` method of `m_protocol`, passing in the data address and size of _B_ and the packet type `Fw::ComPacket::FW_PACKET_FILE`. +#### 4.7.2. comStatusIn + +The `comStatusIn` port handler receives com status messages and forwards them out `comStatusOut`. + ### 4.8. Implementation of Svc::FramingProtocolInterface @@ -309,9 +320,3 @@ sequenceDiagram deactivate fileDownlink ``` -## 7. Change Log - -| Date | Description | -|---|---| -| 2021-01-29 | Initial Draft | -| 2022-07-18 | Revised | diff --git a/Svc/Framer/test/ut/TestMain.cpp b/Svc/Framer/test/ut/TestMain.cpp index c94c289a77..8e2297a7a1 100644 --- a/Svc/Framer/test/ut/TestMain.cpp +++ b/Svc/Framer/test/ut/TestMain.cpp @@ -37,6 +37,20 @@ TEST(Nominal, ManySends) { tester.test_buffer(31); } +TEST(Nominal, StatusPassThrough) { + COMMENT("Ensure status pass-through"); + REQUIREMENT("SVC-FRAMER-004"); + Svc::Tester tester; + tester.test_status_pass_through(); +} + +TEST(Nominal, NoSendStatus) { + COMMENT("Ensure status on no-send"); + REQUIREMENT("SVC-FRAMER-003"); + Svc::Tester tester; + tester.test_no_send_status(); +} + TEST(SendError, Buffer) { COMMENT("Send one Fw::Buffer to the framer (send error)"); REQUIREMENT("SVC-FRAMER-002"); @@ -55,7 +69,7 @@ TEST(SendError, Com) { tester.test_com(); } -int main(int argc, char **argv) { +int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/Svc/Framer/test/ut/Tester.cpp b/Svc/Framer/test/ut/Tester.cpp index e5e78f1a28..05f14c7d5f 100644 --- a/Svc/Framer/test/ut/Tester.cpp +++ b/Svc/Framer/test/ut/Tester.cpp @@ -17,25 +17,24 @@ namespace Svc { -Tester::MockFramer::MockFramer(Tester& parent) : m_parent(parent) {} - -void Tester::MockFramer::frame( - const U8* const data, - const U32 size, - Fw::ComPacket::ComPacketType packet_type -) { - Fw::Buffer buffer(const_cast(data), size); - m_parent.check_last_buffer(buffer); - Fw::Buffer allocated = m_interface->allocate(size); - m_interface->send(allocated); +Tester::MockFramer::MockFramer(Tester& parent) : m_parent(parent), m_do_not_send(false) {} + +void Tester::MockFramer::frame(const U8* const data, const U32 size, Fw::ComPacket::ComPacketType packet_type) { + // When testing without the send case, disable all mock functions + if (!m_do_not_send) { + Fw::Buffer buffer(const_cast(data), size); + m_parent.check_last_buffer(buffer); + Fw::Buffer allocated = m_interface->allocate(size); + m_interface->send(allocated); + } } // ---------------------------------------------------------------------- // Construction and destruction // ---------------------------------------------------------------------- -Tester ::Tester() : - FramerGTestBase("Tester", MAX_HISTORY_SIZE), +Tester ::Tester() + : FramerGTestBase("Tester", MAX_HISTORY_SIZE), component("Framer"), m_mock(*this), m_framed(false), @@ -65,10 +64,9 @@ void Tester ::test_com(U32 iterations) { invoke_to_comIn(0, com, 0); ASSERT_TRUE(m_framed); if (m_sendStatus == Drv::SendStatus::SEND_OK) { - ASSERT_TRUE(m_sent); - } - else { - ASSERT_FALSE(m_sent); + ASSERT_TRUE(m_sent); + } else { + ASSERT_FALSE(m_sent); } ASSERT_FALSE(m_returned); } @@ -84,15 +82,45 @@ void Tester ::test_buffer(U32 iterations) { invoke_to_bufferIn(0, buffer); ASSERT_TRUE(m_framed); if (m_sendStatus == Drv::SendStatus::SEND_OK) { - ASSERT_TRUE(m_sent); - } - else { - ASSERT_FALSE(m_sent); + ASSERT_TRUE(m_sent); + } else { + ASSERT_FALSE(m_sent); } ASSERT_TRUE(m_returned); } } +void Tester ::test_status_pass_through() { + // Check not always success + Fw::Success status = Fw::Success::FAILURE; + invoke_to_comStatusIn(0, status); + ASSERT_from_comStatusOut(0, status); + + // Check a success + status = Fw::Success::SUCCESS; + invoke_to_comStatusIn(0, status); + ASSERT_from_comStatusOut(1, status); +} + +void Tester ::test_no_send_status() { + Fw::Success status = Fw::Success::SUCCESS; + m_mock.m_do_not_send = true; + // Send com buffer and check no send and a status + Fw::ComBuffer com; + invoke_to_comIn(0, com, 0); + ASSERT_from_framedOut_SIZE(0); + ASSERT_from_comStatusOut(0, status); + + Fw::Buffer buffer(new U8[3412], 3412); + invoke_to_bufferIn(0, buffer); + ASSERT_from_framedOut_SIZE(0); + ASSERT_from_comStatusOut(0, status); + clearFromPortHistory(); + + // Make sure it still does pass-through + test_status_pass_through(); +} + void Tester ::check_last_buffer(Fw::Buffer buffer) { ASSERT_EQ(buffer, m_buffer); } @@ -101,39 +129,34 @@ void Tester ::check_last_buffer(Fw::Buffer buffer) { // Handlers for typed from ports // ---------------------------------------------------------------------- -void Tester ::from_bufferDeallocate_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer& fwBuffer -) { +void Tester ::from_bufferDeallocate_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { this->pushFromPortEntry_bufferDeallocate(fwBuffer); m_returned = true; delete[] fwBuffer.getData(); } -Fw::Buffer Tester ::from_framedAllocate_handler( - const NATIVE_INT_TYPE portNum, - U32 size -) { +Fw::Buffer Tester ::from_framedAllocate_handler(const NATIVE_INT_TYPE portNum, U32 size) { this->pushFromPortEntry_framedAllocate(size); Fw::Buffer buffer(new U8[size], size); m_buffer = buffer; return buffer; } -Drv::SendStatus Tester ::from_framedOut_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer& sendBuffer -) { +Drv::SendStatus Tester ::from_framedOut_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& sendBuffer) { this->pushFromPortEntry_framedOut(sendBuffer); this->check_last_buffer(sendBuffer); delete[] sendBuffer.getData(); m_framed = true; if (m_sendStatus == Drv::SendStatus::SEND_OK) { - m_sent = true; + m_sent = true; } return m_sendStatus; } +void Tester ::from_comStatusOut_handler(const NATIVE_INT_TYPE portNum, Fw::Success& condition) { + this->pushFromPortEntry_comStatusOut(condition); +} + // ---------------------------------------------------------------------- // Helper methods // ---------------------------------------------------------------------- @@ -154,6 +177,11 @@ void Tester ::connectPorts() { // framedOut this->component.set_framedOut_OutputPort(0, this->get_from_framedOut(0)); + // comStatusIn + this->connect_to_comStatusIn(0, this->component.get_comStatusIn_InputPort(0)); + + // comStatusOut + this->component.set_comStatusOut_OutputPort(0, this->get_from_comStatusOut(0)); } void Tester ::initComponents() { @@ -162,7 +190,7 @@ void Tester ::initComponents() { } void Tester ::setSendStatus(Drv::SendStatus sendStatus) { - m_sendStatus = sendStatus; + m_sendStatus = sendStatus; } } // end namespace Svc diff --git a/Svc/Framer/test/ut/Tester.hpp b/Svc/Framer/test/ut/Tester.hpp index 55aac73d54..29e1661546 100644 --- a/Svc/Framer/test/ut/Tester.hpp +++ b/Svc/Framer/test/ut/Tester.hpp @@ -36,6 +36,7 @@ class Tester : public FramerGTestBase { Fw::ComPacket::ComPacketType packet_type ); Tester& m_parent; + bool m_do_not_send; }; // ---------------------------------------------------------------------- @@ -62,6 +63,12 @@ class Tester : public FramerGTestBase { //! Test incoming Fw::Buffer data to the framer void test_buffer(U32 iterations = 1); + //! Tests statuses pass-through + void test_status_pass_through(); + + //! Tests statuses on no-send + void test_no_send_status(); + //! Check that buffer is equal to the last buffer allocated void check_last_buffer(Fw::Buffer buffer); @@ -89,6 +96,13 @@ class Tester : public FramerGTestBase { Fw::Buffer& sendBuffer //!< The buffer containing framed data ); + //! Handler for from_comStatusOut + //! + void from_comStatusOut_handler( + const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Success &condition /*!< Condition success/failure */ + ); + public: // ---------------------------------------------------------------------- diff --git a/Svc/FramingProtocol/docs/sdd.md b/Svc/FramingProtocol/docs/sdd.md index 79a6ef89ed..eb6014a126 100644 --- a/Svc/FramingProtocol/docs/sdd.md +++ b/Svc/FramingProtocol/docs/sdd.md @@ -26,11 +26,11 @@ defined in the `FramingProtocol` library. ## 1. Requirements -Requirement | Description | Verification Method ------------ | ----------- | ------------------- -Svc-FramingProtocol-001 | `Svc::FramingProtocol` shall provide the interface to a protocol for wrapping data in frames for transmission to the ground|Unit test -Svc-FramingProtocol-002 | `Svc::FramingProtocol` shall provide the interface to a protocol for extracting data from frames received from the ground|Unit test -Svc-FramingProtocol-003 | `Svc::FramingProtocol` shall implement the framing and deframing protocols used by the F Prime GDS|Unit test +| Requirement | Description | Verification Method | +|-------------------------|-----------------------------------------------------------------------------------------------------------------------------|---------------------| +| Svc-FramingProtocol-001 | `Svc::FramingProtocol` shall provide the interface to a protocol for wrapping data in frames for transmission to the ground | Unit test | +| Svc-FramingProtocol-002 | `Svc::FramingProtocol` shall provide the interface to a protocol for extracting data from frames received from the ground | Unit test | +| Svc-FramingProtocol-003 | `Svc::FramingProtocol` shall implement the framing and deframing protocols used by the F Prime GDS | Unit test | ## 2. Using the Interface @@ -103,9 +103,13 @@ To implement a framing protocol, do the following: 1. Implement the abstract class `FramingProtocolInterface`. -1. Use the implementation in step 1 to implement the abstract class +2. Use the implementation in step 1 to implement the abstract class `FramingProtocol`. +Implementations of the framing protocol are allowed to produce zero or one frame +for each incoming packet. Producing zero packets is useful when aggregating packets +into a larger frame. Producing more than one packet is not permitted. + #### 3.1.1. Implementing `FramingProtocolInterface` `FramingProtocolInterface` defines helper methods for framing data. @@ -161,9 +165,11 @@ Your implementation of `frame` should do the following: 1. Use `m_interface->allocate` to allocate a buffer to hold the framed data. -1. Frame the data into the buffer allocated in step 1. +2. Frame the data into the buffer allocated in step 1. -1. Use `m_interface->send` to send the buffer. +3. Use `m_interface->send` to send the buffer. `m_interface->send` should be called at most once in any +single invocation of `frame`. Aggregating protocols may only call `m_interface->send` for occasional +invocations of `frame`. ### 3.2. Deframing diff --git a/docs/Design/communications-adapter-interface.md b/docs/Design/communication-adapter-interface.md similarity index 55% rename from docs/Design/communications-adapter-interface.md rename to docs/Design/communication-adapter-interface.md index 72e45864e0..b4cf46f2e1 100644 --- a/docs/Design/communications-adapter-interface.md +++ b/docs/Design/communication-adapter-interface.md @@ -8,6 +8,9 @@ Implementors of this interface are referred to as *Communication Adapters*. ![Communication Adapter Interface](./img/com-adapter.png) +The communication adapter interface protocol is designed to work alongside the framer status protocol and the com queue +protocol to ensure that data messages do not overload a communication interface. These protocols are discussed below. + ## Ports The communication adapter interface is composed of three ports. These ports are used to transmit outgoing data through @@ -43,21 +46,51 @@ This port carries a status of `Fw::Success::SUCCESS` or `Fw::Success::FAILURE` t > Note: it is critical to obey the protocol as described in the protocol section below. +## Communication Queue Protocol + +`Svc::ComQueue` queues messages until the communication adapter is ready to receive these messages. For each +Fw::Success::SUCCESS message received, `Svc::ComQueue` will emit one message. `Svc::ComQueue` will not emit messages +at any other time. This implies several things: + +1. An initial `Fw::Success::SUCCESS` message must be sent to `Svc::ComQueue` to initiate data flow +2. A `Fw::Success::SUCCESS` must be eventually received in response to each message for data to continue to flow + +These implications are discussed in more depth in the appropriate protocol sections. + +## Framer Status Protocol + +Framing typically happens between `Svc::ComQueue` and a communications adapter. The `Svc::Framer` component implements +this protocol in order to interoperate with these other components. The action taken by this protocol is dependent on +the number of framed messages (frames) sent to the communication adapter in response to each message received from +`Svc::ComQueue`. + +| Produced Frames | Action | Rationale | +|-----------------|----------------------------------------|----------------------------------------------------------| +| 0 | Send one `Fw::Success::SUCCESS` status | Data must continue to flow to produce a frame | +| 1 | Pass through received statuses | Frame produced and communication adapter produces status | + +When a frame is produced the communication adapter is responsible for determining the status of the message and its +statuses must be passed through. When no frame is produced, the communication adapter does not receive a frame and is +incapable of producing a status. `Svc::Framer` must act appropriately in this case. + +> Note: `Svc::Framer` must also pass through the initiation message from the communication adapter to start data flow. + ## Communication Adapter Protocol -The `comStatus` port must obey a specific protocol to indicate to F´ applications the status of outgoing transmissions. -A communication status is one of two possibilities: +The communication adapter must obey a specific protocol to indicate to F´ application components the status of outgoing +transmissions. This is done with the `comStatus` port. A communication status is one of two possibilities: | Status | Description | |----------------------|-----------------------------------------------------------------------------------| -| Fw::Success::SUCCESS | *Communication adapter* transmission succeeded* and is ready for more data. | +| Fw::Success::SUCCESS | *Communication adapter* transmission succeeded and is ready for more data. | | Fw::Success::FAILURE | Last transmission failed; *communication adapter* is unable to receive more data. | -> * Fw::Success::SUCCESS may also indicate a connection/reconnection success when a retransmission is often desired. +> * Fw::Success::SUCCESS may also indicate a connection/reconnection success when data flow must be initiated. A *Communication Adapter* shall emit either Fw::Success::SUCCESS or Fw::Success::FAILURE via the `comStatus` port once for each call received on `comDataIn`. Additionally, a *Communication Adapter* shall emit Fw::Success::SUCCESS once at startup to indicate communication is initially ready and once after each Fw::Success::FAILURE event to indicate that -communication has been restored. +communication has been restored. By emitting Fw::Success::SUCCESS after any failure, the communication adapter ensures +that each received message eventually results in a Fw::Success::SUCCESS. -> It is imperative that *Communication Adapters* implement the `comStatus` protocol correctly. +> It is imperative that *Communication Adapters* implement the `comStatus` protocol correctly. diff --git a/docs/Design/img/com-adapter.png b/docs/Design/img/com-adapter.png index ebe740facee434a38ece96e58900a6d61893e4a1..e51a81a972fb2a53a74bd0d7fe694b524f3e1f40 100644 GIT binary patch literal 154761 zcmeEuXIN8Rvo=LQQNTj)ic&;+?;r{S(tB^xdkGx^BA_53O?s2wrAQ|MX#&zq=s`LJ z2tBlrFXHo@*Y}+3Jjegv%XKB$WbfH)X4b5G?lo)eyi-w2+N6H`dRGT`@2)b#0`jRpg|l=~Y~vEN$#9Fff>796qSBN}G~*qr!4R9xcnO zGqK5~x?8&BtumJxr19f>t~IABI#^YB%GU1^_=P0gbX>km7GLkC_>Q9$Pep;N`@m6< zDx!&v8o+ZPw)2@lX^WBNLM;!FstNNPFlr!zFStN*%J2P zi2bo|I%8zLo0q@4N3+P?7V7eg{yGh9Mt#d%xO+D_8GF|IyQ%u@iOq_l^w!LaVm%GG zaD`ebKefRp`L`CS7L7jEad!}P+-d3=p{^sV`8 zj{~4bRR*65RyX0bi5O{GcHW2IelXK3q`koob$Rv{u$eEND00~%0%c8Z9mDhITk?H! z%Rm&{|338Q3~w*JGoX*n6lt$fRJ`&fX?`IKL)b_RZgKs38aCe#Zzqz$5*m!{=tGaC zd&2W3lgi}wx6!`Vve1#UR8+)xj6S}Off;6laSeThiGER{Ulg;MI$a&qWTb#qq>3r9C=CwG)?Yc~2;5E~60cOAu-!sbp6?53}r z%q-Zw9GriOV2FANqYoV{+)e4d9PAz4guTQbTwNiIKK}VN#{>GSOWf_m9_T2l&`UeH zTF~>ebFyNW^k09! z^tAA@`BzJhZhx7DHjv}z84fOXPLBV&H(FHm=eNQtHeMF?y3cGJ(C$IEA z-f38O?qn#9Ztop#?oIYpH#dJoVRL}1ki8jXJWit9oIG~IMNQ-KY(Yz` zq7@~1pV(EVZLk_HMuu03K^#sd>0j4@_oP03s1XAeC@U*2Ie2V zF~5~`k*e*Lx$~z2lJxkuTiZhdF|e-F|H+#qCeHN*7JBhinLpG>G7y8d{LhsCsWU#a zB!)8P-W2a2>VtuGZP%ILk5vC@qKYIYmKXlp!TdjV5Pe{n-JhC@5rl>Irn;mbf8?L~ z69ZG!0Q=8ekG>_bN+3oC)?&5I9|glte_mhsLHWnAkQIpbCh_e|MTS2Kg`Xx$Vh}<8 z*i>z!Q7QKaK}1uX@}+5B@B)H*q?wM*rBK=+Ni;Q&R)~6Z-$u6aNYQe*~fb zg#JH)=zmcEpFs3KsQ*v-g84tF{}1`@KZNI>sM3E3&p(9D|9^ysIml!iD|tU$MHPCx z7e*y*qX}SUXCdfJzU$9+<9YJ;Y3+{KUk?kAu-SEKK?uVMtrI#VfU*U-yvRAD48VqdPfPdvB9=q2%Mj-xMcVrpp3 zI00nDJ+B7bACF+ZYNIYpGQadm{CF|@*g~U<;3(V*lOwf$1 z$xh>0$QTo^K-@N+tMSmYEwV<^{B9X1y0=&~ESRDKfrIf0VZ|S7RYoW7^irif^>#31 zE-NQ^L_)&l)g2_#*=bwPuEotjJLZ_xQ*kvZs!eP)NNNfyT*Z_}KSo_1ZGq21Kh z>jjZL()7?)`(m&{{fY>Be3X=t5>9B+GdC>!R4ErZag_a}=%x*)bPPQ=<3etcED>X}5fj|A5RV0t*8BI-OueqU^;6@A*WQ)|`C}Zs#OI-mxaA?0^E;fb zD-QtK`tHfZKWEHM&tdZuC4kWMlw+~%T65z<#~B*B5$YOsjgC_DnX`_ngDVfGKHwDa z6ce zXxl<+5jGa^D`)d7NCL8_Hj0uWtzHHYIq&r4O`9?rSBo==Yqb z+C2=-iB2wh2B*8B;RL1pYJTH16e(X%9!L^P2>A{00W zDu0oF6K_oAYCbN(+ju;O)Ibr!U84XwBf|>G{Nnr_pe{VsV{^ar(WC5IH=uPBYIw+f zSto6@hPnNTxyX^9o53%CGc2%Zq&1YQv4kkt+42c&x~G}3GE=6$zS3Cinkb2ugKWX( z)95#=IiB5vhi02kXO@;L6R(7E?lC`R*D@@8JTD+No=a896vlg|L7~8Mb#g|!6>#5b z&ZbEjkZq0#EnX#6jMHos^T=p7{I3CB} zZjHNco1tbkYXjVUrviqXr1fds2#xJwZ1shccWVV9N54Au=Hywfxy4WB5oKV`|!5j}EKHQXng`af^W|@Afu!`8CY6`lt zv^a3{X@De$IoVZjvazca-N~nQ zm@ZsMe@QWl=d?H4x$|=rUAI>aN{TF~61HSYr>4FY*WTM9E%nn;lOtFePwS6BVbV)K z%(LHY1lJuln5|t!KyA5XY-B-ctrCSCo*83CSyP=pa4@{?l70S6?8&e}eqXWA*RF>fIY0gh7nnz zts?<|=KQIgP|!yl35u752bZtU3Yg*{`=mW?;n@PQP+UBwE(I5H?FEiemXS zT5jGbWMAH>zMx}JsvGh))xPQ%kN1+gW!1aX`Rq031I&16AP|v310p`)$wUoc{lm9s zjphTaKfgvJn#DDF))I44+OrUT4|zw}d`)b4uS)iYn0(T-xw$qG{K_$s3%FRxBd&9H zsjuM;e|0p&LeU$s@occ#U!h=ffWw`a*9hSc87bcEHx{zH3d_mQfmY_uhJ`g%w(YQm z$SY@|Tdk6Gk&{6_jm)lTv|I@}=?}-M17Ik7JNO@eRqgm!IIkuXtW>DHC6s)?nm^+5eld+coL*bo;DX~{QG@Q#vU}f{ zM-45c56WgR?5;AEPF)~RPA5hN030XqSFNH|4<}rqkGOTTYNAt@{gJai-tLK1KZEJ7 z+=V7Euxs2aE7|Wg-qjH%@%^j{Qr%`QD#Xuw=~Ry?G=HUTVCyuFXynIW%U@8eFH2vm z&eif`Lg@b1jbEWfj3!a4t@g+$(OP|f6}11NS%*PhzqJw0^GH5X#{kjq}>5z+hI2$riu>-d`QVgA*Pej)wW&vH1y1(aK>xBD=q{YCQn!IfX>womMy4 z8(p5C@fv_h^vb#YUm=nnD4Q;fE%UH?{h(qTmVxCzCS|D(*T=OJp=2UFrwK>*^~O4KIq*0)vqP^C-)=qzG%L?%6+>%H|mE|qB@iZ zQrWIBa`qStouSVaFfh=W=_!^Uqf>TVTltl}TV9wuO)&9J^i2mFi~df7e+}B78SXEy z{Ewql4oQr`)zm7PzwEto%RjzNJV8sO6zSalh0p)DTu?t5nz$V(>N5QAYWz3->`2iP z{Tff+{ttcs+l7Ds+q!!5c5C%%e(9Y*){5_^gymz>UySIgAOHCcjg!|Gru@_={#>gR zw1h4X$;~Sc^uKk%-!@#K`YC$F!5+k7_vc#mqa{j{!*Q;V;x9=5M?)t4&}%;Y(0IN- z*UAztG4ZnV_3x_wQ&e5I2cd~as#7oJA8Vykjh3*>H z%2T=I^P^hjWNHe0_4eRt#Hxy(ZV?T*<@{lyh+DOKT=w}Kq&-C2_&u1tr2IyhI4VH} zj2Lo_IH1J3zV&kv(_=x-u_z{s!Ab^ZQGma(c)!P z);U^Vs+}?dUeLhcH?*U{B<1O1MR;M^_87|f591*dA))?Z(tU=Au#}0pPm@!mb`6d? zS9A7XLn>&S(fJ4|&^}HyKb#fP!w2`#RL~bZY^ZqiQuj0k+Wzk&q*aTQ9JWn3S4>A> zAb5`vw*rUAnjM{pNsc13eYEYYfeV$BWM3Cn%e+a&PA*1ZV0<#8Q;V%`+gYIC7I1S) zWwh4HZfEyX%jW6sob%;MX2@QUU3POmJ2i3>9&$E-)U)+HZfOASE!uH}T*lFLFtGK$ z`kHM8CbiWY%k;X}DM!W_S{`z#u(qUUOPTuhaB@*+HD{8wTX-pjZ*lPRcg{ zjtbXy>%slWL6%nei!oZl?NQv_^-wMre>yrMY;E?ip5Y%Veq|E33`MDm^{2<-wJlZG zA9XK*#&2>+(1ntGSdJb3PCG9DLFFLC>0yNZNy#}24gK<6Fl10a?`28LE3+(#W47~) zk1XVUQh{g|G%5NMWd~jRDr`J_g#C8Y!Pm8w{mB{QZMul8HWtTxc_aUnS4mMDbpZo)4v`u7#~o|t%>X=fXVCCQZ-yWYl}Gu6fp(1#+H z@x**Hlg{N5j?UH~?959w=CWcXj$Q-~sdMP$U8{HfN86|8BfZ5~a7~W`WP!MvWtQ<9 z7Yh$pq1{8WuRC~j#+=Oa5cPcC8MbXqo=4LNGn^LtzE5rox?;G#zWYFR2;U>a#8?LE zi&>}6?^-ka^%I{*vDcJBc)%wvTe9pEhrZ}Ap^oy~sDtb(kxF3%eZjXMRqpyiOWT)+ z!`{4q;Cz%D?8$4PRqj5E41C~D)VWcWPh7b8UDT+H$brya=xEU`MSIUAP5!a>pa*Ib zFZgnlF66-HHjVbP&k8a&4`6yTPY-^Gkg(~|tt~WrT)MA|02$}~x``ESsbphz)U_Vu zkA~Y{1pn`9QF<>ua8T;Rmth z24b5C(*|(IYiMj3M23bUWuGp!iQqRVoI3cnzOP9C0h&LV{=VE18+1TJ1e8BFqLA@z z)L??%OCg+Vux$|q@3Wmmo~ty?`?JwCFBu-%nQv+XP)p@G2*_x1938q&&k zCy9KENPGSQaI5&mYfnP)z2u?O6RX#FY#jmjacF92n+)JwTZIFm72 zqZk?ahLx_l>CL?VJHnKi9!yaM!W1%e8Ef<>%X1$oYxr712fEiKE3<#6f)+4+I$0p? z?U3#v*dXeL^F~YEYbQzeIVSP92iff2x1D)yoIKOW05x#iBw8v0i}5en zGHzNEJ3F@`!!y_(%TLf~lcYT@U&}#!P5S6bn(EpgIT--W`7zxPXDUhI)J4pj!xXJD zQz%(jFDqppcr@kJdZ$Y^(VnU4OCCyCY9{<51N_lVR} zJjY-M)W!FDUuvkS-bpN(sphb>dCXE_uup6B8)GnOy77wl^;phjTEK;jMg6(j`uRyc z)Nwb{ez8YWgx5BWQ@d>c6)lU=$^B=H0UK%`m05PS`*bcc?Oh)zn~0GW|x4xVA*GwRKc5 zM_0v>%`50T9lE5k)(GzLZQB`M`Qr>cjlp8$`t&j7YV~6MqJTx8?&Z(ivBi2CIX*QHc1Kib4N{&$Gt`MMkwUNDhxFEM`MRPpbRdDuWWhzBK`$07+7d< z^*8mirayM@($*uIyK^kMud!wK0ufU0ScB-XdK!I(N8P*xip!`jFr!lqIp-ohI(S*g z?s^nlH@@cb9Ldy9`Ot{sT*g4zIo+zkCdOw>c4g(uKDk#FTz&A3-I{U{a3%iidE?j8 zvp`!B;qkf}0bB_$)U1{3_Sid4uTz699+#HyfW%OLy!LVtxbYCjGL)d$sU3NrT|EEz zoQ@z)H~?aWMjP|c`-r+Rzz&h(rnYO#Zeu>V8>%Pp*g^v!h z!))jfr*Oz=t~EM$aoQq_pcHTpdbYm$gd9@Ksk~(WCh>1&D@v)?p7Sb+Q55CY@y@#9!!IF&-i`-o9Y`2UAsbKa? z#ffKWTKv3SOW{Z2EuIZ`&xc--oG;d7mV1&GW$2;TsVEcny0K^DE-M;fkR!bvr%Gjw5lPx8K;Vp4YKN>m8X>5t^N4o9E9-JCG(nLTSwgxZH zhmIu5KwzC36bay{(zu@|@NjdINfuYTEb-hQq~)Vb8_fv9mG5OWgBHUs?N~q_>7Pwh z@^frOlIkbuDtwK>=u-AFH#OTW?A?H)61LVO-#Q6F`qKOs^lA%T2N=6f`6SJo&M*C; z|GUd3@@8j7qnRCW+R%G;_8kF0Q){yE#S8VF@eWwKfAYp6;tbxm=H{2B41OFAG_NFh z3hW~}QrzfVf|jCa{k9v%wuNrXmz1FF3DMI?E~%B%-;tmO zY*-590M2B#Qem3@AGB>zX=;N9Oc?=}bkfnZRaJd2yAh;`eucz=K6So#EX^<; zBLdFBH@(I%c1DWF;sTWSF_s|I*H9KlST`_eGgBifF1TgBM6-P8BH|Aa zWIO(5tg8h&R+~h&E@dypFqsdj8^m1hNq=2ga_XkDs~Nx-3uGf)aA|KI9E~5yp@JX- zQ)k`dj_TDHzu!a=haP?4%yBrs-yWnM_4?RX?=Wjg$f?9*qs@A_U89N+^jrS>JbEpZ z!}!)(05U>{Xs@yXvq<|WmSvpj;=9q@4EfH<2)uYFt4ly^G!sqbz9t}`x2kPBT#;=@ zR1luoK*QoYrIG1)U(=0IIkS@Z5IgRC#UCC5Goe8cl%0^Zd%98AH|Q^MSn|W& zlKXrXZeg&tTWdFd+h_g2csT2g`DtC_z|yUJh(@$)ky?8$cK8`bMg%Tjaqw6n;c}P7 zztaF3OwT0cj=<0@@khbFWQdTHx)r`Jl=aOV@0qW+2HhZJcg}i;XHT~F`b9Y_#^Qy- zU}wPl8wBf7fIH*<&7fQkbl9~ypF}`!jnh6$+f>-a2xLD}7g}%kzs1!Ty-Bfiu;(*N zH&U`dN>o32(8_Xj>L-?_k?A`>cbWFtt!sk?*D|~q*3_lp=Kq)b6 zBfC3;zxay#2p9yQ%1+!`f`eYI(x>N6_6Mn30S}(~6)E{Y<~n&M#lMs3O0NzHgIho= z+Exe!H#JdcX7|i}SE}(60=Os}%BSEV^gD~leu@3Vuz3d*NB8Ey=|UKB8FkX+ju9QK zai(F_vb#Un9*D(eX_0u?BxJ(CaDY1wJr3A(Q@|1xWrIB5_Dnq6rOt{OLyK7~h<8GTYrXp58}}Mo6De_~I&`_z zAn&l%l!^v~vk;BSeNvAJ#lz3bVY^!j5(MY8DEsfr>Uz2~G_gQ5F@H*~i5%}lI*V%~ z3nZdox?ad;Qeiqj1Ay@nYcYHC{36nYMuf6@}A2438-$fk!)%N0%SQ$9ylgcOhMsC9%Z!zxVJYnI8#(dp_I|p(xs%}1^eCHqSQxPGd z&YkxtTS^K@NNcZU_U4sId~ihLp}>4W;QhqVV?qb@pr`T}KR{F5IJX*&6EQNrwM&R- zpbJYhK4zm~D^#;@#V4t6Y%DSl_=r7YLwq158w#tXa?pndw6gV93VtzEqn>rS5J5e1 zhqYPB6WMHV!zL;HKPW%uw07N!Bqu=*0g+DoMC4~rq6J(e(i%>JEc^}y4q}S;G{vqL zNzKACyf&=%Ooxaf2_NdI)V!yA7;)IDUT0NtjL60T8|{SII1ENk$Q8LC9t5?YQc3Uo z?2p?VA#bZfM)Ij9JFVCKGsc)F@3!oODMC-;miDmYjrCRBhkDXJ1o-c9gYFv*_aFW& zMFdaR9iA^y#1&LyMD~59cz?WMsYMxFL8>Rb&;!#mXa??>?1~F-iZ&3&u27fxuO>NQHpIM1ByP_1gD+*O8uleH zMtAs~bD*T_Jyav#H*|f&5vP>k%qt$vrQClyT=&%Hp^Mrynl0Ikm&bX=k7cF6CwYX zL8u)sPZww)k5N6)`c#b=n^2TWl7FE+nd5j6qCYmcw-*hjDKD%rF`&4h>G;4dXZ#u_ zI^eOt06u|}bc}u^T9i9ejTQdh0A<$iUA)XQpjnzN0rw7Q3_WrAxoLs$mV6t3J% zhG*`}AE`s?0IVHGsvaE4Y`^5Em-CmCZV_`a9zD;ew7D3@WE3aF^A%Kxj0k2-d%hBW zHp3W}5MtvZk@&GPb+97XMxOYyT2b5LMx&X5>Q1K4+L((VGsBduv37YMV>h_IqPJSd z@1zAx=wGbui}DkdOC~73w-z9Hw5V*3@m*?LTG-20X38=SV61sNjz432Nxp)~6PY%C z1aV*2@gTj8lU3I8y>p6RG^?`{Sz0Cwzfp!?`xrGPVG9m5qmL{Y-q!&15xn)x8pDI0 zmpE%q<;8+iU!C*dFQ=$91>zwpG(mJNwEzXiRXNJ zh8uhW55jh`)acN3D6CE3?Mk?WJJNJE+vL8o#0pFC88PN|s5w|X+gb&ByBTSjr)H-y zR_Zhr#Z9~3NS#PAEIpf0XRNP|F}U@z_J_z6nXDVr@Mw?SP4MGIO&j94)KuUaRWe-$ zf8P2@Q#3gF=KRLHZuPRmvwoi!9^n!NfGzD}LAs^f2e!V4ty%?zQy)d(Gx7bt!d2>n z{v3zt5~<+I9dQrimlbPa-yNTOH@VCcoobWZpZVnPQv6K$i_CA8;RTO-ZwX2og3D*d z@51m28ym7z!&|JB*Qi=-$3IN%wdPb-elgCuWhm<^okmr5VK4_=&B+_J@op)ms|TqT z6g8v`cO8)w5W<^2I8eK{CuI&AMnBdR%iE4>ay<$ycUEN>Gq?zd=H1pN9nPI!;GJ|7 zJb0lhkn3~!%HPh{V<>bpM2U4iFMi6={$Ra9p#n@z#m$qq;*!1rG-D{)Of-^BR(s{! z$nJ^z_b#7b1xxhmwIXy7Q7%%i0U5Ul_S69C7L7folJUW)$UKb;TF4;C(nmfu-#m9| z>C8I-g_(Vb<{1_IZ1qf6kb3AxV4(USl79BU7vd~Hbz zpZ#))dX=2aGvq@;G5F8DLjDUAE^ck7#gQ zeL`zgQ5RDNC1DwTp)ea7EG60>2eUV_G(f6n1lXxz@|GYN^6Hw8;f7#0##mBCO^uQz zch0WB*Wt5t%Sbw{+ffA)j!kQAf?~sw6I(VJzPu*pSxpN5ipAAM#tw(2IDeZW3n)G-tioM+ zEn*8W(u(|+1=M#Ix-u~Aok*~0FRw{|kyAShXcoDbuRG|;qG=N$7UnDB(=!?rWD?DyPt z2ulwD>kFx`RNhx?Yw6nwvnq3~h>vhR;?pVjDsB*0Y+7+!Fh7J^IgGL!G7xQu@^{*d zQaAIKPd%fiUZRlmb3}+BJ0p{4N#80m=;0+$9y`W*=8yT4TeubLM@@Q_qM zB&y4znE-n0LJE$%GaeqSCMwL&G7l6GuF#q#-|pJWJ;@fBbIxoA#Z+W~t7Qd*CE`zl ziq!-%TcX8js8zR@j%(R%&Ps2dIn`Ha6B%inrL_6<59?{AE2h@RY%{{qv+O>u+r31x z?0B@k!Wj|ap_WKqvJ?OhpyPlKN8!};s|`$auqgPi-Jrj+v%PGPTT1!k{3fGprLp|b zu7PgxYO}e;BpKsc=Jgg00(ZwJZaK$+lnb#|wyD&}5drCHN-nX~Aw(n8$b-PRrV{O@W< z!OM8I6`$`B%6xkgciIlPO{BNW3nsL85jyU4dJ`3vsnJr%jT=@of8gwenn4L2n+gWD zB};gg#05ZTJiC2H7ZqtQ#;n@22Z5Twn7xYu9?X(U5a6ZL8ri5v${5jpD;)}U(RxD} z^LP=Af-Z5-%cObeAf@{Vn0I|>R9v>~fLROSTjIhzLn6R)I&X9yR3#}c9>8QWjNQ8 zS^@S>^~=1b$g^^?-acIFr^UHMuMlWI^$3j=!WpB+r?9YSDLz=tx~?3@Is-TD(f1KvA6+s9R*Fj=$wWT|ntxOoAl z>yu?tYY@uF4X{!G7=L=HDYeoU$ zW5pGpxsR>bjLfggil66w)<#Cxeo=;P5ViY4kudV+l{_&3!0gN6TpxH*Tt)d2X~ZT> zDQPH6oX1$CY~KSTIwBIiWacl25smH44mvgy_v(hU1{~q}6c>A?33FiMmkVD;L-qLI zcEgS|pmKp~nugNr-;Y=tjUf)#RyM6f_b#Gq$Wn?Gu;2MPYCop+TNdw$lFj&jG^|uK zxS#GUqZ_ptuQ{Col|V0V-EuwfX7dI=z+LEAzG-{l?1~E{tw%mc#_hun_u;iLauuKJ z_T8;Ej_ScqGx+qJBBD2buLnEE&k>K$a3T`n`7j z*nIYU8I9Y@KIMb;3!i}0f$>ojPbL(PWFq@P6uH>J7bb!QsfU)tgQ)c#w?^5?M>EW7Ii{m+A_thF<;E{>8AhZ!_j*B?V%JVw$1Bq2x^w7hIF}dQCkH0t zh%nR`<_al!5?Lc@(tqrdf$qpwG9HDld|cxDP1oDZX@TbRd?$bi| zl)vBtI$lam=T{F4lEY*=rDQXzm^a`yDlHSqF2y9*R<`cUxJ4arFvAD;77~`pn=5G7 z)k+cGt=)R^P! zjNHT8mX^@kxk@+}E@HV{)wdqZ!NOom=4|=tOJalI7k#q@@sW?_0~qm!1w2^Zp^>T< zgL@d6>=t>#7h3{q$cT&peYsl$Y2m4d=jn=Fz?*V(HY)rXxE7JqWoMT~WSRO^c7)5* zCADD_P4H-Nb!7!`@ZsVjm<+`x#L1j$Vf#d|WI#So&Edw*l431feA*Icj=94TITG)dDaVp75#Lx6bofuiYq4uMNN1 zfzMc9yUa0kFOFUV^++DpDm!oyk{$q7U_q~2mB^A%xzii6J|c9+JE4iU1wXkDEA&)o zp^DFwu$5v99RwzPjJgl;sDt?(8f61~WP z4HGGD5Lqnye2x11w*c_w1jUTeL*lx#)0)ilz0AhwL16v4f3@wb(Kbo> zlb2=0;qd(w;k-6l{Lx};FQ4U=@My4}&Df23U8OL{Z^ezt z6s$_xnhc$gG1K?fDs|_ov5Vi4TnsOZGdloD`~(IkFVwAU1f>kdrtH%+EgNEKbi|>nM2No@km$AJJaGJ`KDL%69;PqOrCIf-_&)NtnThoY%cFQ$drAJUd zAT;(1pn}|2=NVN&3O#nIN8^B&Nr{iH?)1-nD6@6yn#7&JBegWkOHx#)mlBQpyI1v!o!nL7zgZyMyoc0j9X zdlSLqG)XHJa$@svU4@4IW2gNt(CQ34eUN+!R;DTS)XK>F{zL;4UsAp@rh1vD1hMwE z8xNcGAmifViddjH6*GzPh{SWQ7oF8HPqf1m`oFbl67IVim!TQ_nZ5jx7oL;%och`3 zlG{5-bk$j@hCzj=N8YJg?koIAN{t$UT17AaQ6sBjI=6tS74SioxP)9&SR9_0SW8OT zBSS{_^i!vy&LG7d-h=A9T*h{GwY4Np;v9P4VcCw*l5s%`frFI#Six zt<78RDnT>i$!RFD?P9fEjgLP6xKnhgazxNhS06QGWcN;rzkz7`gtm;M1$7D;>FXeK zx;Uh$-pFxkgMxd}dwbzwwg=WiS9 z>NT;_<(IZgGkcgDI%kSBmof|9>6H^(e59+~w6Ycu%up5Hr_BrZFxMT)qM%X{&_T%` z-=}#JN2C1NS>oeZ_C=S$(YMHysnDLSX+~b1g^N_MR`KSRyM7Pryl zx`W~<;P+ylqzMdP5QCnk`A)EiD~0<+6NJ{;&)-A*cEMA1Qnnr0U19X&CD|Lr1}JAS zYaPHtNW_GmsE(GG=c52tJcZoIDuqT+^=D9mUOU@~hv{6e zzp27m`-Jlcmxa2ssMuIlut`s>O=$eybAKPMk{AeuSXH-eSWHRc*F1=^*2iR`uk~23 z4P@UR>7^^+ndRXPSC}To8aDjUc4~)Maeru0)3xNruf5ap31N%k8`ot7qN6Yz{A4YVP zn`j~n1n$D0ERWOoL~P(yWS{?d(1wB6S;YYd@`=HCgWl}rf?I-4Ba2zfS}z1#ksh9s zlB8&DYyT44e>J%7<4nn+9S`NR<)W{#i!YVQpaEY9~6_1j~BFycvkcp;U@|o0Q**ujox%r6>kg1dA&*TlJE*Ap4~4tH55a zm;Ql3>GF7pamC>GE~@>n+7Q&}*5UGNSgU}7)ntR}yYr^!18b4T3DDnu3gfd*>&B3$ z#IBAb@9HA7*ziT9Cd}b8VEVWYwK>@SS>}UKu!UM$ZHt;scSQ-NL%zgBRIIVXNeLBn zVsvP|YsfvFVMeggM@AWPu0`3?_=9Hc-?nn@zPlkPt>n>|yv4{gM#P;;InDx)x(jfW?PSu?{ocGL}JMD0k;yTzpK`g9z6=**-6SSyy3sim6WhStB0RXF14gtK+a0HU z+BiHZVQ=o`P++xNG|2CH5J{5~ti})%*T5YIAp@4FhsmniW(;+L*Q|acskK#sRFz`F zPCeIKQYSZ}frkj&=BDB^y(A#bR(DOBBfXkC(Tq$miT3XLuhs2N3j(wbvv};dR`S&$C&tCo>nfL>lNr@Q;9{LpTZZPoPe( zC1rvKsz+ljv{#GLoOpFar%Hnv8{_Zit!))u*b{Hd!U@x(fsA9elr|6+F`5)?KOd40 zRa2b+cPl>^nz=T*Y7j_`B6DQsK*Myyj^o%WkB2;$YsUhNZ8G?z69Sb}83FQ&-17C{ih6i0iM`rs?rF69T_ z+>Jr;lQ!s^n9I|EeiE&^#Xj-cB7@Jd1;a)u{WhI-T`*2{{>*FHGP;?R<8TTdiL#4Y z6=>0=+|kd+dn8ANUOQ7=U%ydwx|?qLGO~--dm~jpaU_q6=_T>kYx2$XSb?~BQYVdiZnl3u z&t`HxuwkE7knJKw@6IT|I&h-4SI0ZK;g|9B z_^Ho;WCfa*P!O&{;iHgb=c$2kj4 z&3xQLv*VINr>L({8jz9u-u5g*2(XK1H6xe6<-nT0(v9R2;dpHYlK7TvZmFh@lgBK+ z=cGVF9!r}hmcvp+y;W8J{s>`xwpN~`+8JcP*M#Ue*oMSmo;SJAZTap~9I?{&S-@EE z?mv=$ic&9OY&&r+pDuNLh0j&JAGZYtmtF`|XDn`%hm{+AvnnpKu_f#V?a6YvNSUn^ zZGBWCs5>sJ&vcPjw|s>BXrc6se(ejXam0>-qI?lnpa)Hhtol2#q~@9}ZDpyC1C+H} zPn+MiIy~S6cDE=Jo_L6TpJ<{}`7C2|xjP8nb0yyZm4?;Ye^9(6J6qk?ujrt9wXc`+ zz`oDCRbI8wMwMQd1bN~NgV^!Dt_^@@lRsO^_t|bPHGl588SHa?w_l(f0vkZC9k?Hz%$P2GrBHk?lsN(w z`1-IZhKE)N02CGj(b2XjXSlh#6b*fwIplLW`rgC2h<95I$T*`2G7|CSKFsivz`brk zhqX$lMpluS`8(lCzs4Ab7ccL3=?#s{8gPsw3RE?;)QEf^@|Y{qL)tCiz+7578#V_S zyPc|gGF#E*X+;O{clPmf?`)$zCD|kRHz>0S%4hHlaRsb0t@Pr--(V7m>p0Ro58^q6 z4QuQwp%*T09l8J|HQh=YAFT!plsBV1zOPo-FRh{%Y4wIAhS8J1N0{V2pwbmPVf3u_ zBY3>e%h^qLyt&}qIJAkKZL-ujm7G#%cbaK07@Lv0J|_M?jxK?bDC{&bE-^mF>OmT6 zeDLcG5Rv&+1bW)%ytyWEOFEI`jg6ucZz_Ix&${3od_~xNi*p2A&N@)epu<9Friz-; zQ?O8vSZu4pG~KC#o$j`fKZ^|j!{*VO0ebO13VIdfmo42ZY7*wr^k^*KqCam}_7@jD z=0NpVp~Nn_QNp~BIeR<1xgU!ttFD^V-nGat^2j$LQP$*l-tZ&e-VT>wLe)nPN@?|x zC|mI52ejr2sxaYhEnkY8uTtYkJkqU+UC}yAxdzJx!cEG9ZWbIsl!~VDd&d(S4EA_U zjl!aNSR9F1%F5*eZUt`!w|J~Bk@J2$6k;@%O}O=Gt=)6!D53wB4Ah)9%E{3Vy;IvU zZWQXbuH!sbO2=uy7#jAK3V2HQHK8uxo&-5fkFbzCTN-jjB4kP8WCo}02~Drk5>BV);szOsY6|h-k4e`p&~i5xkS&}AHLb22 z>{s2iJFW0TIxn6|(39Ke*5<1FW&=DdPM$)@hs~GA{j3dLOfp3mZdan)?(}bjJ&-Lx z_?;-F1&?4#LIwh;2U-q!@@Peqfy!r8%83aBUZWLb9&1K^?6`!dGOz>g5w}NaCqJNJ zM5qnAud=9?Q*DNCTFH6>`*UA$2vKWr87|6_kVG zmwR;yGC)rLUi2P9I|=A5I0^|Qq(d(I{s@L&XgcT6{QWHQRdcl!lEG(ml;a#4A7L*u zsVQ#IUF^cYo+f5$4@r7%-P^@jh@f1!7>)*|!*A~0X;NlN_NXf@X50e7fB0!d-e_5? zKf4(#wO9`IN+%nK#_vQ}H^44&f+S|NxtrE97Fi@jf{peU-qPYc7g9lQN;DDekH>z+ zUP5>xN2V;M0Y;bv?4G@`TweD<91S5aQ!6hw8ljz#0FpCJGIz@a8;kWK75=2&F2l;` zzF=tF2yo-+y0&rL`Rmz1fF|HM;+`R_G407+Z2l2UtpK3#y@AiT#UkrWEiW(o`}{@& zpbXif313#4^WQa|Y~FMUY-F8X>g{zikdkfpZ>c1NY1UY;#(0UlA`|;cJ=Bd{^V1aI zATBUFPXE?uyyn2;>RBM0=X?|W%=?0Cu!#oep2AEQ&qknHn-Ls%4(m$Ky(8zsl&In)^%lnAkohH>YBXl|n=OBMoGwTxz!FBJ?xF~>kbX*hH_5dAj zM*QgAJKYvBPn;o+T?7ZayJ9F)h`RzVr=2C-+vlZCAt3BMwoAWtt*SSp;1g8?u<`$6 z?=7R^T()-6KnNNjKyXWf1%lI9cWDR#g1fsl4gnf>2okJux8UyHG+fr+ zYkxag=ZtgD|9i)HN7K!yx8$i=HEU{x*}OPvDQ|_gVIKKtbQlZ4M2L2@K!LgS2=^ie zDCowyye=z#_L3OS$ml)S2iowEFA%n6nXp<<7Q&9ak8D3lvrAY22SRgc%pA^0JTS>! zmnkm=PiF7>`9sb}w%SOTt%k)VHh>|uu=Swqhh=!h37GAWwDFB_thugP5bs?wOJGQ2 z;2jVh9{%)mT67JlO<{4gL`{dza6H_W-3&XokeIx3Zuxu+TOJdicw2y6Tixc) zHnrD3;mcD7%zEmnL--i$Lt*cF7zf7w+`!4#t@Rsw6JANc;PD*3R{*ggC!Et8bU|;| z{QZCZfcg;0Gf2K7u78Y{*CFh?2!N0`a5xFxLXfey*c%I>#>*pSlH&tJjC_>pQHR_py&59fYtvdCTvxWDPykN2`oey0fJ< z<6-9V(MoPhB#4VLt#$#(y;rjoxio%5(O*%%v0^B9lka!(4haiCk)ZcUMq~y|#4B=d zR`+(E_paNv7^H;2k1dG9{B~w&4`Qf)r+q7Agq&mX40cUMvqj%Fy1-45r82)n{HUA` zt>6*q2oi#S=E=5}W}a;`fs=3ECwLE&>1;YC4Hdp59C%oB@f|=X*j0kJz4zmtu4zs; zS}sf|9+RcW2&w3wmMV`kmo9bs7HhWc?V!G-AyEYC#ZjlEnUIB=gQSTcikk z?JlT+wDze2Exy}Y#m-8)%ZJFNiycQ?fDUQtKByajpeyR%Pfk*!y(z+J$jFELf` z`75>T57pTAScfFatdY48BdS)t<(db@`m>U@iZGFbBF)BMX#&9%0Gx_u&ynm5+T*}W&fcAVs2u40iXW)TyWm8y zOfMIagox`5Q1b-h7T9ksoiFptcBD}ZfkRb|Cy%x0+cXPsyDvu9dl_LaIZgX7^G~; z2bgKjrUwl#vY29Daq{}E2Y#4NF?+h>buCp^z{Z@h?+@$euV3u=z>LMvuvh1!;cet; zYZ+2oU&VRns9CK}4WhhHHFrc#pIGi$RpXKJWg3GAVhx_CD&6akr0RVtPfxwCGTasKdxdITOkBbgllJH4)+h#S2)UYxRk1T zmEUpm7aP3Ne^+U%iqZ7&T{9EqkTl%8zX4yh2GTn#9dmKhe66F<`=oNe71rpG6(fYf zunT}ET#oNuIB%cr7==&A&wb$6UG^(zdyy6p{1{!QiNJomAg=L6$iN%V`x<)R%i}!t zEPvoE4SYkYFr4GQ++lajp^rY4LdluV#gcvM@hD&M@lRa}(c{lwz5L+$#%G&$&t7q$ z{Atjdzvv!YzNG4esj`=X3}}Sqo>%j8$B+UBz8OJJ3h&n*?#8^A^o6u7OY0Z$tsb)} z35&nBHGEjaY4pclYDM7c7CkqQ=m`zsa_J#&8ccli;p-t&tuk5vU z;-o9j=c>o;PI%<%u}nU>-~siwFCPxAXnWbX1bUZR%zo9r-?s(i%<&XpautXgGL7SN znWs>H6;r^~blx*Cd+yf|p19-JIL^(_raS4CO$D5m3BA;J{JM080wPI?Gd-%x@jiBzi9=|l5xA&Ko%FW>gp*G4VZonPG$YFvX0-R`~h zjPrpK;UwP$FP4ja^60HuK*xu7bLR_7dB7R+{y>k*fK21+^Fk$0WvU_Z_)l}r!A^^> zn!*F-!QA=WZr0zp>0`sreAQNO}P?elW?+f?eo2K z5jrkp_gUf<0z#Xr%@^PC4%$Zkt{o6IkU`znY!%luI)vwf@XIZMGzz)vg1+5PBNws1 zD-g@^AE*_XqI|p^JnHBR>JkIp3Vr2BLEkE_ig7c2it?2@UsJ{9!2P^v2IoiwX-8Vh z#rw>e9HonqIdo6_&`L|0U_uTOaPBd-ycZt2=V-561k@|#V)B5l-fDO$Sf=7Thwlo( z9GH=Ry5=_&#;En&ep>1t z*qYjSR<#UGott+aY-+ucNa@@*uv__QaHN*LXZYt*Ka04BJvl znyYjGmI`Na7npT9t%gxy_tmzZ3G);b^?5+kBM|7Z?(I%EYhW`ihRdgK4^t&R3F1@sG6kbg#Of%jr#Zyt|x#47OnF zE7H{;uq2)6yIka+O|FVcJND=tR&$gEOE~SPajo=(HswE&>`;+C;f`O*I`;K3&Hx`iecEiZ2 zYK^T$Kf@j6avx>r;jf)5W=aqpE3rt^9N!s8p6^CDk+0U9Lah)xYrevG zys;N`Cfab(7-kem2uezLCzmd?z821W5%s+^`tujP-iy82?ZL{{68n4cirx+?y+{=R z^IMO|>YqF`T8y_VO!QZAs%Mlv_s8-qYbZ&wMG3*&Qwwu3Hd}8#dvh?W_qXL^$2V+f z+_4iS>0Nb?l!<@3d1NIm$8>rb6p; zRN=zL14%B5FnmBiS1^`~k*B>ltZ|0BF2YSOZq(etO|e%Otm+$XKUZE_K(R1}by8oo zHGXD(tK*?Jro1Se?!XF*N*mh6vkm!l2~2#9gM4$HcHJ?6(}*XCJgW`>^uE;=dg}?3 zscU(|*!EZG9|7t)gWR^oP@BxZ(`}I;l1I|3fR#y?vAUr(K0Wdz!8*2mTu24Guign? z6T7>JQ}sF2Y+f_A=ulNHXO{HxU~JX1@AL40!8KG|?G1-3@T3Zqod%s`JDnpt|GM$W z-W*-&U87mTss|5CU7@4peRjbYW=|RgOX3z(#)};b?{m**C|<1G`m0zrl}DAA{3uG` z{KRgNbj3a!-NbzWZdjd%_J*0u`Hn22~5eP z6;WMc6j7`;3O9UFz6+y-F|8W-O=euEW!kkx?MmxGKkB=dcGXkn%KAsQWLSHD`UOl2 z==PS9T4cD?W!&AfYm+W*n*CtQGU_CT0i$-9cY!n4$tqWzhO{W$ShHxky6BI2tENI^ z_Xq6t``z|s>@#Eh*>nm*oM~+MX0f$-SUWCCKh}-4(p_|3^LZBOC9xFw0jsEgpdW+DF6%tsF1w_4& zlFqp|__fKM5@qb(B0kC6m~%eUiqxCNhUo@Kg>+Lk(4n+?k@-cEe0=Al! zx}D55@M}n(J~nQ*iMiGp?)~c`7BlZBrGG``2S3vWwfxq%M)BZeX+qK-3;=vJ=7><= zYKd+-f2)8v)CPh5@`3{_{EjlUpmMnJ<(3)W2^(W;Laf!#t?4O24Z*g1&&wM*pQA+w zN~>BZH{PRN2b0d{`YKxjTEJ}MN``R-9|h&gz3gV>SJ_Q;dZPcKrHX#%u5`j>^};jt zus2QhRp!;GW)m58ZPt8|f*zM;%>Khtzaxdko2OsD^ieqbfgoT$_ zPfV!S^vgRwhEYVEHQa*P+-ly%QG)m;j%F!$@jKF3Y87+68k9TYcfe~w-On;S#Lw@` zwH)@2J?@?;&O+YRVYOL3gVuL0+>|l|cW^B|?ALBB*Ifq^FW0V6wunuO^*sFSz&5rQ zm@Am9YcZg?`z>2adjg*1t{~|w8#i^l@n?PpmU2FgNc*l7(jlEO=UmxJlHG(N+sdjpsJF}-Ev5X(ghSJm2^EfR^PgY-J3-yw$Jurl0y|3ITak19e3+=i z_)DfknfenPQ<&%{p+Hz7N$RS0)t+Xn{I6#*t$CAEN6zI-iEM2L`FlSvVhbaUHmals zezc~=D5@*tRmU=F6gUVt*#|#biR~CwSO!^Acj@}u61=MCj$%w!r}ymx^V$mZ{5kI$ zm)a~r3ZLQSP#}?&y^w~uw?#>O-r>i^1(Jf`)2ba{W0d{cz|2UL zGz8dM=u+F!@P8~F%@v+n64>zgh??sM?1#tFAp_yYf2pMiI+}aWE>n{RrP(P#CaR_ zm|x)87qjZe+>=Uq&g7n5k70=ZBPV?-Y#efrX)G!9Hpd%mBB=~ne%Cbo%fJ4A_hC@- zcymOx8uU4=#u@3Q$nLo_e*X`=P#^H`z5YF@`ZtfDzlx;NJlal8rK&Q>nWN+mYP+yw zy2So>?fmvXKXTefyRus6m%x#cIf}^AoN~d(6P)&iza|M zz_uSWgrOS~3*2|Oo+Dsj#SrFj5!qHgo~(rtmA1Tu;?|Mr-e^L!mDXfbIhIW zVuHCi0#Ov3ETOz;Juv=MD6BAmfj&FPNe?Jum7UnYwlwuy_u7%FjuX{=rRd)c{=3=7h|``5Vj)11tZ z#ytD%XBMwpmP+?QG3Tw37&Pgg_ASK$04_*X6xT(@*XM9Y#={Cs{@zut+c$qVymEuK zQrIJ58O zGvs^I=S}iInE&-faTzHuppZ+8fna=f9dbSr22rd$ET@MkYHL`IQDLS>U(y$xj#-;$ zqZ-7PNnuD>f(wX}z`3DXih(#B>1z+_b7tm>{p1 z&R^lSjEY~B2UxH0es4oOn)!PUBPbBkCii3pEIxa^VS)}(e#^a8({&b8k+CEvlVO5) zjVis97n(TJnPZ&JvvDT5LY z-dxJ=6Q(K3ZssYmDsA(|J-$zPWna2_A zlEx71PBUW4L{BK{B~4jlUX=XRb6S0Q{Xn!N-@hLIbl>8`LY3Maskhxx0!bK@En zYYIExIj^t^dM?XV)0z{dtJjp$d&ey&PvkC&QvdbZzh6#jmwAzexRWB?rLfdYI&R$Z zqdejqj2SLh)L_O6Q54&Q_laWSMIv5){$sKX5a}X?so6_Q^MXn1KJ}NbNoQq?Xcd+S zan?Hb_*Z5RIfzWU?J8i*wma&y<+n2bO?NYIz9;wRS4qE-&rfc`{&ZVf78!98+A|d~ z;j&o;v?6CeU63OUm^AXLX$AaAs(y>8)`eeho27p!EVmL$VK$XHE+lZ)Lh@@XLsLH2 zQ{mGdnuq+_SaS((rTE92W-r>Ct62qd-v`dqNnmi+fu}|tXX{6iy zCMo|1lnGwH@P2VEWz8S-h*SOi0#f0Y{AE;TDg(#K6Il_dsehyXANYR07H;>ja1oTd zXTTd^W59dhca5^-XG-~0@4T*K8I|2T^c$7@HPc8qiW|xCHvxeAfuY!f0M+n7smr7SH4oIUSEgbQ91QGWn*Ww2;L)%ccyZF%NI|u~m+` z|EN9!=r^Rw@Nx_Seo@|AwF48Yd(C-;DRDffWe)o0!Scr(DqO5cA>nIxwuIFo#=eggoT3_&+t@=ATCukFRIxASD5+W z^47*%y_t3ujk*CktG`z^i?DDy;L9YD+k&#?;f_MMZcB0JxB=N819{{CDea~ViP9E6 z4!a-qH_r5QVx1IKT-$0!&JfQ${wS;1i^LG`kV2VRxb|+QO~rP9dusprQ)f;-e@uRu z>q86O-(%uYek>=gm60kF|7k}ueYymg97x+x)`X&Lq}^Krd`3C_2kx>fFHo(mt-<*_ znpW8idx78t)?+}eD>N%PU6hShN@K4`KSk`fy9g)Rac4%Lh`td*Il8|zq@KT zh#F-tEiq)1Djd7XZ?n5StGA-@$1om;9MK-gE>EcAy%i0cTbNBu*(-Irqas}4{zo|| z_4l9Wn%KJD1q7;iYHl9LR)pj`(_F`7JM(L?9RFfJtbQ#xGYbon-51Vs*)^?otVJ`=a%UrIBG3kRxqNP=$RoLKCssBHV=-;b@ zj0({_yK`=ituZIDEiQ1gn85P0`%OA|C&l9yhSVqc_3yPr#`V{dV_>YHxHQ~bb;B$> z2*&zf7TO7waL>-|*y%~rcklX~z^U4atUP4ye~{psl!1-?j+@?$j2^y`Xc*?CShZgP z#bFF|^zT{Fi)!Bte9m9uqIncpHj13F_}wk}j}=XZfoQm*SxGQ=V9Eu7&=tot{)2MK z6cG31_m?hu#6KvLy1AIF1^f@2%-gi~2h$wor4-v{ye|Eqnf_ehqm84jWp&GS@atCE7~)w5cY2 zzr?>cpZ{za{L#KK#0(~M9Q!?V?@0A2H4B>3+Y^};SJw+sq z4>z*IN3lZ-L(2}@&1yhYAYY))%=x>X{op6jR&~9o004lR;-9RtH_o?aq?}t_x=+ho zgI&-3k3&oESKpYXMG87ag}++vJ<3e{o3s39`2X)e+p}@L`)!RV!i4{a68~?%9P{{X z_7b`W|7#fSKDaZg4UORrY-%C-5T&tdJvt^UYYREKAtsN{QgR-Pc8FWq%Y|_&?%qsl zKTL9Uu$VDZ{HrP(cxxc8NQ8c~(D}-WN8`Yh^I<@J5MugIel)y{sMSCTTH_gYK4W*l#V zC9$?Nu0#v3r3l5_2B22XYv_P`u^H;qbZO)54NoBVWjcp(p^Jb7nDT}`zKAewk zruu{0-8PW8xVe-Y3M+BL6IqA5V94Q^SyCxl^ZDa*Yw&kMN}25)cu@qF*5;DBHenc? z?0&X$!Wi-IENaY|&YQX0ku$bvHZJ~Jtp?bSH8EIt8!|Hq)~8NwnU2kMS~D;XON=zM z)CtvGTohckc1#GcCp3!p8h^By?^4>ej~!A~9`QD@7(z zmPk5;uXndM;L(Y^*7E1?D{=ys z(lRk=&5JJ@W+AOS1->_?mIsGuSmwhN_9E5$i4AB8Nd+Wv)*|d7dd(pNLNUEa&$P@- zE8exZHws-i_wnaH;O9FZK`ZhyDHsI5tIL{LWmCC7cq#u*sVt(xKasjWX{9GiV_bdC z-zW-V8?Mea+5V~?e&!UOCf#Dj0v_(b35P?hw$u)U-+TddgDJwPjU_c&!pi$_ck*xY zCQ0(I+?ogP^}c?Y9zx9unA1)fm$a4e*cvq0JsN~47F9*}5NeEHVVjP3GH981^<{{x zY`h_W&NK*dJ?1jXV*S@^MY%I%IevAg<9$Ibw?Yn-M80NqEQ2uk)UdAT9d1@gHNB3|21;3rm>b z;selgSFnPuTz(L`flB;8PLmnZzF{pJ`G6a^hQ;k|-RJ|BjoRdk{P+#lbH;_1_{~6x z5|Y)`gpO9~T<9u%z8{?l{Fz4HDH8~r=n~iyJMSOsYT6x8?<5=N1>Ba(UBVro1E}Bg z-<_^O_nC1`dD~mOE*p}Uc;Z=p3 z;6mPf=V7|)o=i>=Ycnb;a8S0>awfK;`>b?Y)jmj=a~ABcd!WS?H{3sSc2f4!Ng)_> zO0;*q2gd$i=C|?{H;aKmY8Y?XD`6_`W7H5&bhuylbyAPQh+H*yzQmH35N6x`XKFit zjI-ew++__jT3nBiuZM|Jc3W;|t{}N*G!wa3jS>n%F%$NpwxhpvYaxne+A0-rmE;artTV-Ki~BIo%1wi$t{v#I7!Jo9(5Ol!+tB(oXm{>eSUwsP=mIflYr zI`M==&SS*`(^D9W(Jlin0BgQo?89roxIfE1*eWB8I$Hi5Tn~}aS1QjyFDMzuGhFSk zb9$%-DRfWb>pq|qso{s}(OP_MzdpY>Qt34SZ{(mu-@yaP!u{)N0QpwZpWGD0$q^@w zlYD5av9!z!3k2Y6HL@7+%T7rxm7D9L?wVZtRY8nDw`W7d)aZ8k9Ik4`^=bx#G>a&4 zhKdU5-0*^pU|12PISpJ6DzL8@1~?s*Nxq#KnP@v>e~`7h8L_hc5Rj3`cB~o_0Dzrg zXOk+lT)~KJi_7|NI}^7s^}Y$0fCn0Za|K9;(eJy{_fi6WRkZOxXPPLH=70Eg!Lg$Q za=nFjkB*40ot3aa9%5^&F!|{YB48eJS%+xW;@u>cE#Szh|jP;=RVys}Qf*(VWc zn|w)9lMYJTTiJLq)G)y*2&TzEZ`(cfAm88-uieH4;PUV&r_}S{Ry8wO9Y3XrvQ6FB znRjU6nyu#Y9Q@1bh=00f@^G)H!daemz)m1_R^{qq0^3kM|L&`&m;^)G2zm~lo6ut- zi*M{#HEBWmAUc8T{fb|M;1C?zLab-YnJ-3;1e~Are_fm+rg->|nDw{|R|NV3tw_gY zRc$PUjRZ<6TN$8$!m}%#J==qd;)?CJf?)hAXq6y*&D(MCttw}C{aF4^5X;?8CMD<4 zc3Pobh`pIOf-0_z{cZjnQDZd}L6;2ZLdQTwmenty;ST}7pTp`O zQxveZwlN7w;%iVZayZ)l zcG~Jqd_oe=hTW5uBI+ps*W$p$Q9%~ks-L~Qhm--!YSuWkGqdG*f^>WO7^FX$c^Kio zO)^}aXlj$|vTaQapI38bRn?iko_4i3ZDPq`A0E42oN&F5G0lFJy>dgkMHiiinNb>@ z0kZYfNM7>L$vrTs=rtjQC{`5j-yN=^vU3ep;EyG`0$`GA7)%!Ezo51X^p)E9 zI-D|3tGQ*F7S-^D*LWm!pzlT!NV)a*6Gj~7<%EWw=uJ9Xti|#ui z>ijB!k^6FB_fMY{Huu*#ig(xj#=LeJ`$M>EA$d!ViDNfH_d&W(^PE)sp4d!GXhq}D z<3aBZNYUH% zbcz^&sJXADon6%5PaRTtLl)6~3hIyfpq~&kT55kFuUzey?kO$3kyEQ}DQcnm=s;dW z&Oc0uhh26xcw?tN?KA8!YW>K&0Q+$&_U*mS}0(nn-(>h!WsM}}Y*N(dTO>V~uexijEj-Mjs ztqVb#1J^Wh-`+)DhH{IMma#}0Nf{|h#X@)Raxv%PzJ70M{W8RmFE5nQ>ZolCI)4~t z-sT0!oww95#Y+{TtAzLncpvm^51hGIpTA!k!QNx|8PU2M=eJcE!X1KJyT|jC9n84c zh8J&NxKEs7XrsBsj<*#_AsnfgOzV^}?3cxpzbvM`t;0j06|%1|j4&kikm+bN$1vqj zieLpGxQ$}qNvnSKqvnM{#6g~dCF#P5E~H+3C#uvYP+TN2N2Q)Sn=g;MPSb=W!78cg zLWYbGPwgS#-OgYT=;e-uOy+-b0c`p0w$^5j@ERRGye3d&L%rV~DvwslHcZwETchu% zxT6?NontWTbhvhaC*?|y`Fwi~V4EIx^jsEZofEwM=`mTn%V#tuYBMAkZ689Q6?^!T zRLflLC=nxnqT=}k!cG<_p{nIj}}lD)wBkR70ZX@0|-py zE(6N@oL_30TX}_6@_Flx)~lFPhg)^eWc7Sc$-^e@T?I~=f<*@^g@!|oVqOk^RIyis zjo1_8iRn*9U{?u}pp*q3uAL$8sA>&|C38pvQAoUad|ZU8)_PIst}{);QP^OjO^_F8 z=;p5>3QI&1+T+%kp?mqP$LG!vaQ0yYpkal9pEoxhI!`sjCv@WZ7cx9=kWlrQi}|nD zT{DAH6L*SErvzN&%a>foM>eL{dQ&$_q0K3H4j1L}az9`n^*iLMIFqen<(~>w0WP_3 zx)Lq!r^2sAj`&-&uFQ#Tzq_iQ*u*bO0B{jA>? z0)0qlCju0z)EBx-3lVP3vtjSdpn%-+s=ImRwt0ApdzWCkNfE2Uw;TD6?_apdM>4u; z_ko|QJV}(FZ{M&g5+mmUY5?5EZ*mOtUJEaY+UYf0YHvjit8|!`)0da@eC*AoLmd{)xk zYgbyVdbhvpLF6X>^1EPxG(Xodf8bAy-_EzfXd{v7O*f7ysx*pWZ0@-g^PrO&!0i;u zyvoejmKj`INa8{fg5YPOm3ywZoE&QLJ~=^Fruz~nO{MLo2Lxxq+1}s)_tJFu*^CM; zjtM5&uwE&$r?>L<5FqB0!^Ot*Y`-$UR+PjHh4>h&Ghvb zQuV_G_VRXf8`?p~Z8f(K`Xc+?ZIgYv$+H5&qebQTl%t#i#TGemqlM}tvr8?K+AoR7d7KM8`FU}9;hiJ>`^Pn40 zKAS>;%)>Q{Hc68UCEbRzhLubsFlOiE3mBTB)}5XnZczi)n5uiuPZ;E3y)ujT^XR`; zo0a#teKF`n)1P*i^G{HuL;7xG&GUw{qXDJ%V3BZt6WWYHS?KNfblc>|pIv3tTh?$T zi*I#ewyc*TT~V=WCuyix&ijc=Qr4x};EYTbfvWyl!x|g02rG9;m*=I$^OIkD%r#4<99b={0^E z6HElgwejCe9F(dOLMz5q?a3aD1f=_0cn4+&IivdG_T@W@66|!g%;U(mo3WimNFZ^JV32zzM-sAKY7<~xB zp?awnk<|aZ8rmRqC&u%bIvv&k8+{<$B(L&jL;dw;tC7;{M#+m1Rj0`WNo(W#p^6Fl zoK{gx!W1R+b-g6_r#KmXrtFBP9h~2OLHNtIj`2Q8a&1r8O%gMQR*iI$Oa`tQIbO({Mbg_XW>Nftr8g+#;T`BkcvoSb?eI|P;!hK$ zuy~YZE3QxxUsiR)!Li%ulMqupN2k}*WF+#kqsnv*HRi8!^wBUO%_KYW6wgf3hx^-O z#XWMB6>L3g?}sn$mVTGCjd8MATB*|=w`?B-0I1c^Ay=kq@-k!MVRHD1qg-W%tA@=+ zNx8{_%$(os! zgaC}pT)B~V+bFoNN65GCk0UGF3e~BGXro`Oy;YG;5k7)Qd4AV-BD{@;XYD!I^rq`3 zlT8E1>>If*p&r}lPP8c{&BGJg%i=N5jQo;MP~+v-ed`1W%iIcTcXC$%3N7GlQruwnn!;_7U|uLNVYPtplOQvH!Gd= zbg3)B`)MKxsvGKa?E@@@nLS#I6A?9{{CJao72}e34KMfZLMnr`B6v zfnSu7DFO&#gpXzqGEBt$$w>fnE^>!R6-JS$m-Q0anZiP^ zrZ0t_HgWBA+Y!X5uAK7g9q(+#UG|HKR^Ed-zKsS9PmI*mT{^u5$}IT1t0Cl^1@U>V zU$`o#){l2|B|j&nK-%o`%9ke+v1fQa`uYd!#qmHSm47_@wQ&t@Qm|XcO)b9)bLG`wfL*9jU&l{5Gb`QX z^6KJ`0NNnVbUwt1=a$DUhQhD5zMTXipg(_))V^4Zbk1ozaaE^8?lK3Y!BJzdH#3qh z^KyUg+gF-D^eM`Cs}Xk5TGB$}Tw}2!-rGO_!`RW|ZvRvP{+o|PZ(@7@dDr%qL%?=6 zM;lB3Q!@88aHTIOC*y62@}$Gd zl@E0k@XlAS9`;7o%QH4{iDI2*}ODaAEZh%$3i76$EnItopZ&*T=u~ua?dRT`Kc3K zxY36Xxm&Z}P1DOqRd&XN;4C|>PMkeV_4;=~5A@f#zCx99>{R1i$pkrw&@aUiht@=% znymEO^z4d?odFl0D8oy4-jPm!ZPiS#_ ztP2svYUE>ZHaUmSgl|y}*e|-Km4*Tcq)B$B3dMQI^I+iAnUDv7ua$-;i1^t6u{QR8HZ zjnIX4u=a>5BcjcxkC_h|w3j|-E3-3)lz+?=vntZv3J)~C`}Y1>kI5VixobwO z6Qx%S57XQlBmDiO5`fwR*AaV*WZZP8F^H47`+CKjIAtcHpMNlH6zo`%F3yN`pY|}g zaQ%8vl}T53XVCURu&0fcr0lJG#!22}a`4K)J~`c7d#-i}dgl+ZcTzGEW1`LT_jCzc zT9Toobk;dh9ey>n>bS$BqO%S5Sq&Rg=k>~b-&JPLA|5@vIDmgCZS07U3c+H+v7_+H ztB1lThotCXCJ&Y5;OEzHZJc!)jA%x2aNKGTsm2j+vMX!+dbsaVw@?i@^M2qVziN+$ zShf{3*zT|7U(8bPVxbD#X>;Oy&X44W@>0}p7&xLM5F zh-RJ`5+ULc;L8^OwqggJqb>AZp#XshOzGLEp}3|fFvAJZU@LorpInXpzN-p0c(d*H zA)#WJREA^Hhlk70odNdZI8s{r7C`ok#O+m5YiU(7xm-aIyU&M&vf?v{jcK~Ptm3GY*MW`m*ge^7%YM)rfWhi&69i+alxsbTy$f?M zP#fN{q~r%$8YdlE5Bg~p8^7^`7S4^AOY>W?Uy`Xd0TxnyK=#zm3~uRl51yOqx2t;h z!~bzYcy!6Kb3m2t%M%l$N}GmAx>II6VGMqL=IVpy$lsxP+bK&IiW4M!8UVUZl*BcF zsap`r9+DPQi#<~vJU|Lg7Ui}*A4l8Gc<2(cNw!30E^(^8lrpH7!*?7mMx+gVMWPkp z`_6CqOALJ>bBKD**l^alzAQpMbc9%S)Hq~*mUMU0if_2W%89XfEQ(b)liWtc^eu7G zzBa}iQbDN4kuD0zZ{?eH00@3M57Q zdOL2Rx>$>1tL)XUSh+;2c;_(EyHw@31Dh|>TV7V9D)I(8vo%M(Rh%zu#QTXc#t*RO zRFyOd3tSI=tu|=bZ%9HC!1gKzi%7^YQxktAaH8bBD`YJ0IVYopnL+EXY}w_crD7FR z3f%8ay~6=TD2u@a-3zgi+MH6_Iqyao0Zwl#9+Rg3_(B$>Z_ZQEw#=7R-$}UY* z6WH=y9L~b*HO^sMz0IwKc^_g->2#j;2Zp2da7rs6LeghcMm)F0b&&gQT12l`E_8Z^ zxi-SeYw6Yguy@xJDx3(j^4N9&d4WXAaHuZ_zSDIn$7C(pI}N z8zr#fRm6sqTjTl+7{^!WEVT`T@FoU)p5yp!z{|hgtp-oBAgWaUQ40GyQD(p&rXGhT zBk^5k0Ie^mqhvE{!Sfnt!VJAMT_x#6Ag41@-p#56i?`{_6Mwc8h_y@u4ACJx>pop9 zwDI0ui0STMDE-`juXdcw!0n!!t6t8wyFO68W%Cq!Gd*G|;VI`azlU|(-`+d_GF!^{ z-aC~ivresVrl+C8uN>LuMQ{P`Qw(p++gcj)#sCCiz&Bj*s9n4!>JH zCZ315T;^SzHUmPz{N*XG*I`eX@p;j%alhr;W|+x-8sW{gC}o{v6l^Z(FOJRbU`5P+ z&3eb`&4MqAMxFb*QIb^=bT1XYN9+#sXGO8sGmib-_jTAlbj)?nadJ=T3f~1~l$Gei ziq@7CB7zn&W~|0bAUw4#(IHzobnr1AnZJ0e)04@od_08y@k+UXB`@^Et+{NCxi=%F z9l;qXJKxvG-9rfG<`}`FqGIHEer7OppWmGZ>|UZN62~H$liUVd^46>wB)u<`?PotH z0R~%q8|4i9A@(%zvV4mSTUrYU{eNj89t zu~+Gx4Kb?G+>p7bn9L@KVBnkLx=*E#_rkv;38(iQ<-x!{d~5NEngIjztwoMHLau@sl_ox6pNLjEto@9o7#ofme(PzohYio>Wa|y;8nx8Fv6GN z*YUE`R4G%rj>5eGVFUb4tT0wsBCdCm8>%E;+R)R?lOjPY_3ktYAG?dEX{3CpVW0Tj zOFy)$3P}QesMK5`@<{6V`?R@d?j${=K*6}g0;6Lc;;^Q3x$SSG^f@1RMbscapPt{i zzc(P4w{*(uM|X>LzMTMD&Cg=z?0e|Ze=}l5*&FVGzfx>2vdT5moM$z`N!pA~4o)yR zPga}l`nkPrD4L`4{y0M(C%qrp8Tn(PctLp4cpqY!jjV|HRur;7KOd()N-NIxFyVHx z!xd7uMe2L)$t1k^BRwa@$zNp$fHPiL7C+50O&uXs6wYuRjywE-++}a#C8oD`i+yAR zR2zE{q-Q(9T;kr6-KO@N+gG6mqUH#IrEQ2&&$}n6g}XT zfq^jyG>AXP@cCj<-nfTYc%2uZ|K>osoFr3(%~H*A zG7(9=krg7iGPc_uJ^2CWF9Oa@FF_RZipXx&YUu?>mJ5t&@IS4z+6v?ajY! zUIosfq+=k?Z1f?{rFySc<1*-05JBk;S>L~UUe(44*^foy+T5^Ra5^1`)sCEXF zMqq}oee(S|#8~RWQ(W#vuIx4#GNF}6=|MK5 zuS7zd)#XTJXDqPLTwRmOT|QrIdw%)VSh#;zyqO^}y`pzx1~BU+1Iz5q=i}tc=pT%4 z?fs}u*f6DEBAg`Fnl~vflc?qO<1BKh_jKAg$t*Q>D8ncvJC7bybF$hAEJ4*=37k)9Yei)PKT9 zye+aQ)5Yc-Bi{L{G=bDPNg5q<^tBkqEkgK*3knL=8<8tk@1q}enIF_?5!Sp?*67In zg}G=p3Vd#9V?;)1jq7uW`>w6aEgR`<9&!exW`uh;I_zt=l2j2a6D-UgosE5^_xB$ki{>EC+q_3Hip{_#9K`>?QZ&gaaWnK?7>yyr&|Cx}`( zBlZZ68%ufqu$Cars`TT2t(stWR`O?2E55pzjzxEeRYs1Sz=qXNbv><#$!mHW270!DDUMpQDa2ALeNB9GK9+lJu4zU)cDjai zTPgacc;H7((}nqopng_brH+fHIk~_|P>|LFOc`!Z13U!1Js9q;BXZX;6aw4rYb!r%W>h|q8y8~{u5;>)-19M%1cTjF5`gn{~0sXxpA~s^V)ejZZ zjGRT8dK5V?g;NZnKGw}xA6gozj+xK}t)eYlW2=SmcCr-ds>Xb!(}b99Hx&ek4G2kX z8u?2LjcQZHl_c%!5P1ab=UZw0X#l4B$S|&YI5$BG`%FZqbWU~XdLlQ)yml*b=4&=) z*0rwpj$w+C=G)Sohpao8ZRIvZ)ZA3(neExMV|u=2M!^d~HDM`*O+t04`aTLVw;n0Z zW5qF3UwrHAK$q<*$1?In(?Xc5@AOeM-% z(`&Yh;~*sBM{C2xM_m5`*F0Y<5UzXcJg!n#U5VxD9$773r-?4J@KAa7oiF{`$5^9= z`K;S06c==3nFr!)^o_ct6dzd`kmWLekLr7GW`Qi1*Or$*w;m@Ly30z8;>e#Ir@R-DaGU zk+aY+IYv|s14Hr=%4)+z7tRL4FAv`&F)TpvDvJpa<`M^wS!iQZj++`rqq8YdRK+7p zLJFV&l@`IFjk)FIm9eBlQ3qZb$%WN;{R8nwC3Q3~|O+-#=I5b%vj2rN&)Js_G}=`8^Lc z!GOVc3h6covI_h4c5ZjAP3&I|FKvkC1Zt&`PVo-N7mf~ThgL79eK_*E5)r~cL;tx3 zDXxWPrc>b7%lyFag@Yv}c!(aeE;r}RFbK!n$s1N!5f>94L2>TfDC9X6q~R>iA_e2# zt`NGn1`WR5-dWeV(SL}xZ~uC&3s&q>6Kbi4vxJX90AFPQKUYwtdN-i}#9;Wrw=9W| z4yNVxB?{6HPL38-^g*@*{zPrp;-C?vNvyL%e!v{@=GRi-cG=>Xi#X|=l2UetMJ6oP zk1*N9Af&jdZ!YIN-_vPGEdjLv-VbkJOt$#%tJH-8Nnc}?!Yvm!3FW^f zHY?IB&=lDoLF>p?)mCa8dfG5x5YG+ZB{Fk1C67?Oas;G+7*a73PeSoL9Vrw#fc$&O zLgA=Gm{>$Lyt+Nv`A+4<6cW5w;4K;eFq|$mIew2kVC{N-dZdT)a6m1_`0ux*@h z7`bBUeJplPbZbc%S2~Kc8Qfk)LsI`U{_;_}s}gjg$hZ$FJ}eJJF6n8RQZi|Da8CGZ zci?F8l|AcJHvE(E(&4m(@@2~E=^Tru7Eg}%xpVF&mEbuMaVwF>uR%Z566#w9&Yp#P z?BHK=nUcb9G?yR-H%1EZ(O$RzLV$PqJn!NWwNJU{nOdJTt3>0#+JSMvclN6QQ#AWl zA9T&>&IZCp&U-4`&qK(APbRMtYW9OIGA~*==>}kEU&)|?Yg?5<3+139px2z3%{c?K zX9fYuwPK_h8^LT*{~4dLd{o=<>Z}iiTSeI0s>NAHzRQ!H8-tP!tbLP~cOdPGPm*2h z1h05>jMgZsDk>fkE(VZv`mq|pqU%w9LCf?U(D z3ncGZ`iy@lzrrHLwMB~*){+0Si^29lyg9+1ExQfxW2iW>=O3P zwZs5y?%ClcmhT?+8m_UEj{mBPtpC8umS3e45Y3a1itRjH-YiG07?@`Fy_tg{Qj=N7 zI4-(La}VW(+9{RM3G&JTx@rxI&P1};e)mGPZ&}dmV9CD4bD4JGo0te;Rf58ySNLB( zA2)ejp1IZv+L73euWegR3o5%OdgqpSjO)poaX4!f#bKTVxd%~3<679S&zskPuY*!q z*$x`oCF(E%rDb8|FlcU{#yiRc84ULCZ{CvAAsq8=D6;kyI7G)UHnldtw0ya@8Z`^k zFuCiFZ(2wPy-gFP6QZc$;TGb3L><`L8-mxi*#T~A`EMdjW$g%h2=GaOX5$$^^-3L} z@710}?1a6>h9B2a#&jo@ek1ZUGF(QzQ=?B*Ex7YMd~4#?pfndn^Mmqrtg(**T^Hv3 z!R+-Z9bXix3veOsadPFS7pnX3Nez=eBfs0F@VUjvRTM#djG<~e`$7fW>7<-!>+woK zS^;Oyek*KjgyVKzqW`TBW=h!8N`*o3%@IPbT&G02>Uxrbs}}LiZ!;b$tD0(oS^OHA z`VycE&@;Lj1t1Jy{t95P>3&<5_G}>?2E!mIEPkHIvd`#v z?a8-06*}wWrENEa<^^Urvsv=tdUZeZF>?RWT{5MP%puV#+hp3%y~7>Ss0if|8LuG4 zLaT2HK6r^MrKFMoyJh-{NGoGZKZegQpI{nFNQANlDy~QtQm1UHy6kAk-JRK_sUdp- z-htVU_LIQFS3;%E=#l1~bo3QYsk1~yBLe9dFEB@nrhQ^}<$&`|MBIm?Wcd+a9iYhy=)WkEkST;DIouny_Y)(-CtK*iI zh&gQxI@J2Y3l}*!iFyVSj}_Uz=KI#kGW698LFhiTJ;{0ZW~u0K;>yX4*NbCBV3m|4+kgGX`Y~`0Jxw2EJO#cf9b!sU5?33dqGu8EO;wJ!lKH#BBTtCLfzABH6Li z=k9wPs5-7>M+hfV*KTRiBr$T~n$>lZ^d#;CrlBJEm(<@D~RRf9O0+p1MgJ~(#z&_OPM|;;mg-4^-)vc zl7c6Ehpq(~D{!Y2)ICK{pSd&^m3)#w<5$_lpV+R;g`XXs1XkvHKlI2$D@nayt>n_8 z|G0rz5^%`a*~t@-kc6QK+5H)@Ydv6PztB17vwWb-=`7e+TF(Jjys5#5nEbEedypyyqKI=0w*CIkctJpCX>~ zo3nbpQ7y`mYclPN_~9!xhzuh-#1iK)M#9iC7lgj3m$S&x**oq~t>x)T9;(ie=VD~v zu%46w9D-H-CPeTG@q#}Jb6#Hr&(J{@rYCjtij?EyDCbw@E@idMead6RTlik38s-;K z$c+dAG9}+#!jM9W-eyvZP*n~{*!|qYeI-G^p^mxdZLmXzsRc!!hli)fdI~LVyKC@Rif>j`m@& z;!{K>Dq{amyttIS_$Wlpcs%Q!XP8HkR?4(LDsrqLwD1k(TDTiXssW~UdeK-HDy@F~ z{(zSW4QmVbH%b5>E%BEZLRTxe4mvezU$FXKr5f$z+Y3grjdAR0Fs?vY@|<@PCdj|F zIVfNk>w9FA{fHXra#;z^oZ7DM7-}s&4H*m^k%PbFN!>nN4x!@%aqt3LD+2oVzTcR= zl9ZM5Xn=9Y^QLqMdWt`C2L>@-j9!dzOS7bL{a8#_gkVww`Y8>TD`M5%(OT+|z%Bd#C z1}Y%m$be;5%%Jv)RHI@^MuHAc;;c! zKggtvq20RpJ?Xh==7M?fMv98n5-tAKe4rv&JyWXPH(4QbQexIbKWQ5oIBGt;X*wEU`%C+{`BA1L2X` z6=N8Hi7!DfYyEqt2PVN0@eUaBj`TE&H`l$Q1mB0A@l$f{TQf?V^30^my>5r#BYz() z-`ClkST*7qio^V%0jq28r#`aP zt-&PqIaj>hS-slxjb`W`b$lxnGh|B1Qc7xABWBSiboym2u-V^W^T79^@{45O2kiv% zz;(Mu|8S$utJWQ)Uh!*cRQ;_(7eRHQnRu^mKB47v0dNElwXJ3!XYV6m#?*TyL9GaCYiu@8%8Co;knC*M_WEh5oWuC-Tuk_%1w3+ zZ&aic93daU+HN*ZPk$VcCU!WxSK%`vq54>A^l58n+4rYnsN1rkj_`FdY-GpThoskH z;*a555DZH+rl_4zmEUdpses-EKjXrSogks)%J8^sWZTKYXb)6F?LlvObMtKxDaJJm zKui!O%q)d&-dKI9S|eCDpZ$yt(nLr6=6r&EGG(WV$wuttsT3YY$E`-Pv~ylr3mw5b zJ{k5_9uAGl5v3j1yS`%2KJ@Jife*XB~PW>$UH%2 z8yU^pc#TK~5;1KpO06~et%>=M)cqfpwZEfn6E0K(^v4X%HVCwBK|y2fm&cvb>Y4KD z_fx*Blh%B5Ldb`o`CSu6jxOfA)FwrPA#oL|^ifzy-(e&k2Qe48YsjkG?)FF`R-m~! zkk&!nr=sx;xgz6f=wb4)?9)vCo92AKh?$w0GkY%`52M$kQogdXas`MO=XxIbFnsHm z%xi+*CFJ!gq-+6T`{~kzv3c}O*1e}?Txzz6)_Vwhgs;Mi>5oWPkTj*vnYb!mT+e6X zpOC7EFWD@`pq}}s$U|att7CClu)Coli+k>BCd7SGDS9a0Vz1zlzhIbr6$!`@nJ`m% z{8a~U+lVS8mU}gl(%;LoPaW^^M-WJVZZu`qLhiZvD^4mR5Mk(a1iMM1Jhy0((iIMH z7#l;3xjPyf!k#zQKH;6>J9Jnnf%RDG5HDC#T7=y&YzRwUvd>IB{JZsj>CpS*mhQP# z^v77+$LrypPn~2*GANMuGcJ$z4*N6+33e&DO--9P+f!Eg`0$jGF<^8qwQ`@}Q8ck? zsy>}*dZ%fHThtaN%}wcA6b0BuATr9J+NfGg!lmN8vfCl+Gj4HyxViS2O09;$dkRol zonO{6l+lPgp3Z{LMqStXojO(w`MI54F7LB~9kTP>B09p=Unw}e7$4n+aSK(+Ww-m1 z`M4qH#z8}oi!?>3e3n@qGkgv)p4W{wm@8~;RQZ5z@;16KxXYzP=DEtpG0vOU?li%H zrwhBcr6DxkmH;d;g1nW`lUW?%!axq4UhVpf{ zj}6gV);qES3{*IF)m5o0Y^;12X~9wvk~~XL&_`q!(8nJ@YjeFRdwVAzom%M&>_=uS z0qb1bi|l>Vk3CB-;&tcm?`3#zu8#ZJy)G|lS`X2<&tYsR2_ej?TzLun+!iY6dsao) zQwpxy2xY!RSu!%Ei27Wa`-=Xv2!pI>$8PqAdRnnfy!+yPbbaYpPgJ+!oNm6i->|yU z6%ZaSwln8(S%j7QKh4)lDCgtgiDAkRO0H;k;nZz$BabW*8)TCP zd_^j1!FYXii13rE8XwQn=ctcBi0!1m=u;G;sc>mzgI>$bCvQ>Fd9 z-EDMTPpeY9bTjG6wZ0GXzC34<{#7bY-7g%~2Dm1EDB{JSVY%HHyKXXeAOP(4RW{l2LUn2@kl#ReJO*OWv+4xB=A`;Ui z*vja4?#{OqDG^D%)1tm4XkE_TkEqO_ob^?~H{`Lgt( zeO;aiFejZYsL#Fu9hmdQaina8mH6>e!I?heHP4>V(xHBc&&;*v-xecFg#hv({s{dO zo~jx|q`Cvu3s1peNunEysYt|wcOspUux87qSp$WY%%X|17PSge@f>AmTVl2g%!u#F z79rkFx+$QOjam}fCgu!^w3v;m=)8%6h>Z4!qr?mpllfo{@0VI3>u3I0$O$d+L8{{S z&K5b!0$>Xd6M?%U1)MxJ6hxn>G#aMDUC4~+%H-s>_|pxNin3zB^sQ)GS{m>&U#{Z8 zi^BW#;F5LaC{o|9018c=pty##{`6;E)#P1v?wwzA|Dt8ES3zQ_=t@D~x{p-S++df! z7T+#jlluhhwNVsEM$CTPiOyq8@ee;YdKtFcgkq!#>$aFX;@zNj z7n@^Q>Y3GuAK{|Z-Y(BQeonFj55m}BspAo{pyYrPvFPg}C@2xllS-~4G147LdJi;G z3&X1oE3aiGUdC|{XyL-5!Ltgb6NI=8x#zG>knhasy*7yGxFJ-fXeYQq1`oJg9|Ej3 znCEQG%Wa_oeKmNv?}9?)&c~fru(f22T+KW1HYOXu04|-cZeIx(lWp>6>Z;H3&q$5p zC%w#peWMe4&tod}rWD=MIy@f|GoG$(7}mw~vBhAFbSZomFedoIov>ryQb|8*vCw#_ zx*$oF8DN{y6NW`cWz`pm7f(wo(&?KmR5;k;2vzbp1UF9F3AzdCwtMi_@7-6Z#1o`= z{HSH_ki6tHbxN6WU7uv(clq8cU4{B^CR9|7@!&SGhHrdxSjBgVgmf6vNg-&Kzpe~Sv*yguFsl=M&>9b3TWFjI9KXTrJWwYjYr%H^S?bfV z;O*e4f}Bj134uFzNAhw=9>~3zJM!E)U-Jp1vqLD}M^*EaI*b?fJ|Rr`Qg7x<)=iUa zed1^>AR~x#ZdbSyLMZh@p`$vWo78)34evFn8Rx-EW!q7u5{dEfaG7I`M8l9y#lOys z#jowRFdkyY?(Tfcbid8PN>9`=kHlTBj}RQCxP;U9Ioz#{6u$=ex15ES%=^OyzqgK$ z;Fmu*wL3J>hiL-Z0Xdp*iPQCNin`W}kf?qRb>=jZtr2F}H>4*CPAl&(7KZYtopatg zq9r`3oqOe(U{x`rWX=!2fH0>CT<5j(3i1)t&#@Z-c&EKYYo|X@)6kJLsY~IIL%n&!PiF@K z3ujXSJ@Qlo^0!L*GA+d!NpJ69G;NG;P99zR?PmVHx3Q2|et1H&9!{m2RP^(ZQ-q1J zLaNE2<^Hf1oo84mugKl!tPGc>(tt*$3-hrN!jl-Rg|*{Gl&vI!`WnO!bkYwA98BHQ zpUlhgwm)B)g~#_E%NvZ}uNpZHndv zJ#>$6D$RwVz&29%3{=-retLS zA1PX19|n8$Wq2e!?AH&1zzRWaaR$qPMTVMOqmv7BbCa-BXa5gnhO zFJbw9>#?WS; z_>-CSWw*z{aul#58nj^yED&$Hy)`+i?K%l=b)EY0!&pm43&528eeX|U!SsrNkPyU) z7P=iYI%)(m>3H#fEwo?!8<=s32Q_+^|DIYEs$cQY=_jx2Fa24Qn=-glpHR1_b_OH~ zNC;#*Z$=TJXsTOR(CcyNoOa_>&+&0xLqo@~UfaO$nZuSAJxEwAAcEJ!8sFJ1TGPzR zJx_3$WK#)h0Q~6rFPGTw>H0mUg3-9bJ-+z<`$(Rxhh#8fXj#4|v?hr=mW9fWF=Z7Q z^{i;^?xH8fcCVGxN9Ap%r($!_x9(Vv=6XT--;c*LiO>+q!3!NhLoI9clwnUZ)(VK+x_B9ijtKij{E%=d0*T<61tP+c2^-epj=U8WF+7Z<>9{mpQLHykcWvtbh(b2-nDcm|kpZg>Vzv?!_$S~E4zKs(=t&Ls~grd_6g zW`-4oK7KP|R0$}*R{BsDNYelH^>2awY%Z`ya?{z7YQ#d*B;62&*##(xNAo{JO|$wT z`NKe*L*mU*m0#Zjz4PL*FdEIUx>B5!r%YE`AINmu9eH(IJzj%(*^`QgoGd|BPn|R$!uSxy4z~Hdm4B^dVCddt22GIa2VQgpigWI0XC6%9tETp+K;27`8?BFWmk9c`g`_97-DZyLH+biQsQ6p%N11 zFv`2&!A*<)caSnt-j+0fjG$eK0Z?%H7m95&Z`u14cXQ8kJ z%mMe$Jpq=P^KE`^N>Vucj)3WpdI*c(HCYUy(}^YTl_zB5C~eblU{Jp{gAU*^&c0{O ziSG#ejmiKmj!D;Nc4e(<{>tpyS`YN$%Ti5L0l)n3aLX(IV;rNX{raeugj`x{S-ock zEyq@(s`ZDx5HG{?FMl=8N`wd_EI4Sj3WyuTvxPDdKHw#9>k3P_`WUi$pADKplOp)% z^jg!HGKG?XU;??$yQ4c05XZgab~hcgu{By(S9jaidj21NQAEi{zH;UGMYGxQ=`Ib0 zjgU0QhSD8_F_^+>J|Q0AQIwK^n}{58!2x?|n$8XuH7-`^SrI&A`;Tg|__a_^7&F%02u!C;Y>9hQ5^Ils_d#u+{>OyvrajWEDnB@|u<4${ zKWK|3ED&9!Y0bC?GBICgb|=HEGOQ96{~eb0&`XZp9@>c$G6DkXvAph8T|y*b^n%C@7xTco8}RIMdtwkNr}5r|x* z#TpC=TbcnijPhM^sB7X7CmGESX4Z$RFCpa0X_<2}wk@9W_)DxY!0286l=x2{xglcE z`VLaamNdHuJ(QuZJ?-E4dT~sLhrLMi^1>k+v5}t84Lz#-@>dgMWyB-m`ilytz_KE} z1zw_=$96Afr%Yk|ly@ycI3_x4FdHz!A3rq(Wt1y-{=U3W+{ezwpV4vky%hvY`qdRe z8~+oqTmTK0vIC^3*>~SmCCxRHON^&lAjXef1lZIra~0eK{suc6US3;W z0^tOC0@e^d@T@St0gA$ZbDv1_0tK3G*D0^8%nl8>T$NI<(2>Sv&X5Usd}mSBDRk$x zF~`BnN&Hy!#>f8f53;Z*I6p5f`ofBjAL2SO;-juFuRP)FuWGDUMv6}<vrv<|RULx+%qU~_D*gJ6* zpbb(0`Y`LB@pvTQVPH07j|@LgdGHw;+nM#O6nvlI^7{$V*RR>9rQS87@dqE5AF=+k zYu96tG3#t?ZRE;{iA$<#JO(6$T7s8o%3hO%eIs3oFWX=@QrP+O!%a&=Lz2C=78*HM zSx~K9G)ek!)XKrnmeFx@-(Nhd%+La_M7(C2)$+?_b&()pzAs<{;@O><7Ku=Ef8&Ry z(pI`WHANnK_wkFOl4|dwMOn&NScm3C_Qx^tTz~W>qKBZDmQprgu!Xn#<`4bvPI_Mo zhd$Z8$VWSGxBuO8^Vja+AwVEu-{W{UHaG&1OK~kO6T=E7sYfH$pjB^(W1D!dGQ2G! z+Ozmo>0p=onsdgLYxc8fV#~V0V|m?Ws;vBfX4wWSHEwN9vvZ`Nl6~sKRkJEZb&FifnC2^) zTPQsP6*Eo{aWJD3aKFX!Bl(Y^7nQFwYfaoI63J|A&NKGC8%CajB@V}J4~y-m1?IE1 zRETTpOd0EP416is6(Xnqm(jZm+4{Ae!N_Nd(%jRtA%NkmVy-xE94E_W@kjI)#iwBD zwlO(A`BKP2j7NT;>0x8h*R+07F8a+Dnf(U8?XCxY???a0%DoJWl?Ime( z-Th#_HoJ+iyMr2W{agGBd8Xi=d#YDFTb$t8{w%LTOMZ4JxN%iBnMqIbu>I6!R|$Wd zx#JeF((K9nv*-Ed1^T z{4T_Qul3Kc?kn;)g6H6-Q$=mvqJ|puj~H?qOp2OjOJ!p37!KW6_c#XR7)LGE&q_Gl z_iSaGy_D<}WM7xVE=UMMsJCT-1+(0ZL)4c4oMD)O@5c-ej|>u`^c8Uu;x*Y=>2dWl z((>>z|;k!8TV#{XBy!Ifg{t#~?d$?zfP#5Kv?op6ikA^Mo}s`< zIUYq9lLVuFwo^u4>N*`rUadT2e!6p}ri$WzPV_{Tn`>B`3Ow@Rv>5ies`$Uj0@+7C$la80r8H&I2XYBE=wLMvR^@ zCR4C=OKI81v5hHx6C4-G3!Z`5>E(=|F|gF9^YglnI>(q`K-|qL4K9|{%4VR2Mb33e z$75MSx2SLGL)5=q?2SaW2=PEvW+sQdDZ{8hMog%L-(J80;rF${&gsl)k))m$o>K*I zU23mRk!@wtBTZTu{EW)C$_}x(1}^5rZB+e7`Ko%MvrkMA z!4`!YKV{);$oiC0Z*+m^R*~Y=-I-$L2U!&h&^juEO&?isbKnA9ACo{9Wk4@4t6;plx zjfG*MeT?eF;3)6RE-wnn)-Wryw@yuaxMrPpn3R2+MmNU5T#wvL%BQhO{!~R+%5GXfMZXIbyQ@uX9Z;vxFRP_nW=Z~JHChIhF(1O0n0Tdj^Wg+kqEZ=%3797c!afdP`mr z-&+Z}rynGO-wd%4Vcrl`n=Xg0g&!EIVR7Gk~4q!Mjh{ne`19DUbUhs;8dnnh9 zX0YKpJY|b!7H3HSAs>P`EpjHWwdhKjwX#Cd*eaz^ZKP3ERs0eVo{|uJPXZ?Ej=M{KTlT zo3*vmlrPtXclY-ampoL7>p7oP%qf>BM4%IbRpIB|T~3F!2Dy#V>F8PRYZ#?hf@=i` zCl;o43PBTGD0?1dLtPZxZp}Yxf{!nPB_F}T&V%6li{qj+jHb9%pS?(y6PE1Dg>C)9 z(7_ThenQfJuU|3<7q;zEq~ze8DSb#rXtWI=b7 zvgN9P(4s;}6ca7hn+92c%3Lf}LEKo9p~O=XEGfO32j2uJCj>Z))2?1ju z5(;~;>-0Bt=9jrs4eh!5GlXy*Mzu~(&<%N^XoeftRUh_thlBd*>G>B^76NWOdUna* zPXEa?`ccS}aW8x;Bw~ABJ9kyqove9&B>A*DEr5N%vf5 zm(>M<6PD6CNQ~cT1N7s{x&J))^FRl<;_NN!6e2Wp z0%0HDVx55{``W&#_oe@`6%ORWk6P>71xRkZ)>_Z+qn^X{PA=biUB96s zd3w3(y^5Gq97I$EG6_@xtE<)YUb9GU}AC zF!UbOGVjds@cq+R_J;{q=n^JQG^cBt4OdaLYn7_9x6^J2Bwm}it=SNiEjJl4UVo^3 zrd2Gbwew(h*q%i=T+7fYgX&MYBak|1?2)BeQCiy4;yE%Fl|NH4JJ8!F{rr0BtW@;5 zmK19%!9ni`=(4VSXh`}{Ab$1Z^UM;b@3{KwaK@&rXz`Txoj3!C{QUfp5ciYUiWpGhU<~M*YUXD5(;r_sxYTsMd8pB(K^&pBSybRc0*s~trg(<_bDQT zN3pU)s0ktmal+g%6Lk4~fl;zRNWh~tPhNKI+J0L^Q-psW8=I!FhOTvoC3f&lQJ8C( za?2(UD@M_aqb4r(>yMQq^2dBb7ivs{P%VUG_p0*5O1*D&4AUapBuv5XT>n|QUvKsk z9vNv<57F}NDP(K}0v6#*@#d0x0R*k0W$~q0dn%~T48RqrMb#!c9vt=&Q5CjntJSZ` zAmRCGQFjr3sMgTwc=(dG%F+h<(k4qH_~E|y$)IU%O;erD9@74gzlX~1L+1G$X=hSD z!`UD1EUk><5;g_^Ei3@q)}MaoHMe`415}9Ec)~+BV#xM_iSK)})AI3YW5wLoUxNNM z-Cu9q*x_C#B)s9Z4tN_2R2D8)esN&$)4bmMsrm_$lTMD*X5AydG1FrK=ivIZIPNS2 z&qhmoD-v;v4mqj#zVtFS053u^FR1y10zg?wyY55|r79SQ& z&0wP!nA#l+gNtWkU@XKD{1;NkT>#^Nt#hu_)qD!!c;umpKNPYTPJ)e4OT90dOH5D~&Sa5%@5SdItRauyaAvEjI5 zgM--pm^&t$OY}mL@P`Y(Hq22q63c;xt>)$j-U2oCx8&%bc<*z*X4q_<-j%}>Q*m%} z=9GLSQX_cPJ-8;S9=fx-MmP4wD_`s?8tv~@`1OzeS`rp`(vU}DbA2e>;CF-!Z8^4l zpm{@9lrUwTjBqpxt^y}?@U&Ap=3c_09!|Id$E-7ukE!EMn9r(|6`u1=7Xm*gi0we( zj|EY%LckmN^wq)nt3_bQ_VU7%{=YiDC?gC{w)o^6|$}gwH2qGGBHHr5XT1JrXQ&{UGqurz&e=+mGda2n3(%N z=I3xAEL-)42oYU3&spHcZ;or_3IALIF9i5D)|R%KS8KZMRHOD^Q`7hvl9@7+WvS>J zZP#M?;U#`PIBfeVbRtY6Bck)nd?Yg4CdT}x(AxtM!8t`Bc5QGN7x@}HDADreTi913 z>NW>|V&=ZjCNaIBN@&K0mR9xaS^BZcwW)U!w*OuEzr^7A=KWjRNV-YdaAz3Qjf12D z^FU#y2QgQ@uPr_O$qQM41h__{|5Nv>VeoO~Pjz$&{waju((;)r2Y=bTyp-wXO zjt3FZ@^Ur++p8?Sj$$Cc>!HxZP&7uHls5S9&9jdUub16JnTHE?bBIdE#e^2e^oP2i zIi*E>^J5{$$9wBAW(pT7C0JyHP6CWkwl!3Jxs$N%PA+d?b20trnEyDVh^|ab`*+05 z)5lYmuEe<1%Ee-LXn}w$;T!rbJQQ^^GIs!dTIyq?q(W23DmAyeD=S34_p0tKKL?u zi#Ip)eS>n=zV&j13}csLwXfBQL!4^d>pp(0V;FN_t;OEw`4Xi$@O`DZo{&CdfB1a9ELHvqmP5sv&oWIFd%GjX0 z&%g_2EKAXN*0fDV2*r+kaeP$kWxbdA*dai^jc z-NZiHSf4`%c{!lI<=49PZ)#bF4|ibu`c(&rQjpTT&!bIeULE5mlVp+@=$ zf3AYxV+k^}esC}bsf?LKu-EYdHJhLyRWh?)%-Y?twv_OI(Lcsp5Z%x5YZc8$!vcLp zkn)!d<&2`kCm(oy7A*bHiJfTr3_n&g3@t2vl_my}^&Lm?nskr#^ZG1>{b{U!MG=0N zM)nZ^_FzVYPk@fQMC^kf8du&I0 zIhK$?{p>Ss|7%RJRg~-JFKl`twa!D{*#SWN7hrp`wkuY@C=~aYlzbzgW=79;_xXa; zpDXpR#kfg-WVBD!(CM$x-@3Px5XhpJ-&2Cx=fJ|`QfLJfJj^f~KB%Obc5tXk58h^Y zzp#d6efU$+;9x<-{-Zd?cYj)dst2T_LR*fP@i5ej3?)`<$zYG;_kD}der(5^?*hxq z^)b#5V9q59*i0_4;kFQTQA=|rgQdhq7N*5i-It+4Jt zt8R@A{uH3xH(=6@zOh|n-ana%xZP^tX^F7p+A9r`(M95MxkFGpEtVQv9`7Yw?y+P48oPZRsms7W%6?1|Gaa}{gC zeC00C!^32l>n^D>yWSiT5#(5M{kig8p4j%tq74lmk-|lkLk`2%&f_I6V>vR7GI+MO z0EehfwWIPft}DVw*;nzQGyWMTR@fRHmxJ{^OM^{#tL&+E78C?NS9BEd<$ZU*?w&&W=K6kpc%BP=l9a_Qj=Z zpmpCq{~xBlIXuqpi#E1xn~gKE(YR@B+Y{St&@^h?uu0Wa&3mv(aZg2V&zW?%%N@xaQ3rXbQ+%Qc=`|#3AZ=Xe}kn$W9~2PlZe)T_cviw zn?WgJ`IyA#Y6>1$$Ce`{p^5JF3#@%?5Gz?KL+Y%7eOWjjKiU2=nJvtR9n(Fi**y`D z-h;>eCjp<*LcXw?ohB>O(LyJon&m^q5?MfS`TQV;`oV0dc6$5-UHAzWA0qXXDGBPm?#`|);O1t2G zDnbNzhADADmVphTgqwzeEkkQ<;JiuPrxRsEs~Me=mfMtscDv9oq<`wi3k5KQUnoq8 z{1?Sr5LkI)^vUn#O&ttotogo3reGv5!Xi*k?U-uCmwta0PNrTx$91IG$9&0q0&=CL zj(-B}nw8gP#FR@;Hj>w5@W@kSPYm@AsuY%&tBXAEa<14Yy%)ku6E%1=e8~9=-d*BU zTPxa>kV7%T9|?RZ(Xd0R_EPY-oe9k`Gbqe^s`>ZaCdx^0)~7(h8a;{xsmxC=8NE>mM=5f4A4K7m9ODB@Ir`>EZL}kP+&1pz%lhL z7AD4JC>(V^>#mRy2e;6PX=T^+M(%D~piQu{2z;<~^_DNJ z!;&R4brEKq9kr{)QFuR*<$e4l=m;NpiBN4k05}%QlFUcjc8zgwD^PxCd0*2MTZ8<0 zmRH-bRGlTv ziTyGaXHc6>o_z0zOy-050;ue5Uqu`Nc+!h3b(}kGEEnVtncxCZ%mFhmXu4m5L%x6K zSZstU0-6+=rzS-)R!%RH+Z{M;>CO@+0srp_U*A*AEzrrTWF_9@27K$uj;2nYnH^lv zoR|3Z>I0MV+;4a5Y!@p6*D7FMQKEo`3LJg$(J$8eR$Gmi3|v_0()v)RC1dP_Sbg3P z28aoPr>`!8$kt_9PR&hmC4^@96l0@!wJS)mZ2BGR^_i)p_V;%P4kzFpNFoJAw*`o@ z8oyiqUnSNhh+*90107FO&gJ%bL#*|?e&upGb+su}Yk@3LZ}v%@=dtV%gWnFlM}-qe=AW{uYdr#!BfFZuO!CXmHFngo?dlG#EQVQ2e(X~B?8#9 zH!@sjwP*Bl|68+IIVW*KuFx`moLo-Nt}gE09kE}CS{SqW*3>YEr9!T8|Jvm(%E1=q zjt|m(+N6~kcYjKw)Nf|D{5+BST`Fj(Oz*ij-Ofk)XzJn6#RopkKtgwgyrC8&&^p%dC&bHI5&oAqz)pxB@ zA7(WF<>DhceXU6fS+f75X?RZgT!CDqhA%A#ngQ@*dMIFJW+WC^wrKm~UrlZ-3xk1d zG0p4c{Zv%AC8Nt;gAp)Y_`TA=+!!SsB`W-|FEoAVZ*6G&1Cd*N%=O_=?NRIZ>~98o z%I%*G9>OS%i$urgUq)qRC@~m@Zi;w@sYR;)FvwQyt<40wmZMU!!RDh=&?|0L0upSL z`#X0RfSKC`@FW|2XWPxW)u4#YAG(S0hi*>QP5#HYm+oN<<=L_|uauc`N(;goL^%?# z!UPN5o%Oep*&iQ>E~1|J9CUkOK76ki@_NvQdwSj-J5qNgN?o%razEI3B@(d}b+4kAq5#e&wLbBIja_@x}u^A;;fIg`Ik2rRz{ zP+>k^<8KZXv5Tbb??1Ki^!Ef!Z?FLXycA$O{WkoIEE{#T0&^)B<~n$a&A0gN*u2hHBb1%$stffM|;QAi}`dd*J|T#1Pm7x!B1`Pk+7-{{zD_% zR0v0Y%Q`G0U73Ch|J7^GF1z?&?6 zEtO`8ddhs8PA}Y2v;dDgI8?j~(FH80+*f-3Sof_OPr=^)0v7R3nmg|7?KBimVH33b z`9RGIE@-g)8@#PAZ7fqiFW{2>v##l?-%4h;h|Ze-H%0VNnU8H!_-QP75-f9b%b~J- zruj4hBP@6;Dx2!7_|&TGFkY1#i<|65zaMku?HE3?N4B52@Jjl<11vGKr!LYqCN+wV zu70S^XiyFc#BSps6g;thF8{_aD=omZlJ6WTK`P{oDw(fLw&<1FPer^4H9C0C=2(&! z8P5Mt$AwP;QxLS{jJntVbmU8F7+%U1`6^jjI|*3Y`K6U&Wub7XkJ(-UFuCmp)G(YG zaY6x4ice2ZyR)PCdrNa)Sn{!+;iQDy)&(f%Oi8(aCb!y{zaQDGi-#WrqSlnG;?zj)(HnW8j=t6Igbq>npquc zQyB14@3`Zy*1@LQh3>%$vf+0TbRJghgalMO!}5ycl*oYvd4f&Bnt0FInx%HjP5}>N znY=3Sek!R_=_GCYw?K28!BAzG+st-x-u4WTA3gG}>p5CXp>hPCWoWSEn>~LAqoDm7 z&5w2g_#cO{u(Fp6s$}O^_wqoIX9vZ&CdRqVyRAk66Z71*N%)H1(?5KjY(k?sO{`xH z8?vn1!t$M`BBk%U3d!2~vQ2XDbK>I=|G(cwf_!7^OVwh*W6D$8U^2C2Sk{2o@ z4B$~;nNwc7aFqem8l^!&lHoK&s!o%^<@+r?$}jxs_vZ`QtuyHKInzm)0MGsUihQP3 zU7Pu*<))ogB`BOl(0c(z9gawI1IdP1WeyH4#u1k)K{lf%jl3N!cbo&9EZ=y#^Q`3f zz)AXxwR)D3s~gW7ki+`F-CDhg*cFV*7d&&-7qB^<&=QE6&kLRkJY@fm$Bi6d;Fb$A zeXGhL1Gv7VLn2}vo}egbflzBcj;*}HfR<)oRf4YkbxL;(+`lGbJ39(|W$xm93Cx{b zcSdX8yVC;BBMv;W)HAm3od+T{M*jK9;B{)SEV6E9XZPP$sJ4PRe4i-qxV3+AI52jVG@;` zBHnUKGNUpXV#q6q?hQ@yrA6`|mi-=4eJx?`5Fx|vhmiS$<8xE>-3gxIN!%aS`hQOV zWV3;Zv1TU9`2;7=UYkwb-|DIe2QQM79a{e+=?*IJr1-lF*jxQ4c=!=O;hYyv@eU1W zLVcM~ani7tA0Ini~6>4C{VH(#B^1mM6+JU-9> zYnuXI77`uXQ*QD~8cdYjnMKqh%K*50s)_21V^?@f7UJ>v`_9Kwf_jT~|5s%>&4O@( zD>8N7tPzyZ%j0Q`P@Tf~9D?Z8SY1O1UOX_TX>6=k%;vB0CFbw4J3qHhb}sD)NAv^9 z!blYtewRLEw)@wZN#d)o&5#Ebz4{Q>@Lx&tv?H%t?YvXQTTMwe-^ysFrX{jn$BdXO zPWk^nZ0ny*(W%C zjgmZnqzi&z0ji*`vP7=u^|J~7RVyCuW!fnZ`(qO_JsV-)D+##sTRY~;0(Dt)8*k~V zO;8bHw2!gzpqDeEs`hNmE}Jy}8P4HhLFKQko0S!b9vHycQl{S5pS9|b*4=h=`kCkqd&v z@kLo(ih%Ipo4uZwdBt+BtS3v;waFH6(Z|D2Gxu=p2*_Vbxub!2-l;72b(zUg(`x(SjDv2@b4)xD_e( zaofpq&E#LswDIYWNckz#A6!xWVHI&*BJ^D`h}f6*o}al*P+PT$Zxw<oOUS6X67j?>~uA04sssw2+%Q=qavqTEK%1nm9iLy*QSS@c{d#f#do4=8Go zYvS)R(N7tY9W(4Td3is8dxhNLsm}JugR)3J7&nIZZmL`Np&J)L-R=No>f z`K~whU%xDP{f}_IzGr90_jeCKQdiT%_&GPy6K`G+OK&5nods+vtacjEb!qBO8Yzyx z=0{#1?J2na8p6~GLY}N#_4M=}ZG6(D>9TE99g224{8A7Puy+bSAkEqabBfdt3d{&V zhOwV^xQG1kq?$vp@V`^7t_+G0tQ>?X#u#IOpNWZ;vqDp&X=6YG)hD1hsag4z!>QUv4Uhbi|C$}sa$=F3oCdlGatYBCkmXM z!Cml!tt{qM_5U`5lXMVYfP+14SJwh;lip?>;8r>ayctA%sHl5;y-|S zwT_X)NY987t1T-DtN2OJ&Q=CSV%^?LkRo}k^vtZReA95=V3jR_bV0**oDZ$yw?VMk zz5>yJyEw$h#gh1>jV<3=<2}b2RkI}FvxDR!Uk}eN{CRYI9sX(Px5`}s#7)29tXa(Y zVwxh&+`y2y!~+F{vk_-DCe}mb-f?nm7(HGnvRAIe%DWqAXlH6UR-Gy`&8|(3e?Gfw zR3b;65^?{qP@oltCd_*r3K7nWv-7Z^iE}&!i2R{Z zsE%{MFCOnUVq@!}?%*Ci$xA8Y({r~||8ms;Px)pzg3snV}T4z4*rSkd zj=*E<7X-(67}&)zy`U-A@;x-ZuC{8?&1~?0tNh>I|5uabEg*3BxWrJA9u&@&0$^F6 zx?gN-;>+3XRUy$<18twngIdv$C)@bx53AJe#!kKd_pQ(1=V9_*V*W3L|D`o*jM)C& zw@_J5A$|tvSAW;zK13aT{Rp@B6%%qK6}=V~x_Wx03{x&4S$FZPK) z2yS!2gUG(6jkjhZzzEyU4Q^}Josn0Nk3H2+5O zcOw7S!f22U0wA)_*)TPBe9$7@C0OE}Xgvbia9jlWNkV=j*~d=jS}JTsTQO~2ShA>z zkMY>5Hj4;pxNona=KKRnr(xiy@{kz*16jtKm_rUU=4Z>)4ap?@-e?}lt&ayN_zTX~ zQ4>OGzn;o;weFO&6Yo02m&XohYThvq@4@g0~>!Obm?#Bcso*k@@ZXX~KD84YTKO2cbpiU!Ir9#SHPx=^p7-1Yv5h$j~)*h_+(?&wE;vRId4#omM*mWdtmW# zsnb*1j--t=2RyzDS&Gc4;g?U$+QZC8f$P{klEw^v<3Z)daf?Yw5s&2s(Wh-B?mahMEGW~X2Di)AWk?F z2K!4=Bo7bmluVj?c_E+)4emYE6x3FOXu!$&BGbR3h!pH|if{wdjWEiotL?1oHoO;+ zGO@^o*?vvU3E@b2u7gtb@vxq+Kmpp5X>+x#9T^RZi3KzG2c@a3Lo$F zC8@03@F@CEP`&d~?>qb-B+e&UQt?Yv;TO4SgO#tmsk41+g5QJvG^!$}G3lbONk6Dy(pFJ8?F{oxfa zjE&ITPz~}yDOidGcs~L>Zz*mt4k|>N(Ie9d`UEMDNXXI_;@J*HLPu0vPE^BYdAQ4l z71jy$Q@EB}oKJkC{K(|c_)s&193)+nQxb7}%y&5CxvrYY7MW&+phoiD(kLMWbUz+n z9GjdSjqD(E)p{MY(Ck}%OzVwN6~J=Y{U9&T#wv$|TPQS$0+eA3fJ@7)oGoMdg8)L@Bg<|bwTU=!@d^r}%7Q3n7k=zLIakt)xNObsdSl8O9 z${CnUQ2H|!;xblbd?-uB+oC6@#CcH{)kP-z3Zlw8#ICwcaPMIjZyP5G$$tp@GEnw8 zM+QC}%s{DCp=uuR4Oy#1`T=-oFhPkO`YJ;yRA6{>y<*iup zYA-&40p(VlA~xOUts9z9$Q34Jt}(%5${RuN!myRD^C`1)ns=y#-7rM^AWfIz`tXhw z_tx+J#K`Xa%If#akD>-;(%&L0h|7DZJUx}gxFI@dEt?e*QoZ6X=r^dqLmM+Ra=M3C zjG-w&TW70!m1ypu6A1g9TOtl@M17$M7o6y-7Vo6D_ukXB!YB1rlfrRyNQDHQ8;A&1 zOo(tX+i~W4i{`Usduk&LzdF{0s0kd{fYC!?%7@|X&v zz#ImY1HN`SDn;t<*hFx z`}Nnqk|m*CT|u%~gft&i{cU>@PVu2|JQYS{G=sI9 z*R2aJK^T7V!7Q}K`VfAwG`gaZC3!$X*A-G(@i7njfJC#7XM4cZdFp~LSsCBJO<#f8 zeVh?2%5Lvd_Y2ww;sPfbg-hh%`2a^<|GAvd=pY9mmmgXh=TW=QfZMT7;A@nnNLA7I zG0!#(XCXb#S8^#fyh|Ocf!&1sE@=I91#DG47d+k{>g#|P5q$@isx%zzTw1@kww3s= z57#R^*Q5tpZ9udM3E5fTwOcZn?YGp@IQ?UnS{aDwMcnYA?aURV2S zJ+u51_EglrHoZJHgiAgf2S?3XhL%H7pf(jWH2EILNW`B>i()Fes%m8JyZZIK(Q8Va zqT*qrVCz*AKiF^ZdQ85zkitB}$Ip-!@H8*G%)UBwj+Hk%vF4-rw$s$KH23}nYfLRn zO^$nE5jKB3>em*ZZy`Kv6ev}GzgkGwHYGM{>B$y*+a@j0cq14c4;mm#y7(4DMY(^i zm$+dau~ppO0BcIdkEpdL=y7lDaQ3gTRgDF^%hY47=HrJEz*l?dBk^ujI*@-nyo$j; z@T!hUs;rYpa+D?LhHzL1bfVs@v^)bv($=*NBINd}Vmy1C(*Q5CqLRK9khsqB^cn(0S57`iJL*Oo)>AaK5@f-yY*?Q+ECA=yd$8!}wL) zGyog7&|jT?3hE4JY1#lD7q!3JR*$a84P-J}$Yl_34Z9gd+_{RH10P`Mgiyz68X5YW zmn%ud1A1Nb&l+sXd@*cV59Q4DxPs0$`B+nLlX7IsNj-W69L{D)881(#hi=tvTrkBw zo~6w)Di;!FC;_qExk0A{C*%qx|Iw5EtR=wSS2)bc&n#@L^DkFiI=B-3Ccg5C>Nv+@ z)w9#nkip8@E0@0g3z|$5;@=d?=PvoUA6j&?B%O5-9`upR-Eog#*4bGyy0se1y?%l5@S+U~ta{T*qR&K*2;<1Rh%2ZY~yqN`{vIQ`R~ zGvf0|okK{QFEa#As@L5v-QxHNJ15>QW$Twid|8laO}Qqg&{|}}g;uN9EIY6vTQ1(A z5lJAUZt&}G4vl<3N%<|5PXHt{kTQ`Zn!Quy(zS6P3Y}^x zK1W9_6#&Pv@TcwupNm|!v&Tu4+j7O2N@rs8k&XKTAsKmEevNClxs?`Jjmh|e5GG_d zI(of5O%3orstv>Vy;4du6{^39k!7pv^4iOs!muJWUOABXyxI{|TtdwPtt}#z&(3DG zq--0&3U{Tj=kr)bJbF#U9O3Tz%hSDUyh=ecnV7Q`Yu@`Ma#5yt9rGvwD2KFJBn?`l zoyq8WMzs#q7%MXK2kdsMg9`1;!CqhwP=~_q)?w`CI?sztpuate_b}SgnRTe3VXly# zzRM%RF3VAEufJ{gTY}i-ETkIRj}eeC*(lM9(_^>8hptsL7Yz7tA-{D<`VRA!nQ;0z z{X;qSg+Ys&H<*nQg+x)0&IvvxNo(1Sh}YpfRBa;f)P+}XZ2uAeDAOG?n z|0H~7*PW*X`W?se2Dl1VwSuvx?eMxya0X_GV}SC9r+Gixqh$%P8|)<05-H|%yv#a% zB$#pA1^presQDzQFc5e@t~*hR4VRY|npsQjI~kIsH zY3qFGM#rvWMtAJ~+NJ`hoV|Fb7f|9YRFgJI`OwU4!vB2f6^iJH8h2nc@>D0gQf7yZ zXfFUWJzng)jj$kks8xg}32a%`HdN)y?=UN2x=W)XS}81{P~7ggQzT>dPbHK`N?6Dh zUGSf@`Y?lnsR8m7Ye83GL~p@)6jwvjadi&-I-k?X2~c8N-;t%^eO2sN|DnAXw1bM4 za{}f74X9ck&LcL{tOJx4pZKY4;PIk_aH=4qgw9;OmCx$w7 z=_4=2wvLL01x!GLqGQ4>a3s0kRm|`LB#duZueY7~U zFbhvVtFYqg^)}!+6XVg>u1-%I&u@i#&czZz(EiYDm^=IP3tO(eNn5b?Cq5Yl%luh- zGm3$rvnaI}Ikt)6>)zEBx(t^!y6tZF7=2ZtDU=e`i4zg-@O0XW8$zubg5WC%v+Rum z`i6cjHHRIo@|yXlU+U509aA2yanOwE(Q)LONuN9&Sp6YXK%HuS5zl>i6GChQDL|)6 zvbY1tNIRbef3q{trOS5B{|Z-on*^+k9FzK0YF2a62{3BXohCaK7M z^fhW#D2FkMqHeWluN8YaGV4wmn0OK87ATo=ZCWH@sx=-N&PO z*sy#Fk+Z_(qe9lrFcPx$Bb@~;4?ONvlFlq*&Mfqz?=RRA#*+T!ym=uIv1GH>(QPjz zfMzcVJ=<{Vq!Ctpx6&TOR9F^&=%JEtUi2LuY&YyyVe!I) z6FIM{te${Gj15WFSG0POojQ*DFvjXFWaXa0M5B` zW$u*#q?(=K~%UY$`YhoKXb57nlJ49LG0YvD%!-dx#K^sxAm0)i?Q)nUvp74-Q0j3^?nwm zV2_h4BwzzfRb2RAc^&unjQo9w&H)EX6Fcm?Vnlx=eeq!kY6W%r=6d|IlN1dg3q zz5N1pvL5_wl&XYsQunm6Lb9S>GIO`cV6GWS)*1Ys`j-nhdDiFyLBI8j(-vu=#3x}Z zF2?wE?M(qOeo++Y@x;~*x7GpDRl=FyG2o6y%HDoHKI|Tb=?e)l)s?I5xmoAIQx#Un zeBw>op-Wq3$KPF12eE%mEQ!f$|J&0cA^GEe<3AYra}FVR5yR{0WyBuvQV|C@c=ahIS?D#gbGFeNTZG- zjguJ6wlpmvjrU@;A)OK<*|$rXY!vQpzi$#K1k^pmY^mT zJ^RW|FQ&6lVkS1sib-@bbnJD%Tq-)cTD?Av(%SaLk=;@fM8w&`N`xaEp%o)XTpJRa5x8n(!5WCNWKgcDktUz50< zY?$FpAgXI>8QkQy==ZI{pNkvM_&c~KP_g&wBgvaDo3Vu`tw*We#Y$95mfvgfPbwx_ zB_n#iJpgEOGFT2CPenaiXtsYUL1>m=6L=dQE=d~7BUCITb{$-M^ezWd6PEIgzSFgK zDa5oMq@4RsW?#_Ik)#Hx;;9#_`Tc89$=A>A8+K5@5U{=)j)IOp+<$Yh%TRW`zrVjX zom}GEZuetdd+t`&S&8??J`&;mon9l%OslSE{jJ@1lMAsD)Wu=A{UJ9V!Q$feitDzhyC|mc6xoHz;xOML)+Oo^Xd21K!0qF7UFriapdn8TrS@ z!vf|$(Kvkki{}Fc`AAA=BsJ!m=4= z3P13!yZakDp7v$BPPK%~XSWSRHe9dxSBqFnGEX!P46{Wcf@?V39c3ioSB&!8g3Cf( zwmyP{I0DhS6mBzy0Sz6$oVB6cEBu}5?mGM;`No(iDBlmWDw3r^D$Q5Rpe@KxmK z8+BZ#yNM#U5_@^I054T&Tg~_|F6@uO-?%V18?L=vP#1kM9Nq8FinBR`+%2jTXJ5%Lem)W?$s#kKPBcFhCa4mkAPnUJ-cl|(^~0&t&t zaigBaAXSOA;WJ$PaRl~U#x_L zbMBUJ`}Z?E96I1$84UI38m1Pp55SYIXB_h_sI*~4O@nyDw`lCxmrHu37_=VPNGQC< zBU4T{NHk%byI*1ml4{7|!WB{GJm%0L5g1IYdaBD0W(A1f@HAyyoypVlEGc?nJiK$? z6_{50bOC0;e|p&8x~@Po0KJBiISp-V$GT%ChK9lvI$RC53gm74 zn_ke_-)zXsF5s6q^4nn|^ZI5;!W7y$fiNgrczrZCNNX;KAGiZwV>G|tk&2c_A1+KF zNJ(TfE#=Qn#cuu%UFoRnsV7yIHu1~B&C~s^Yp(f}ielP2M?WLo*m&_# z{zeVZ#qLx=tG}_Fw2@Hma1m_f!aOmGkQ(n7F>FU*HCBWfv_nm!f^OXh3sfkwcsiII zlsHdc=iGEvbhzP6>-z=`!}?WU(-ToS7}FY%kl!yUnTSXW05rdF^gZPzCKfCRSaV{?o+!Dtu;SDgNf z#EzgqzqNkYW&w*7*U53qO6ipry)OD}WrQ>y3)4`aS=8bdzuR$0%kZuX=_D0w%mpDd zhvgL%*??arsQE)ss5KcM*3muyxc_;;1^BV(9c?^38^a00E4>UZF!`3>{>9%cbg534c(-$xilRR+{Pf^QGkah?Wg?Tm+TQ$@@{ z)L)zRd(HJ{`Q@?}(RVz^q@HiiL7^j+Mf^+9%_dBvg-2y zZI#sfex?DzLUvY+E>pj}*8wzTS_?A4H zQo_Cmn`L!)cU`BhJ_AjOnC-0`k2Z3Ke{=m<16Ei-MuBeI&bx2p>m{`i!6<3Z!&j0R z*}wu=&61bB@SW?<*B#Ffr6VODfVDWAi6`3lKiWI^IpHYZ%QX!Oo9dP7IhUCPPt^oF zf@!fHWnXoqkKo?^jZV9zO|q#Y)OX!|W^G_!8$9_uHTX?3=j5UwCJ#34LCzm4fO|qqpHm;M^jp0_SS4><)l4xVI+1t zMD-M?bblVik{0I32UOua0q-CCUw@m7@tZ(P>gnD&{$8--^H+sT0i2{CaQs zGYsf!30XDh4M2?~Kd08YUK29V);K8GIyn8Gi<1NeY7eEWd&y{3;jcXc56V7}`}QWV z%9K!(32*CA!tS=D^G&aELO-nk{%7vna_Z#k5(*ulRc%^sFdcy41#(;|t&>hx*!CFV z)OUnIduKw!=}VVjmQtE0C6U(im5xR><4a`~|B_?t>ELP{MapX7D02DxP4_~I7?YXw z32vN%IRB@V7+VI9{8=RgdxnqshY`_Mxm^LPXD+XbRkO{-sJI!u2cpSj+GBj%pbV7a z%9qo5QEOaVl5^o~W7!igR})hq_#`X?|MbIRu?XDa7nX8af75nkhcb!knWFST^p*ZP zffU61X=EcgauTnbUgWn-^3kX9${ExR z*pIVSdANk-YR&AGXP6+YA{Xqf)Q)0=<0+K@$b4;brjV}`NP^$0#BgF9=)JC=byd{+ z7K}sTbB(KK!g#CaLwQ>nVY*24KhIN-E1{MmEE6f7NRV&kO1@^h;=NX^Qfy!C+}lm= zoo5AFs8d&`Kscq2k4=oc!lUn%vv(#^Cr4VCxX1^90?bx-Cl|mk^Fk{}Sv5XUR8v;X z!v>$4?7fg229zA8_ildr%nyIERHe%i`WwDoFFqHJ6nI#g-1|FWgK;p{EnRN@;DMD{ zyJ2BMxscW3pL}p34uLz1G4P8-q7j)MX2C^$X526~4;lwsFq;Pz#yL^NfhTMhS( zD{C%OIEcijn92Wt*|=;0}uDzLIDK*CyP3- zdhrKNzc=h7>25euC7nXGu5lTMpK+j1j^b0>wJNQRh9{kc<2;u*GkU0F!U#@)TMw2Uzq85GL<5w)S>gx*Lm~a>f`lxEmxJRW z$gWK;N_0r+$B6iaBn!MzPSIrUgr8PpE(y}KApRsa3- zAa{hKk0lwp-Sz3RRH*lvlK%l@q>Kl(zw6|*M%6V>GRWT>p zP9>R`OkS>jVHf=^<(BBbq_qzK<*?i>qQ-cr?#7%9ETT3x$9?0$hbOf^jPDhvCqeqO zglF%_L)Y1Is~tGo{B|pa#3oMJ9Oj{2`4B&qe?YhvMmElRRHHWbWxz$qNI%62V-ly@ zzvU98E2$)??Ld9(H*1&@kY$@k63R3eVL_Hsg+Q_SJR2>*h=J@%&xo9>b*d-1=!;k@y{JjF^mjq!;`Md8+keQb> zQcT0)p6v<=FeGIZ{-2XiO3Kl&yGe9m9RL}>BP0%VS?gA!Fs}>Gyl~=|gb0-)0V4K{37BSUPfzKuu9iHZ+U!jd!K*Y_z zM8(X>t7d!De?<&+kziyT0TX3?R0yT;n>e)`gp?JGqC~k>ADW#1TvQbk?UbELu{8$1r zJNTdO-trade&Z(>TTZyK%s%Mk{X5!>Y&#w5L0oUkliXzaC!g>eRGoVdd`J^Eh46Gs zW9fR>L>cf*?YsGhjV`#V^133R$QpUii-S6~38tp`3Sm)jHgG7OtjZ0l(!z1#)LRD8 z?Ofntx#Il!4>?EDqx;c;t`=hhspG^^p@&#~OVKsNO(&wW0HHEiLLAa*oBF)8WGZ2)+?tEi?w&waPxRPgryIO~qIodkn3YGPRKSO5uTo6oG zvR^wKnpy#UJvIm-FUI=Hn3Ji&oBer`I&iBh-T4cx*Y-Lc%9bb|?(gwoD9r0HJ`MLS z(?<7BN2Q^MkGH*C0%b^@8ESPR5iAMVc#}+hOX-nEuc0bS)A8+ty~0nqeh}^M`ADo= zA9`>B=GYa6pvzRtylh+p12i;$b`=0n{O*o=VvxMNNI@7%LrVM*SHc~|tuwluMU`a& zKMi}=;MiT9i<)-0`Yd$(hPn+dH=$eLUjzBbto163w4nx3#WC>^erhu;T}hA!L{O1% z=37UblA@hM!nVHMV%=q*6v$bVIRb!OrdQPcD(lYlACgc-dL16V$yFT;!rjM0<=7zP zzck|2RN}rX42qPX5&2(;bam5Qo@Z2!3a+f{gLh?TCNxLuQ=SAKu7sqK-ywXo@@1P#1_7(~znB5Lb;zB&$x_*@m znlPiEMY&6w3=L(SYC{;EM6W5rr=~@r+az=>qEOuim~(y|b`y99E6ZGF;Elp`jo6`9 zGMR}{?=$K}W!yDF;n9kTQo1ZL3N>=Zu-x`478EF(nx?he-8;xBBt)}gR^WQw=b~e% zqv3*bKaB|Nu`p2vn>4}&OmGk1*=PXA)J)=?-1oBFUN*@C$8Z)4DJG%^cZ?{!QGSHwH~2sn#o!++=KSfh#W@zB@hsdGsM_2RGY` zpc8x}!Pw$UvTXS~{FAO`_;CDNwia*HV$ZLid|jQNSp+fK8S#)DgZOTA%eTk2p26qF zz&=1#6&QvdIZ2_qUoQY%TUztWAxy;HlxG9Db6DLOl=uW0Xxd;_wdW-iYktTxC+WtJqHGQT&+an;jZNY^nD>$=_@7mu7>r_&Sb_8 zOr~!?Yk{j*jz57@CeP(+QJo8E+0F1SX`iWQ*r z+ip3WxM@7OSuLJ5!l9xA&$HiotEc2a^UuKl>^8<&;8TI!LQai~;FW_xm@;kiIh5v? zA|&}rvmPwW9||pS*f!bk04;^0w1QMF?extO)9c*4t;a*hdpOLAdhV)nl|=p4hv25o z^c@a?;;D}sYPgWyB)NPq5Ri0;*Y84=xR+P-!Yt$zq;xJPI8?_V`%qagbn~O{i2~hq`o}{H)tQvU4~WvqWb= zz9@O0XHQieY}D@qIY1BM16#9O33=+?HxPt9O*SvGl~QV00|H%#pUd*#pEq@1 z;+s|G?mH{k6NuLT>RLQ6q-cFKr4LPUn7JD$e zC~$BJ#4w&QbMQB?wA|nQ^&Q)Fe@_1BIELbTnmRox?%^dJxnl?Sj@ntCW z+>UGmSA2BQg<6~$KsEtszHAu75))tjt_!HjvTQr$qIZ$eO8hJc+uq#?;xL)d(+!=v#(n#ICSznc?KLY?THSEDLG;a z%c9G2;Xh>hwKpv9Kq=#bij2-^iL~zy>?VDaOe3wj7<<4V8PaQjC0y<}d3v$TP`E{t z2q3$_E|nXZtp5JTqyj!&t_>whR!P1jSw{-CrGww7@=ixL`?RoEw!@n1e8n)o9k(3Y zh>zhZ4;KIxUThj$vB>(g|5zU&TMcglUoK>mF!5@~cBjr3xDaifZeIk!m>HMG#GRSw z=P-XfdOfo$yxMn#yOmdGfrH&&QFa=J+giT6R{Lc_)y@mFH5GlJM2*gCh*P)jN*YRS z9m~_Qt|yRy=+v0Et=;CPr03PpEz?0>S+mmOs}a`Q$4$O=u^@+Eru2N9Ro#HQ>a3QC zb9^}Cewm9QB3tgO+1KGH6=9NVls&dE5;tQ0ArM#{*SM3{N|f)<_vSVL!7hs%4e_jtf3E- zAEiGIL=g#pJrT6Ee;+6=!-vszeRIjQ{lawuMW{Mxd5qMDNZ9)w4Vt1=(yNe#DEPRr zX&&qV(h;(7U@fS%4nA(hs?aD4{ zu^_BolEz>fOlAdauUVqHZllDZHu>WKd%IVET#8CFOtFI}_L=q@y)TbX*RN+eJ27fs zqJDK(9=a*$L=vUFsojYqO@Au7lP2l z7~UFQuGWfP#^Tpqy=THTVqG>{D9;vGxdh#S(1O&U<3wz4rzQF|1&aCXuNx1fh$!f= zUODvB@Wvm#Y;(>!CphNhp~M~1%v8fePHI;ns3B4+5cX$sy%{IB!ypuZ^ZAQaYfcfm zv%!mY!8oQRNbEIeKYvw=hu2F&r*2cju)VdBhfI(YAf$V`WF|&iLeRX@`!PD6`fQNIO<=kJB>~`w)?uRS0H(5l{Uag=Mc2i zBLt~Jmo@jDq&g@OPXKU=uwB`xGbXc;AyI}(J+Zx|zaTS*jjFx_Qkb!HW$Rc$)NGh= zU028bi0;{+)?>iMe*y}n-=DY4s}ck?QFL4>k|PK)z?B#jsHMD&`>sP$s@f(d09;YO&e$1-G_}7WCPwd$ zdB-#s1$*GyD}eNVsz8u6MU2KiDmNafBV5a>fe9w{`E`sqPo?hgH0u2d81$vbpNG@oKOF{`tN1 zV|ZbT*!ZWsT5jE|tpuW+u-ZhUbMDWTYB#=yr)u_H+38>bS6n2w>yD>3Um`t|!kkx< zS`SYRreh`nC$cT5ajpVQ)Hx)+?d6#-(GHz%jVi{FaOQ_;kdhF0Ek+z(rGElib`5w> z#`VJoLpA26>(-lr@_q0=rrbk7pYS3ZC;_(jwT^5keOYS8_kKj5b?hsZ)sU!MY)qwx zme_dtj@mjgVJ9S~8xQqDrO$c6#3RT**%V8PqQHFUgp;!2)9P(aBP)w%h{8CBMyXrW z7j9Yph_o3n>8^SujF~n%Zv3ioE@SkOt_tbrPVF!1xc;QS-wC1l8fJSf4d2^JOn`3+ z4ds2FvyrT{$UchNqNjHu$VZ z_>*)hT37Dfd~rCrOOm9I>9&192r^-MC&JWId}pC2{{h3W$EiF-d;zuo^TyAXJ~7fP z7E|(Ny*~vfH(D@s-;Ga47Eqp0%`r@WjDpvBgv#F3&ii<~w?xt4BAPV2>S)xPZ{ns! zH_EnS*5!lokc9~Dc_^i)g2$%1S5K35{5a5p;bE0V!mvN4Tw0eVWJZKKWmF?pBEq{+ z66fIFT0#oGy==*RQ#L5a$sBenihafuVy;m7e(=<)=X!6#)P3N_4S_GDe8jilBW>Mv+HprlJAZF8l*2eH!I^n6`sf! z742dNGAFlx5Aa(qETH07_1lGmW`l_?1&#FlQmYrxB0kBJT{>HL@ReGVJx;*-4((UEp0ovDpU^`5 z5kW^}SH$R}=p{mlNUDO8v?g0K)YUF}qzET)CKMKk5rnZ|jT6$R*zmccY7#9)A-1?X zKC8dTqr$k>k~yizJy&TQOGd__lzFhLti-X?i{4LKd0=OYg{yJ2BRRyLAA7k5HzR@$ zTdor>6Zg1Nbiqx-!TI|mKlF0;0$OUh5x?vB+G)JrgWgy8?#bY^o!AQPQPF{JGY)-M zI=EsI1&YF1jp^HP^#TQp>MdMdor#I?a)HGUE<6mhS-O>>V8( zd`2L3G&N2Pc~(Y!C0Y^mqUA0@w1hdzCs|X&3?uh2+qn?7Nse3gRedhA`0bdMY9z&6g=Icpj)$vhc$)-gvvRofZk6%-=L| zjn##I&sRD5$Y3^EGbXl)mPS4|D>g~8C(K6DICep;4|ICF z`^GMW0Pm87ue_3M0f}X$JwGcthU6`|^Q9B}w#g|%G|}tRUzvlZlk-P9sjO`#w!IX{ zZ|00_)nbTwPWbBBDm@Fo?p*!wqD(wh#46`mAe-FXN0Aj!r(ZR0jyvL>J&IW;27Nh_ z^PZe!-qMn>An)5G=&XyjvZ%7XsV zvCBC^st@jOZ`aYLj4TO}lB)JZ%F6i$Gy}ZXLSu65aFH(nAaRgF&%A|j`!#;{FcNl$1!Za``&x;Ua$J{FgGQS{ z&#So^_uypZy)WIfbA~k8X{Q4ngO-QAYFd@?ri~i1%%l5F+8Ek=uT|_o--dh1K(fqW zS?uWo2FET?YK?xUQ+c~*%xdgmF7~dBG_w~$A=r~(uw-fqI&l0`topxbP zF#<|7?pTYcM4@yd@1-!cdiiBk)D%AT3B7IUv2%2dC5Aih-&5*=xnhK2eOU;$#$gC? zE~^MSvBEg+wJ5AC4|YX~C8uAC?5Gm;F4U`ON-A2UnZ0Gs zLq>E&N_>mHH?nd^qF&b8bS%)mcy&?#{B5PuL))XwpC&TfgSn1e`c5U|<*7Uxi~vVT zQr8dnce^Or&m8?yxLu7V@w@S(W-m=*YHRnN1FSsar(mJoaV}Y7*RouMp0YN5AtPNR zbEQgRHq=z1>Dh(disXB$PG~Sf`WT=45Z{dfEqv9ajq^f(^$r7| z-*=RUNM&;`(he^iKwEjv!m4SIa1ABg`+ zB_~1a%LH%C{m-DS8WAW-LfiaaFG5E7s^Es`^Ivjb?%U3GNY<+e?9LC6`CZ$c%BEmX zm9bCBH~4XJ6`oHu*&WY_wn-=OKg0!NZ?Te?=}BUsAyeHcXTIfr<(U;CiM-i=$mWjh z#`aX$_6#ie-z+^2VMba+_Qeg%(|(r(QerBqnu z;PGr_%D1fF5Kz97(mRzy3Paf^M3*`2l;MEKj6Ld1w)+IwyeY;YbR@@R_mld9yh2?# z8d|nP`p21LSHYK*lq&*C?P-0vC81q)|uFm-U zlerw!F?TDnWhMEUQ+oBHhum1F3$c%kPMTzpCw8#4nB=0@c-Ai*>Fu@KlFxe^rjAQtkv^DJAq$pqlrWS=i8F} zV=1$n^VJ0UaZ27JcFyDK=_bTSEU@*`Cl6Q+S195QJ)-qFSGm05D2>c<2yOd?eQ@SD zy+-Nvs;y zbmGb-dDMFaO_I7#-nH6Z8(-{sTE7>Y`7qPC7(P55b73sNtf3JH>SaI#0M>qL*jyr z-+7T}I-#Yq%Z_Za$0w;5m{moY+T`fM*+R6-hI)L0Ah7qcPBW{!$X_G2AzrrFSEZDl zEmtrKA3txm0eqRCwyl!a%;)5UB+$x$j$|G|FM$%O+ebSowojb`!Vi3Ap= ze83c<>vf(OQ`EHfZD=l3jHs#SEhpCAfmElMLG)|Dz;fCH`yhz-k#{jTrud$IeGr zw0Idt7>wh$>9fKDOlq{s!y$w`VPYALcw<`+kSxuEXgq*mi4Elx6;>GDxWdg3%ejk* z0U5O4(8WO#gtfc6Vxm(c>N3?rW3pc$2eHy)VP%PhFDLneGy?%DO%2uv*#lppbI?ir{RD}PZ?}G#?!i6LM&$o}dLrTnOr25o%L?H4rgStyZ0QQC zBMonVLQZYIDx=}0UpCH7jC!h6Zu^|Wks>EblELYnz%;6-lXAPiQuKmS*A`h)lL*P4 z?#L;Q*Z)xc=a~iLipUukFFxx;rTM|ntl|am`jX9DJDmi5FH-aR6NeFk=s0F@n2m|C z5>}n-zOgPNXu9IgdFQ~K%5h@e+{pk5{ktP8)RLbS(wls-_ub%VzjhnjylH;7x35|C zTl^G>-Kqw^!O@!igfSlKs8st}V}ChQITycNgvBtU9SqBFx1AcZmCal5yklKc8mt13 zlfO0b!U-G^6Y#{rJEfO|Pvn_6d_I&pk%?5W+S2`KX-=Q&$m*pq?4eP_-bs`dP?XDv zWYRFgs8xA(u0Z9I1(%>_$yK5(asH)W_+Acc%vM>7-Ozx@AY}rJS(XDGo zKodMONCiCilqN>5n$TUo#-A ztz^tnk$olWOHH*-yhry_`670W4?2s9jT@ko5b*PBoqQEEM#hw{Oe9?F*M(KF>&N!^ zmPF92m{|~Ba-_QlgV;G;q;Qf;ddZaxY%Na65S5-z7Oo`q#5b?IcFYO6e@63KbRCK8 ztc(awPh>5;@qKw*8T@7V_FROGGz%W!2*bEE277`s68e=B2D%#aN+u&srOgxU z2fwnjUYvr4PY>5w?GQug6URQgAQcY5xAjiLHG0+5b~@IU?D!nm7rINgNKHOdM6!4^ z-Z=c4bYf|`-&`+ly%4d-g=sb0MHQsOgxYyU5S?(y&?7U=L_vwgAa+(sWXc}fUBY7^ z{eu9xcbwe@x3XVC89p6u-mIoxe0xTZ@jzqoh}<9l3;^v#dMW$pWRT<*6xg8mUi6G^X=iA+kN@M&2f=>*G_FPT3vrr zWSv@j)1y}6K!PLCN0juu5zn*P{|vvaPjK{zw`wk2`h3_KIjb1~LKNi#B46L_c4B|-xzb`;V{-l8t{c{( zZ+y}fB$%%ME+u0uF0RBVJeL^N;N{}C7w^sWnTbe}WFx)}G^Ay9XIn)m3C6~L!3{dq z2|2%bG+CB6#C~3L_G(eK|BA)v&)g6r_=kK3pdrjQHZse-aq(hxzY#y$TFZLoc*pd( zDPBG~15_w=NK=Tw6DZo6_$c&Qs1kqqFzSJXIEkK^t?>3kQxmx(Jv^TMtRs1JTC2j5 z1*U6+Y{`P6u16M<*v?bedl(w;)Y46(Et-@}9^zR>V45Iy}el!Ig=)73g- zUqJ*6a2m-dOxaVQ$^GL@2$8(M_+C=rNg<@6W2wY^*0H2;*N+dGPBxARo^LW1MCQi9 zVQLu|v$)_`)PQ25OU~(tP!cf%%Z(T{zZoO%PuoGq%TH*a7H2o%qK%JbvK}@N)EX^f z7P!%aI}D*KSm)MK95T)EjO?NTEqg{^pMi!T36U0=@bf*NkclJc6yC3UnP5kEUM3QM z8q({_5^o1QK6b$A{U+01bk=m#FD~9!#{4(_PAdZ+^%}gl;{9kS+XdT~ThpuJuYZ!- z`(NlAweKL-jNk3;R7iBaVUNYt(In55wK#M3uF(XqbryeGaIrai{0aMRiFI{(DF+el zAca5AUN;i*y+ZrT^3tnzi^GTKIs(KLT$sZ*H<@+fC+rFyBnaL+<3C^8SRJ|GCJ7Tf z2sgHoBo&Tj4g-|fHHUaum_BS@UhD?GDAf6@h%H29oPYCk7@tA*Mu9lN4)KE zNm?l5IG+2LGbh)M(5Q_R(m&y^|MA(JVLkB-teA!AYr9ERc(_RMX(g=l`;EAYM7}Vk!WCeZGJ5FPcMtFz#zD`o!Y-%K9N^2h-jEkh}OUQhLz7Zm@&Sakw1|MVn zu&RgwihH{_=2-;GT#)Z6Xz?CeXboy?Cay( zTJI)20%uPs>5Oi+Z@$-IWk%C%4V_DBD_d-B%KXs7KL(~Khexa4KIYxN;bHVJ4X=+5 z4O5I2)A%`!+WoZ#Oy21 z>d$IP9};+wZeqP%A$1RT!jH7tA2v>lqVcv;p4Z!xxNZ06j{{g%9`7_00Tn+td=P89 z{qdxu6WzEMFA(E7@8wi6QVEWpC{iPQOtSpQc{veO zh-+T3x2mUx0?9DK-_QFzgT9y`E^}up(C-j-8xh$%tnw;8ZtOnhv=^!2sbZp$mMGOF zn>N__^Pb5=B+7@1H-v_2yqj3g4t>uXj;m($F*z!G~)(9i_~9SUO(1v+mj{_w8-K{(CndkyFVi~#1zw`n|`j6qvy6an^%!EB0`u|zXW zzdXC+E>B6jKb=8-v~R{G-v<@?7h3faFRZ6JGQswZNWvNIYH=7|1RoY< zL-_J4xvm7c9n!u3Ki(UiDmBBOg0;y3bj7L7G=NGw(51@bvf%+P5+n zTs#^(8EumS!=etc_Aa{b@w1y1>1dKMYl+ix(;13@h zQKC8gk}%B8n>vtAYwI}n&CL#nPW3hm;1flY5X{e~W_EcG-Hy>ZfMOGVKdc|&Md!HI z9&~9X5H4nRdjsb4k1T1NmDJb?rhMSxHvHH<+oshIo9rkiz!K%)+n>&7j4G$Q)^h7@ zi_%GOorce16ShKRn7y(6uw1J4JQFg}<@dSs_1!_L+Ev#CCD;$5Y#6XnKHPPA0i5e3 z1;PjndYii%P>?~F(5}Y&wfHE+AwpuMdEHlU&_-M1@3UgxA9WJ+qdlEw@++P8Nk(qe zCB@ln#|=K+n=*X1(6SI-@*E*`XsX1&6-Y}U3_o?pM*Ee?8CQYRenkRW(;P@~rbEv`oxhF*`)EKEzj%;&u= zS>IyNuea;p)^^k68#3}bq~p4)cDwmH~(h10)&t?YMP-j$AIigIVbXedyBcyX|xZ4zDAfQ8>u;swLY znz(5Zgq3-x%07X<|<6hTP zr7h3bTb87PDwld}E3REwAcbs7Bs?{1iP6IbJw2@v=d9lw@oBSD(UTE4k|cANXDioy zVql&W)eGxN7{%OU>J1D|OnNxXT{VC2y&qaEe`!j6+$_XGx4-3}OrNMZv}diFh_xc{ zSf?96Pt!rj@~L*f%9@KC9I6w#OjhU*NqMHF|fQ&mdvyIacfmc;lIanDcnW`g* zsamd|)`Xi~h%K$MYD&a?kl1_`{v1|tJKf#e`|jYLlv!&(4%cR(zCY5F4*wUF=-6-# z%h7HaGRk|8JQQ{EQV)6bz+4|xSP+v_ud{w8FKwqFJX-P>w$1kAJPU5TCBL1-4H~9< z^D^J-bXhI9dy4d3$xuG#hRtJEMM#TMJc*!F{%CPAgWW7xV_%Z&i1Q_35DpH zY>}t@uW-!BbeJb}B*05m+bpVC*n^EQGh77Nlp?X#QC`LKYQ6!TV`F3MUrTXiG3q z159JSjgz`!1HxFcJFaNb;XUafw?>mt7i{&r+ByAn%ea^HTe1JXM7A-Eq*?)XcaNoM zQ$Wb50qj-{21D_%JVWChh9kvSYR%;cG<3ooM@#C=4ML~a$kznoiBml=`l-|ZzLi9W z0yK#q@_*kOAtR^&gL-0tNr@@da<1StNV$}IODKtr$$cE3Z`Qq$Y0(=ce^bGWwkQAQ z=hXz*5cK^XVmGa$D2hx1Ggw+A7lE8O+Q}RdX}epPJJq8D@REB;SVUowQ#01t1sY0I zmBsK%^bGc2(g+CTe^<~2^~dPRPUq8iEK$q)#ZCqW|vApt#YI ztnyjJ16K~-Cuf3x?a6lP|blI(v^@$WKnr-%q8e)<|uRGWLoK0Gu- zSu~peBQNrwz5DhWYUxe>JkHPCsDD1P@PlR13LUMO@ab8QV9-VeBBo2RBT zbq?{c3=9X;DP!|FFYgb#dWYRNX6&MSO?1I5OG-vW>&4C2^ZN8<$=fuLuAk916Vc8( z@Bfzmf7JlE`8Wtu^|9q05yD6lf+aihrT%}fn<*^1#;d}j_i^D=?UihJS!zBs|ijb-DomC^uO-6%D z{nC4z_oZ!ZsHGmFJwK1rJ(HW!%Km+x|CO}=z5kdBL$x|MvR`fx{r9^_VGT$=UY3^H z;iATmB06_vn#N)6hIZXB9So5w=6%EI6*z|lxtNzH5>rV^VpF(@4xBd&`yQlw&~5%| z_DSL5;hGP4Olz-lXn*c(3#W`<^qg_$x)t;S*wd%qY3i!0=O513{`B^~C(p!Os7;uj z`B$j_|2H3>fG3oFwkaj~qr+wtP@g@Ah6d}b8@j*0A!Fq*H}pTv_hVb!hhdB?=TrK= z(E~C_ErHc7xR8%>q1*JDoVI(uZALr9)bj+l-q*o03?2SfR{IFWoxY#(Rm$&6XaQQ( z)h-t_W`Sw<6OpvqLsR-P|NWL{qf7qjv%Ab$DnJAy{2 z$lxX)7#Z~Z|A_3SpW)#Vd3hi_9;lT*>g8)=<^$+{FMJz zyaEHJrEHw5~Jy_Mj0i>80TvLP5BJ3D*ALi7Ijf2!R)f?F-)q?`l;29X0+R0X` zPHwp)ypU4I6Z<0H+BDL*uB3K3RDbL|HI+e9z{(EPvC0>wYF3`YdO8)qctTjg0 zJQ&Ww$7hYU+IPP4e42HbRLwGv+#jd2aRqnp5O6}qDqce`IB#B7(D5XXO=?-Ga(b%)xr8+|_TDB0 zqN`2~14>HD)G92VWFViSXJQCdp+y!Wrb<+;2pROaG+$R?#jeU3|2}d0 z#n3YmnCACaN0mXH^l#FI5AdxLVx$@UV)qcvCCNek9L+VK|V z?BrfsHUYHyLd4j@|_?v?CC-}Zziege}Vx$TI_hp#+!iV{k!BS9352wuOgL!^48 zuA!-$?G-+4yV5pg%yIQtxdVeQs#iqw-=aDJnb=OrKbFi|CJ?vx7NI-_6{XPlcxEPl zH!@;WVMr-}Eviy$grqALa{RoOb&!;@*5@+ivT@toe#>$-0aUQXrq$yuC>*~L4HO*# z(iM%6YzY15$@vv2yiBNO&)Z_X*kq%E`roG4yP-$yQQT%pecn!(gP_)0 z;V*yw@l(dD98`G&FKA-rQZ?&*IuA*BV#9CMu}7eVk=AW|4`1I!>VgUd&i;CZw>et0 zpdd4P-y<3-M8*CTSx^jBa(D)@J0^AW^fnegL9`YOYTN&W39EpI>8H(U{Cm5J_#x5qV+JDCI=H}>HRONmzzzUdRo(Q~>I{qi(hWqVL zLs;6H{%GmP7MOH8_@K|W5l+4danB@>^p=luEojv&4ILeb!85(R$r)*;YM&VJwhVVu zi)39;1sHO+D7BrHcrx$NNak0bH-s19kDmv0JZgZnSGh^&y8Uq}oEwqQwss4M?bqMH zFs4onyw$Oz%je?ld8@Owbtq!Oz>K|H_+)2#_?q`bYLY0le~_?zoH2 zm_2-LGT}fdG-4AS;j%51Rk=&Ah1H$u8TE7ObA61LtAI%_4i4_Yeinerq!jdtaT5~^ zJ0cAq3%zt*bDVoR)OzX zi^YNw!a&n>LA_qo{^!mKJ(9)%F@_^5O`A%%6D3XJ#dY2VPG25a9bPPBErBc)^z+L{ z)DO=$KfO0lU_;zbn~x8Z>Q{7*^$QQ4yu-z%;7Pdt%VA`w$e@%dUcLD{X6bm1$eKeB z@L=zJ?Y>*bK5RfADy8ceCR;fH+T%QUvz&4PU@Z;{m`usBCBdJm72b){PR-QRnk34K zeh?mLX^#^yjgmg5#l#t!eQ5=EZO4Vc#Jo(xr^@KPyF10S!$Q4!dXbaU{@3JvL0l zzOO(k+|HY+0Xj-Y9dH6Ah}bwdy-TiI(9r;I3hx07lQ2M8Nz{{qE_Vh9N;+FEMg-7X zyL;RZBdx`ZW(@9Osgp=hGEuOmyeA|gsrw;(zX)!-ZIXY#FkqVB)ke_XyuxD}LQb8U z-*q|3_jd#U#3&yFEjg_Bwf?wPdd0v_^d`tiq;u69_+X-I5N-cxwcdqUkv+4@p;1lS zI9ETSt5L>&`>}KyRv4fBq2JoQz{kJEa-^Y0Ct zoNRk9A)hDFJ>mz?#(mq6ly>9$d{M4R%)I{=gW?lF%?Oalck#s|CyMZps1A zsrIp$d-m_$|9X5v`4^@+EnQ-aoqn@)Bs!MfdFSAFo;_Mp^1sc^ErQC&jpkh{&^|UU z&ev!THXJ6Bw{qBf6(cyrZoWJjLI`efYvowtdV_e|Oz95l#{_Dg5351?k88oi{C@9C zlqjv^76dV?mJ?K?$wifcKlzVg$3&Fr_#`7f{O3Uk6g#lCfq#`$>8u2bG%wehf1e2# z&hp?2_9AVV_Qe2m!ceMJ=Mp71pAorQsg8_33fjUvq_^mmEE+g$!QvRkN+RNi|7E%jc0k2S92_^suUht97pY_(E|bDQFYO(Q2~WY zyCj)4!shmN)9Gq@8mgR8r*`4D27F-ba8mZ=k<-Ten82;K6Nl`?-&ZbIT^qBEB z#>YPpA3uD)FAS(`zgeX%PoH6AY2T@W4Y*$GAGjD^45u769$pD&oGs^v&+86HotvNx zPk%W!s_T(l-8l2V8L1XCRLt?2s(*pKWwhIp-PmH~xFbs z$OXn5Y{gP7f-~Odz4-ma- zZ}<7Pe@P>mEP{&12H++DE8ola3n85eCCam~t%f&Ti4q&qb5gOCR2wyBEj}_^gv~T4 z=J>s)c#+=ZE~qou&H2jwe5R zhBt324Ij6K-v|`EJ{r42`nXg}$g`&RZVg5y9F0W6x+>ev?OMQw!|#8hEs6>;=!K7^ zsyYM}r*}GpM|=8fGezy7VGFiYV-P6wE<+Vff(#Ln_3E9ffe_eZcZKCYF-B*j*R&@p%vjX zJO2}%kwNcElOdx`@ZrvXs2m^1LMZU7p1$Olz&t`U&6yyNc6Xb9XGMoNrd&t`T_hRk zMBfA%SM0~yt+-IHRi~g2F|SO1&y*w}Ah14U0F0p$Hn?NJ7qf2Xj1hd(YrJ;<($DWo z`01&gAAY5N`MJ_%z@R~?sdYOm^D0yH{_5)GJ~4q}{ZWzdzh-n_2FM27LW}hO2w7?R z3mf12Bfjc#KF63;U2vBYp2v{(ffWZrAd?0-%G{^jn@-C?x&HPI>M-%);5XYX?S=f$;PgAUU5O6;sVwZ8Xw z&mWsIeQq;1C&lu%y`VYzS-bB2UkG+%LIPCgtFc3`X(!Cg5>p#tV}9xb%G0t|P0xo48+a2agre zu7BWZl5*@Z=tVotQUEsm+Xrw5{YIi*Xovrm>nc#MM!Hn#`8gnl=WiRI%z}HS5-Te z5IOeZ%7h6U@9bN*7J}&p{-Qh0J&CbUObrlTWU`^qJfw!CP@1>uSG9v7oT&M%64G>+mCK(8!RFNbe%ymAq2<|97oL9d>E1~Z? zE$DI90LGeam7&Lc^OUypL+mkv5FH%Wt4eFi{@aLg0j*dl{ z-&Bd$UH&L!RX9fdF)husP&uvGuedB%#cypA(Su-Sbc@FP~2Zf;j6 z6Q=j;%7)File#-t7+U;6hlPff1=S9ve$xMffZyn#Xu@JHuC%Q_ngX7_ufe5z9?tyh zc#t~?^nvPwXtXgCCl~H~1+!H@#YZ_9-vrdL)ZlaxNmx09$_I6>9uQpsY$qzLfNOw~ zEietpiKOeeOQdB}eWfFiF@P&#B{~w3x`>KhcWmoSq{G1b{1yM{I>ADt!w(!>oHED} z#2U(NU94~p=I<*h@mpfUb7rJ;i7rS$}dT`LESds zV+7OBof5g?dtTHl34a}2$RnD1|HIbS5$ng8rxhnji^0m7j_IQy_mq>RpJ;>8C2zXB zl&!^EsG7^L=B8Ffispl6;2g_dDX!IX`*Up_=Yq1oFWCRS8I5|~3vRL*$hSWzoUG@X z*x0|X`R%ajVBEyJ2huhEMS}rloI{5OXVl~@Lx15V+0wE~7t3^WpNK#~oA1cj-(P^I zs;>}8CPY^JZgz6lHNE^cERbc=IGA7y|CY{49qJkvKmccoiZ8bFsj1IHLDdw*w!IQn z6OMCqBd0?Ko$Bx=8KMXtx#)X0`vpj!-U*LkP^CN`tvoF$VjmyO*N?e(lySF{1?V?x zXsMe5H1@jOCMNsSCO7&duVb~Y9mo6flpkJrRPF03_Yhi?KyH2fTj7_j!&99kQB1fby1pC`ZOpDP6oj{l*5t zjS4LLbd2(Ht{1`GN#}S*nA=uRKV!dD_mBk)4-x%U0=SM4y6*4y15 z9t%6Sqse*>$vVktmg`qfPGYk1TZE%}LT4V28P=RSneS8g!cNNmi$H$kf=ZrcU|@0i z>Fwd_Y0=fx1e*1!pU*-tLkZ%`iNlK@677=VdupxPOv2h%sd%ZGF**5mcyKUt3mA96 zYgrma9Rp8}z8l}XdvgQ=pi5wNrxGoLwrb1uTXqUAg-SZgxox}-iHBKAw2t*{0{(SQ zPS6U8UlLu`irdgIPfC%}xG{eVXX$^w#kKgU zeWaJ*I%=!zp-RIAz*o|{XZ=;oo`f#tfV4mjkyY(f{&UdK@NjK6JlfoHtIvTxf{)PM zrc0z}^3B`v)}4nid5yPvw(w{*eB@~Qp5=PL(5$05U~Ht_f9~kd37HHUfXh)uxzY9I z(Dk!;ZAH2H?>vWp3((?@ztp?-Ruior<{QCwsQm(m6fNljD(paDP*SJY#hWP z3t#n|*|&pB^8UQ8u6W=W&K4jFSO4>>qtvUvpnUqxSi7+x9enU6L_fZ%*8#4i*9EK% z^a9tghWq5b3tvyS=G~-ff&fJ$29b;n5Rrkrzalb5a`Z^4!=GdAuI-BV3s;@$7VY)YQFoFSq)YGJHF`OpTje>h;^ZV^)4pvvPd0P;o+|rt6TS_e#tc(!)bgK0Z(s$rD4~*R;yy^tG^C6y>Oubl7>i(H$Y4WGY5-RX%nOF& zc!&(nxP2q4w?Xf`*pFhZkXJK(!6~P!njNwV_Y%L2x8E?C+fqoe6%Y+AVQ8l3i;2Rl z?mmIptAl0ha5UlyMBYG;&LP{oKO(d=Tq?5m%jE5Jrq>l9MqNQ-h#xuZcy}R3RVnMZ8NL!p|3h>do6BNf3GTF?zMy%7Z)<* z3e!0u3{c9GdPo@&2oWM6%r7ipr$$MqexfKB0r-qxlN#kcNwo7pF|<(q)i5CRZ89xU zCsbnBbYA!$rcRYgT}m}{zflBTu|V#v_WKjld+RH{g*T6G!+dhvR{|W=bo`_yQxF$QN`@>|@b}0LZ;XgA={M{G5y#7% zJ?6+*)U*3^f1A8O1T$8sh0n49rGAkTV!$I z;wfacM07&+0>Kl5D*}ZbfBJg?ga6iW|`IG`XUYCX5&-BQ4uMMWVo>WO{lKuiFmV2<~FoMPkU-IM_N z(fLSrg2%@zBvt2S6k)i(c5tqjx~@g$#Aw(%?Mjg<-Ty7@K{1r9f;b@yOM!~YJInT5 zc!toK(<(o?fqk=9HllYzt!B5n<=@Zjo&;i-{xpX)&E@w&O?^K%1Bq9{CHj-@O60&(1(p>gw8`~sHG z&dv@1%*p*>PBjmC>^3?jHkj^z(6K*;Ov?cpSrSx!fn%Z{hQ9Z%Kf{$_w-^gS>&1C~ zD9H7vvG(=gAR;7tgMaTrtu(}%lgQv$ZT3mRND@G}*`^-n7(D8Yn|sWLaSo*z|BW}9 z#EhJMN2HEcbT_eDYl(iBLxm^)&aDBni61>m8aLXSYZRU;{=~VTi3QAaK?T*k%UI|O z5mN^ryj_$H?jk%N0xATw8z(hfCyY}|eqFB<7QpLYiv9MJnX-Z9?A?@b{v=8tf8P4-+Ms`fyTOk6$8z;(OsFtnm_p1lnb0y+y5VJ zpOFfjctewO8=L_gXEM|DVQOMS-ieipOA|-AK?fmeVltja{KQ|GknMMwN_C2~#@?#f z{6Dh3Ix5Qb`<_l2x)~%yP#TmjNfjxT?v{>W=ng3#A>F(|Z1?lc)04V|az21BE z-rwiD)-2Yr_yc(7dCu8q?|sf8mDjJwmW0L7=_t}|su25`Fmi#Al@Nw`@%*(~&Wk!0 zwI;wK^uP1HFIF~{ALUzo!_NaNk&U07cV9qSh!78kbH+k}G+Tt}C%Ba=n1Q!+I;aK2 z)-E@Yj?<>_7UC6A*Hevk)-Xr9!4;o*o&`sdUYgRTc;>IkkZ}jr-G9osO0-MinT2uV zw4cYg9!CqcHXc&V&BwEa=k(H|H=+P--iGzk%#Z+Uiw565uWwttW zuhk7aAr2u;SJ5dVN$g{p5iBBXa!_+l$lh)cjE zz&5jSgiZ(Qe_Hbmm+-kNiZN<4pX=6pQq?IfZ%x4lZfaM>ZyY;K|C~hwdF)s8W(p4b z0AAI0r~T}0kL~*U7H9WHhAsl@(ul^V?8${t`?Fx=kbSm6*&bzQKq=Flac!=WU{*<$ zGK?gT4iVmb)!i-V5Hs?`dLb7CR5V?pq}S)C?g8YhuN_~0+hN?M+l?{ zKmhSgnJJ2-FAd5`)GRDQStB+eh*hJ$53-ttni-1s@U@h8Eq^5of?egZPSY0Vytiqo zn>){a?=apUEmezP%~C10m{5&|^k)kfuJ#>7yxL4-y zk0R{xBMx_{^~Z@Ov+M45Q)!#~fQ}3-|6hstm*NxEma5zf83%MaVdma}!I#Y+)l0s| ztN$!0Y8ql{yz)2)Ln#=uGEa&BY&vZnPJ6&mWl8X#Z~6vE1m+$fiz;a?O-oK z`>j!Ra1^5oNz~9L$_!<%6!@R?>=#d*RCp3V(Wzvk>FH(QfvIY1AVXAs!Hh%%c z6h&WTQ!^Luo1Oay=HhOn1u^tLCR0jhd~VJ!$etl7*f^j}l`H|;d!8bV3rNAWJG zy~gEvSET@VGwXlE3p$j31p|i+#hUoII9H}pK%4|+)Cw;8X~&ih}&1nCigWBnEm<;aA^yYg$yK3PcK?*fyQ7?c*rmhIK%aa2YxN%kB78 z?VjY29bBT9cuOKa6tgasW$HKpGz0lxF@jFcc!K}su+(`vw&yP5#N6nrIZ0;e)vQ>i@0vBRTHbG>O#yNotsFQyY;I&q|v z&@hH9(jPOw(&IzJ(6XA(<0JPwV_4p?0=RX^V5n&^5h@NxpD$je@`bIf#`d%rDTnGsqM!6Lg}qZ^5JW?QEf%6VW3 ztNJ(U6eaoU^T97H^@wy5Ha0ffRWKEWkg=eTS?8OD(1m4WWKPeIjNU2cOUc131a>8= zcnO~Z_P&puP7@i*a>iM1+utS8_~P2S-i^6)+!@^Rmujgfz~Z0QXuR-Z>=IE;h{si@ zCAYtTzj0fucq*1ZJGS`lx1q2M2j#=ju|=5&+PzwE$N;mPl;S#-`$?aqF1`(qNJALd zDt3e5`AcMcJ6}hF?2+M7DTO7G!Zy^^$gMN5*)yIS3Lkw&7 zYhUfp3X1xeNa+6;~IdEMNzRZAcuKQ!ZRqtt?yF6@sMb~s5C_+8);y~@MlR|zk z?xy)%F{SG^Uu&0eStG#n8=94^q~HdmJWp;$DW#W|!?Pc^vx z$E++CHTtMA6%5$AxW~A9B#kME>m3LV3EjkZ7W7Ltp3naM7yWfyYZ83PjkB^q1AS6O zo!PZIaZ}h`uwRU8rh5y=BaTS%<%^N4M;V~QHD*dFTFP?z5GM@ar;$P$pp|wkN&8>w z!V3ul9RG%~HB8&poppN=H8sN-^q_=@Ej3MwO4Gt2H6ooyF#o>}P}>ipwo`+ytK5fK zeCQXRKSi@On0Z9%T7thUCOjys$v^tosJnnkgSA0Vq0l}u((GY<_l2?Mq7B*Vou$)J zscmUWD=E6@Z3g!q)xFs)zw|RqIapb+KW#)S-<^B*4?-`MNPcs>{KE_PZXe#3@JQnA zIwTYnY{jZdiSz)@w2RwQG7*Q7Dv#Ki>w6CoqIM%i_roAf7rDy4%IyJf?;h^l{DMPt z^}robRCkFY&Q2ACcAOt9*x=t6t!TUudO+mWlau9pzPiDBXm`F7+Z(e&UB=I{I+K7- zsMM&i-0rJoNsw+IY@Fd3r!rmckq8!Xo;WvPo0$IkVLixyVjFG5k;oX{uJR%1{i<r{Vc25Z2CwigWZ3M4MTi0c%eX>ti4dc!QolXr_0u=KZ{j3?2rbL~m&56A7}+LE z^c)8nzZ(OXs;#E_#)>ml%(S%WHsNXYVN&AfvKWF%kEQx;B`KNDDUnB(RfieTx;_)Q z+@oa?G7nRYqx`4#6hxn1Y~ea=N(;hyf{#wy=XA!9_?jG4BAKTR!3XFlU^+yLIyMS; zlCkSf2MPHZDl<@4V?#W@M9xEApU!1f{sI*MwaXXyP}7`23uO7CQadE% zqnPh|`$Fd-es@5%R4)n_+7Uc%y86LtZ{J@%=W?j|fapu7A9THWv2pcQ@0no+dO^WH zB6RJ1w(&?~55Dk7glwRq;e?1EY_(wPMSz%hoiNA$5p4a${{vVcao6yhyH9wP_@B%k zPh`(sJ0mTS&^qwG)37E!KHjZF=s8!8fEbd)({5p%B|AM78k(7yh*Xvd?Dvu->!b@# zO*|S>icOuassEL`|5iAH+Y)eHD_EQ@EGyIr^SzJHriyA>Yz4PqJbTJUUkH4YFvpSh z*X<;!@vk!(Dc5~xmdCYKRYcu6MyqskYmFEU`W3nmk$IzAJ|hIPl!HDY)Y zk3JKhp$T~lvic})(Qw$MkZvJ7#P;A)>fo(xRKJnb4$SNKN}xc25<|amUV=sYc9*e? zgOa1vwNNO~h`~C{*XZDR|IW=<7{uJbAkChVdyw&H{-^d{^uB)5o&}&$w!|^c<^FS!8BccqY zf<|b~fSu!dL@?E3Fx5j-^rt(v@I>Z6NFn>FpM%JBtMgheYtFZ?^CrwnP0P}vx2ORY z3rA<$G)L@*)h+-NR*^UYuhC_Z_gD?eI&ANDSxUp~)w_@|5{=C9DuN>&F|!stJ}AEM zvA%zEpl?2;!GeD=%B*6Pbnz`wIBj~{^@(>>lY7EHu7qE)yAq3yY2wji$rrEV8Z(u9 ziT7M3VK+@pGY^EsF~|c1%uQb=-^K0z*ak!3nLI%FI*|W@I{N|4EC#9-+Y? zwsnLrCi0%6iExwmp{~bi?~&=Nw%OKM&F#BKXeGS_Wi8|1?1;I)Jv*PV-kcwwzC?jt zo!XFW*Ey=44(e=lEkFPw8DNRiQp%lz+%^R(feUUg;s99R*G!8=vq_M1zpubH6FR{IJE{}{OZ-S@6yjlH4gWVYL%4Tt@pn_va*`9x<21`Hbv2Z z@2_;q^|8S{dnSLp%fgO}i=UOZYcV{!UFGDlW$OyI?RB1LlzvZb&lK^hi;t@Iob&gU zi}puLRc1c49DX3Qq?<=e0Ac|yGdX?u;ow&97o#k6MkkI1t0(GZ{X$i|%hAbwdM+me@ zYZ_uig9SCH9fW$eM+#%#%Kbj%zZgK5s=V4!Zvh`d)ASK7dHGoI{E}H>i4N4qSiP$9 zp03+3i?`2Jd{Bp>u={rUx2bQl!gejT`d+8SP^Wnp&0crq@+tbqL@HOsTjQ(q(NPgjaEWEVxDHNiZAK-y5v=x__D69^XE(gJY zmAXrwexps;%9M=TLIW8_%@|!u;R+@_x?(@Emj*OD5e0lq-O;FjX2L zUP?Cm^8uy2GI&5yapWy#Ou5}O$Xr}tHflA-+K*9sXbg?k?k8v6|-O; zR&WLeyK@y+0vcwSTvX$H00DL^|4*W=%}uSfNHSsj^}e3_Z0M0=8k%O`n7a8$s1g}1 zaCA6fzoR8vA`;lqk#4MiWCT#`650la`>O$IR4JdBd`G#c^TN?_Q*uHvAJxz82^9=F zk(~NLP$g3R+_Fn>uk7XmwtuYOMST>L__*|gv6mTcvY+vqsO?P4R7 z=7alXa{J-$AMfD@(XWO+yy!1kn;9nGb_LFAOl0LqL^y<{&mohhMYf)`wkat9q&OnD zV}S7mPXsb=l~A|ZmKJa|QxBOq)>||F!{+-vc-Ypu^o!m+n}rHPPXZ6->pN$KkF-7H z%!$&Vj_}#o65H$B;I!$_YrRFqHfc|v+ScywK331&pFC)EN2Q z4J2nUoAk2M&4ES*TD!iD%*MUi{=1(8=wlW}CNJzzBz*N( zbf5z(6>rSk2zalDqsCQIc|lvlj|6sKbr>>#;8ADu*ysZ0mtt++y!t-@>?^D-7splO zBtN%h=O{w2_&A<(aIFfbwwpea;9q```FwbRBH0z@J-^)j;|G1HWAy><}Ko4%9IJLyms#Tcd} zB{?0pyj{vA8g4A**PTSa7(a2Y zt$A!Gz&>!AaJsRnc{z^E4eWlo0z{SGpta9bYhnL&z8?%mzso zDktK%3Z&Wr61=W9DqT8Z)&29`FL&WzHT9pblZn4h)c{wYm8At7JY8(3{@TOto2kqs zFHHptkMhSHmFzXV4suS1jrz^>qIk&o3>@P<|6fS zJ+a{gO?bTDUvi87cMdP>{zaBeUM**cx?cAEYK{uPoJIWb!vleAj+1i^SFY$bD#g7m znw!0x_qPoTi$A}Y*nP?z-Qalk=?woK1FE|uzS`stQDR)2#^8urL=f4ErsiuC^m;)) zGMLW#n`WjzziAOb3z*y@O2Bpnpw{c>WB~>}zs7Rf&Lt+_HBih0Ckz^;knYm8kkbYL zr7MhLKwl<{5Enyg}lhps3ng4lA%U5W8s%>wy)NG*<5u@UT_jIyy zi@Hu6fAFieRmMqRR)7b@HFv`=#7D%1hbfSxTpUP5}G21+-UQ3zrVb79#%rY1gM z84HzW00@jsun>1-=x!I5XNfg;;~Vq@mK>v zGL5AYak{CeTEd$-k=qsC#f)FPyDI}&KfSY_)dt-#QrtyRh-6nFBie@z7*t|9shlpA zNR#3h4!R3AZSDGI?Z$d<7nTCr)Ohos_2(EX!%F1=e%`e*-?aN>r zGaDk%^UzG1QNYuCfbeP^is$^gl3F4J0SP%6f~@TT6L^{=4Upn-M?vJ7;HE8XD3QF5 z8&fGH4;Pf2yI_EW7{S>Ez=8udB0n?3En z7k(gr^t&W)AV2_c`dk0mfWBb4VhPYJ1XOc%DIj#=4bz;2v^4QK=)8AZO^3r`JVLU*zfyAw{ak4^=8l&k#5VRkF$}NugUI#a3 zCYU2C>PbPzQ(d zc!f^DiU>BFu|Gi*(n&L-8R6=^yHxI`wqJ{9g`i^s8jpW0(1yKys_{Wlm?}ON{%>*X zPPmMU-GG>w`lbPe#)C!1%zS>Hd&E0yZ4HWWb6cpFF4+5jmcqQ4TLfmm6cl{b0|3y0 zAL}TS4lv(*fu)?wlC3-4W3-#o*MlqAL7Da?PNAp*U2s26(&}eyrP4nx0y;b_gtza= z42Rh6fSw!h&!@f#d##Qvu=@bV8DL|g*Lzzd;mX0>;$aZUEcz`Voq@oFkLC@p3Jrm5 zmM_&lLV+gIz$qWV8PV|n(^Cx54rqJ|ZM>+@urWVbh7+fcM^d+CaXiJGo>)-!UBh+( zw$DimlWYMalSL1(p-me*-7W?Hady!uU~`SvHRkmm&fC-i!q#jFtQeS0AZl#ETz$sO zMFpDUU%EALIf70Djq|Wmm8XFs;_eqVd;Y##lM5c_fJT_OBPvE46K&bfw0sLp`oK+p z(Bza8D2VaWRVns%I9UCcqAvOuObpUO1{hW z$nLAG9B?~=C1LNJI-DD6k#`AO+!Ib zr6hKp1+?D_t-O`eg{e-xojX4Os$G$NG*!0d?qK;QF`{DY>7231KQ5V%zDTzYHS~|7 zK(mU`IPCxlF_k+9%KHQ!c0M;3FDD9daYW48wPY!}S`QKLzEY$z4j|bOhyg7)`P)xE zqbwrm5@{$s>9_dvNB;g?cjSTog9i;YhWEy<(xq%}u}!jQD2uO>r>G$y+1Jv=;-&{G z|J*dbL?oF}r}=v5bqNgcvjRr8@;Q5d!xzle5ljfcknM4kJ@|>LRvS3JlVi$uKzITw zLTq6ix$N`EYl71@LTvy02~(?`|2058H$?&d=v9&M<6MB^;L6ir9t?F>CUexDv{nzV z$SvY}Z9rH@qWC%+fLI@%)pb^sK_Y?ADA0cCiC|+f*&mqs=M7J|L=Uzr0|iYKgNG>t z6;xe_v$gHz;2?Wz8CPYAC&u>#f7r>YBrAJgEyFZPBFW~=y_YfQy;)@M&+I9n9dhL& z*w2)NYFAOtMVHWH{f!B!!(UB5v8wv5AV^RVq+cdW#&~%+Ys<*ggGI`ge*D0k?~Hk} zt@ql+52XMwb<}?bIOy|bs{MDi6%sN*2TQG^0BWelB=|Ak0-0)P^kAd7H{<$Xb)fqp zwD;@fdgj_1*{TNCMSIaqN=lj?69q2dAkT3qa3sQ->&Ye&1y8uY z`(Mhx6=O8Z*m2^ciGDcrTWI5+iD{>oIUqS+Tff)V5Q4b74-A`|<-+6*m#V2pGNO&Z zitWl+rsYl3>$4+j+W((Q{8#GCCjON!?U957B<^n74>p%m!@7%Fft#w=Y>9ukSk7Iy zfba~He`&MzlWz`kS%zL*V0zH@u|!#8QGQ!)8ErSmn$?h}<0^f~JEP0P;PTdOlOgeVh2+|&ld~4~ zEI}b#QT#&tj$6dxudELRtzXJP3I0ZyA0D)|?y>DTt!=UkqhBN@Y|2_m3+9bn50firI%Jr>2hPW47lzD+t)A2ZPm`yeY@Wrq}^H zdbf31>FA+uqb;n~PLl#3?*+UAHrec9a}>jukV$mKw0C&f+H1OQT=Z$)g_1RCej^&BpsIKcKa| z36`O3PW8f=kH)@F&;+W_li!85t(iyDc+tb4$wz z2rOzXSnoFS+PN}vaDQ3u;9`GG|L0c@pVJ6adai|uhVd}@!J>|`3x%X($$5z5-s$Yv?DmY-|!758i3OC--x0vmG=E?1KousnBJ|&9*5wrx420p} zrrL}3V#}KGtZJ#MsmQz1=tIgPsFPBklVd;(UkPKDE z`N(KbK_lnJHj))0dR$4d%Au3C3hzUtnLHR;Z@XCF~p>)|86f^v&8WR$;b@jh**z%&<1bdOD0Pw9Qy?wlZeQ3Fd82mc1(}Ls6w}Z_kJG(q@MT6N_?N z7WJ*r%Gmkwe|4}EzaLg?2m59dS0kPq1vZ8UsQg(_9DziimtMVC1u>}WJZ$*Y&zgT=Dl%eREJmLoQ0E2N{J=I~~Il9F#W#s>GoPXY=C>Q|S z%w7o_E;rORFEF%6tMc({(^q6ya@jBD^F>(iQ!!#f3GmznZJJx5BuN>+<@!t_eKL3wVhj{Pibkt9kb7SU<~;;F4JBpi-r z1v+6de+$F4ttv*d^amIzhAktbGGrt?uuK72qxw8HPmSorwLk&37cz2S+qGIYllgIr zTzciOqI?UWYux0{;pcn2_dPeN_C;)1P6hkAb*oQQRSj-Y1diio0$QG3P>P!yQ!ryD zt9cIl;$1KE<9NB!j>uBloj~C7nUxVsoF#)jQzQge*8$IXTg-1bYvrO@j*(oWymWUV zhphNBM(cynX?0qUkCb}2=bgr!lXc+Hi22)}S5qI3%Ee&b zr3Si9x0|lw!977*O1Xy~6J9;H*`8AOANKSXmu7YL1UxIWwJqB2mjJQ5SffhJN(AaYsIQ77{+;-FvAx7ET)CzW`|m8pyf?0lJ$2+TP) zj{LbKI>mXjc*5^O)tY51c1^WPb0g*s5Yw87KQ(JMp5HJjqN`k? z{iQR7^T9m>bv}O07pCzW9VO0;vxsFRl&?{2JbY$;yO!z?S;_h8ya(T7W!idV#jCxg zsC?5%D^j+AiLa$ew_N)1_*4f?RKwO%ctGJ>0=YKduD=p}8+YJq;W|<5mjqRU0(ienXNx}TXSw6OljP~UrPyl! zXez>ox^hovyxg35!2GGyM5in=VPY^fqd-r{9R7XJIMNMmR1Jj4O9Pcr<8tv^mg;UI zRVe{;jMq(dkztP+r^5+QF!@}A6j$Oh2H?HKr&li((x8y&+TQgu*W)vP0C2rt9CY_!&t)p!AC844%BDmZG|e18M}oH7 zzNp7fRv;-UWuaQVK}KTzJW-Oxc=C3eJ~g7l*7FS>CcG)oft;9Td*F@VF~y*T!vft; zu&Tj)_9kI^U63*HV(oZ)EQ*iFiA;TI2sJL$SVVFqe5p?C=(FZPEtPSEPLa}!A-Wzc z{A)onDwu-*vOu6MjQwf6Vsxj6_d{}oSTn{Een-r%%3TO6d(S%hVXQGhB(Fd&qF1sh z(MNBvvsp|Yy|QZ(>nHpBo`*#k#=?E52H7@bV2AVKnfYuRY3xgVQY{s#9O}hOLGXs2U!r_Mp zkTY{k;;l$;;2Tm;-e?Lkhh^Z|xVrW|j3EVEU}>YH^rH85EWAhBa<7p)0CQx;T^C8u zaD=&%)li9uAkalFjuxw%m1yPLh=ZkL`r9|%Juq#blB^9`VFfC$A0NjzI$wDwUWd%2 z2bcX!!E|Xfa9aIwFHX7Z^cxJ*xt^Hvm|%HbN&;$T7Y^(0YP(o~BhN*&@l>kL)F}|) zTiS{o2IY6{4;?-n3^M4p8xqVqK zDe5{2BR4{EWwbua!~D7*BJlM!ej?oQ`o>)tjR(J|pr}vJ)~dR5n^8tQG@?C?V}EP3 z_Pzwogw60bWRIh5F;+QWSaBWQsN%|vw&mmftU(tY#0{*|gKM;UNw?`X&e#0toT@hl zAKCjfV2eQ-Gdn;5>g>D(D(t=Dc^5xD9VNc7TSZO4%w)Fruw;$%{^Az{^YbUd9@&Zl zq&9Mh78H@x%ttLm7Z<_uwZ-76AkF&U^kno98q3Lc(_Pzndr%%#W^_%n2jWLY5WSwV zJO@gXn#*BL<7cE*(ybv>7x?Tf74zmJPS$E6w#sfg*PZ(m_C~Z}?f^ibU(b+I>cV#4 zUW~PjxF~d5+3A^PXB02%G z27CO>#~$JJDw}J3@`w>S9`nW?dj%2xUQ-BB!>=9Hatj3ez5AvgkdxR}_!rak z0q;y}tJ9z?9gDk~F-ljx@pTbd2OW+#2K~>aC5^R@gf|BQ-gP(WgJO;DqY-I07k`b3 z^&6(+Vx36dDvDM9iF1tqaK+8mD72g)%&F;;P`B=iKjDQ*s)wzRgE{!d3>c=)JNrRw zhvE;m`1eiOYm~jm%NeoH0pk`x)-2^4n=@wYTQ+5FKMps1(^?jf84Wb92vSes_e|;6={;<*EiSBR6@m1{ zTN(M*kyB>f<9p-Ou|H}V;=UNPor9_d=A%4WVZQly;Fo_T$*QeF@i zKoRmR{^(H5>3Oo-fGlQG09G{b^IN2u&qKDRn~&s;U<-|%=$b6kJJdMBR&HT-NzWSY zOOoR#wA6duSLAkWLyb|scWrL(p&xLuyydKZSHufK9d{a9slWYky|>tYyo3?=#T~2m zK3`b;JD3Q{3O=u)U|#x`gfR>pfMCLHcgAShk?e|n)a%lcnUqsEaBw*yOHF|{$MRB4 zq^%~puZ~R>l|;9>(lte*&g>B`lf{QXWbl(&0uvNi z3K=@9#kxA3c6l{Z&RsHn~rk=sqJ}Kw;}ottc31Zd~CsAQsc!F7@am zvb)3Gs0Tta?(2q^V|sRL4aT_SC5NhAsXnx4eP0;q!)G-Tb zGeW8n<{Io5m7?ShYs8fo{ni2cc}t90gzis-5w+6*L01$QqBVWN9QKUES6lm{J7fm5L?WyS&r z>l4hW&Fx5xt#@k!X3v^BHeZTAGjS?4A3L8=ulH&iYgiE6Q4W;)0+M+y%1E#zVIsBX z5oR&ns^@tg9A3LGFmg(h3SoKM;47v~A>EEYXm-#eb{c&w(>|8SFT5|5YD-~1tE+Cx zDQVILVGl+yDeIW1$21QV&8xSqGnov&C)hV%;xJAl^z5}XjA;ETJLf5cQ@*gfTUokN z127Y$uC9n#KbSLxBu!Y90MrbhqwzcGwF|L-+G!sxh=I`?)A~lg_oqfrI7qsM@$1V` z^}T->qc$_*bk;#&bRrB_Ny-cMYYgEp7aJA_vt_>$o&PnD9;aeGfv@_r5Y>a+$A!|b zk$S;S`=5QeT3bpcMW@%Ae?I3jc_uJBG$QBEhmlCDG{zfRp{>HE)G*bw^(t4EyO(7^ zO<}oFJG5Nc%?7rSk+#Q8mK>NLYD`@tIiHqb&{R|A;Q2PB3zx5AosSAP8FIVs<%#_= z@|d+V(6^L}V_SA-?&ZA4-Q^{6+!CI~qn>uBt((n5R1Z{+Y?8gPD?dd(8cyYV#J={y z40n~+S~?$*VNL?hTH8teCP8*wdUc>)@I&4vh)L;z4T8pmnaivNC2bxJ8vi76_>t^tv$)Ki(~V$xVZY)kjizFFKgwS@wM-4=-sdYxF!R@TYBs-( z0sU@tArelr#@8BiYuw2XXl23sF z!jIoR`^vVO)N~TZ52TIt${XJS7j?|qDaQ~grTra7ezJlVHA@hJak<0?Uz*9M&XpKo z6f5L)`$%rT@76)`SA;g~3uiR7Oo7WQb%Mh&G#WerF0Lf*540TT{Km5yh& zT}hHP=X7=o83~TdhRE4hZe_m=9%B_eeU8uV6a8wXe@vAPL_PBOdfG4WKM zKp+0lb!l(e=r_KwELTsyFxw>M9=2KJkdGs^;?BJ$ltpxdp~dOtPLv0Cm;`<1djV~s zC@gyF6~=-{za@a@q$rH`CiQN6BSrbC47Bx#?1677!b&(w0FgW2l@i)m#=_1s!QllZs>^A+w)R;EwN^m#|K}Rh)&muKt0(pQV1CB*Q)v(e*QV< zz?=1)tq$@;UND8p-5XtSXEgdhNhI9)UkqA1p z)7EMu7XNuSy6EA<|8YapTc7AVnNzw;|98!nhQ@+hCndmu87V90@kCfojun;#+}O~O z-R-_1&e?-6Bm2{b@N->NT|R{z!>_1l5=0N4yGA!$p!=gGo0xul!SiCdrJxU~qsjG% zm@d@SVQrBCBbhiRWCPK~CL>})ktA-NekJoMMMhZQa-TfRNl%&}?uAYLZGmnZFM;)3 zgsTxr9Oojv66ljB_6lw{gC{t^H}H__#*^!Dn5}4wYwwo+a=Me}aHyw%uN1d}o8iP{ zRv$b)m{83r!0>pjk!8^^Bb^y9m?q3hz+SODN`Je9_rCnJ65ru02}aWu+9R0BEIpl7 zP)N8^ynDUD**a!9y5y zh6USSK>3a@HK;FomAXgU#&Ci2PztFxZ;(EfA&ZdEne^Uw8DC#zUAws)vq6A2*FRrmh56<*Erx7#7lCj9Gu8{5JZDNak!7}YW?@` z64T=w44%}>1hc*@=@?jQmt)BHc@Q!;P25TT%I_6L_w4r_GHIJO&9gMv3{K$tOU(`; z#wWs`8~s9#>JFbSjz8^PFp>63^>CnF+)Jc?^<@}Ctkx}Lt5Ht22#ha3k*55-bB|6e zX_>s|V;s-`xRIK89cktO?)f|mOz@$>TfXKTWYBS8Nq=QBGgZQREK^U3~ZcJPxTGfKK_y2L}HI8CHJZo;o*|`{Wf)q-!sW?6-+kS9gKDv zEyFph>CL`=bfy(LZb;H3zPOneuj&S zX|X-s(b1m7Bogml#+7SHs+3h>KbDu}*4jyknM(=TAP2qL!iAIa?7cD-x%Tl9-MaY@ zPY##kHwZjmw?|!vbg4RIF6ZELYtsvyAa*puVlfa6s0kM&t4*SUCZ`1C#{zPs-sjZE z$y?`B$6eO^aHkx)d|GH0)8Sp#xoE#5E&iI(HBQirDEcQ2f+UW|2K>QNJ)tFHO%7a9 zDY%}Fz{=`P24JOyXBRck`mzr#f6)Lgx~dbsk)d#(TGl&I@XxGAL3ulQytcKnp8QsF4@mO(M&<saD$6 z8Yecdm=3Fq35b+>#`M7;NoH3_VR^4 z@$T|bE@a}-aJ{Ds0;_a>N$iGwZt+pw60D^Un)W>JLDELe<9}<_|3qaEv`F^ll@iZ_ zWTh620N5lNwKI;}4}0V6#=<$#`T;*{G43~QZ;EK@&T%mZquy+HRPyj!%?xLIpj1Dd zHuaNYD2ptp{G4OD6q`jOu(gbYd4C|BT8D-D$vaD1S)#n>-*d?((woV=I`Rjy5W=XEz4(%Ddp z#9a6~FuC>45Hi{764+TY#`BM_rp^;>8>_yo&ZOLxhJhB#b-ClzfXuGrRS*K zx*WI{n61WHvn9s-NMy>XN%^nqLxkuOgg@_%YR@c-9~UbJ{UmeupK3mS@>9&A^$mhQ zib1YrvyM9N)(Bk0Nj*j2_J90EzYN$}*!vMYw9UgUPn!s$*yIlK#P5Q1+hd1xDW2!b zh{}khy88Jj(^Z!G8@H_ZUSQZZt=kj7N1cL&JahfxXH}CEiCRkGx*S`Cj>RtU?LNh2 zuBs>|xlTKa4Jw+*S=oH)d4=l3*_{JxFAPi>##s7>!~N-pnMF0rD4iXrK8VoQ99zUi z0lM(Epa5a&kat1{9n7Y8muH0|FTFY7zN`w4Q)j*6WS|IvvbY8PklD9Br4i>&9T|Be zTJ&w9qE8v0`;_-BG|GB>2Z(!O6KYfqg#-@mgmM&)xwLB@YS;A{uFv?=O5 zW?@^U^KqCXmO93el-qf+5S2%MP&re!^%zYqqa~6|ItVJn`qOs$c!?H!=Id;O3~`Eg z{HK5FDv57|8uAbJR~Q=*-y1AEttSqBuF7@=@;l+m^HGC1!Hn0@2&(t^R9x=iMzs9B zQaBz*qEql53_Hr&yrf35FLaCZjmP~*ZB6w%OZU!eA~i{Utz<37VV~0A@$lP z@$%D}S#T(H01Ukxj5ZeVR6a^q?!CVDZ)Kc=Ys4S@ni%kZUy6#$(w>({X+4anq)Ydq-clJb19TXI)7vn-otP_Cb%D+R3_;0OTdoY=BQE zxhn1V1zdFf^MEx3OG*bVvwd2e^q+f{Z}$KAx(cYM)~+pG(g+9)DJ3N$FbqSNij+uq ziPAN64c({+N(`ye-95C3lysMLgM{RNxL5Dh@80{b#bO;;XXd=;jlG{;&qjSd`6Lss z_jbCLe^Y9I;PUE5p4r_@9>#*FJ#Xr_F|c*O*4Az+g}v+1E-eEtEXYVDPeQ!Gt!}T5 zN7p|g5aXE_eDy$3 zgmC@=rk_x1-{A04k_+S%Xd~CNAEnwL8uF|#sz*^LRMr|z(Ds!pNiAr*tLtPf;XOTp z@oM|wW>r&$aYa?hR+8B`L%?c_YNlY2RK+!oL}+r&nxEm~xn%|cDOT!o@#bC3G*!E~ z=WxE>gC^11pyx)+a{;_uc9nB?hg(q6TGiX*h|FQ*fhy{GE_H=?jB&Caj>df=_|)*K zkX>CG-*n9&V(m(~lYDB%n*`##xZ%Z5G&eWafe42&gg)Ro9Q%60Ezz3I1ZpI`CSLMW z8~A9rQhd4Oq@xL20IOZ?q2D6}(7Xy0?tq%Sxlo~WwT?y@+kKt3GX)(s-Zef6nL)h6u+Y9fN) zz9kO8x#-Nzb6d|T%o8bryHKm>lt&s2II!J1B!Bo8=M zWTH(1E3U3cezkC^lz9_p<>=KyVzS>keq`4Bqm(IBazk;{h26TM-6h)kQ1q)QBQ+h6CbK|}v5_QfA;k(*wwhC3w zRbOVT8Kn32P~iuAClCH0ozM?LioyxJ>H57A7BFj3A2(!%4C26CZ*9B8Q6C_;86j#E zE=2qWB3Z)jW@sE()$->bns|HSkPx_80MO7rBYgS@kV^WBLZg z2`3$(Bgt^X#9gqr6(z#9-Q8cYjx6YHNIDf{U0K-)D?N=7vx%0gjh^aZ?J?Ju*x1M> zx|mAY`z{=JKkhHNNeWbx>FYX*Wi2N49%ikf?_HBMkNB}YTvdG!_AyaUGZ=qVP7Ep1 z2R2qZMb*I;YGBSzHQ1xo-`&7bu3O89XM3_r{-I zACW4)-#WZ|r)6!gWcMViE^iL<+zZymwHA!b_i=sa2^(tAZ*jR)GG{uRN+j(W+ncF_ zwTL3ZHAzMUGDIYfyi%4!M@WJ)V-0wYTuV$)e8d>iwDpohRbYQ7 zjdWX@f?{J0F;NtCw8l9bdjCjztv#q5<}`X-zV5nKw%pp0TL$tuwHt;o5TxNlWte6f zVP=)#o+KP44bR0Ik6Q7?O`x3s?PgxNl&cI1{*?8_ad|y8I@zg}_!9>g?=jK9J0E#y z#Es_~X~f4llFdph+kNUQ;|i;C1>InGzJw`tUF>yb9!BP72=t9@jW<O|=<9@g_b>I1lsUY9vX7SSA!kO7)dSW}1?2WlwazIQo|7;YWUI_rel{_MMOD z`<)7o(Q&K7NPvRzF`1|Ooh-T*Px?_KQaenGK(t$7z_)su!6r}8SL+$(| zgLS_O)1qu5guo`aw8zEf(Z=5F(VAK7_{I8pW<}8UCTHV!2h0&g1!q`Mhlun}i?C|# z#C{w3B^m{&4=rC=fwoE$0Mp2w~s_hc9)<;S$QbRCRxQU-ulAsr7!D~=W0qC@q5i5vv}w+*O001 z=>E&zo%9J|el!))yjos%?~Sa~K~@<;FUs-5pUEoqS3iZ+7?<|*FIO#W_bxX2Ky5h^ zbzI%ajj78x2;QWbm7P;irYa$YvMTF`WUN%sTQlvJiMV9@d&P^USQzvzq*&3%#Qnm4xZtqF99O-dxSZAsr?Ry}e6olQA9*qaFEd z=Phh^A?lX5jSYL&Ko{UY5imCzoa=1rz2Wjwq~-990KDF>0bGGC9Z}*n*S*xJ zd3aE~JDdsL+0ky&&=fiAlI~(|b;YSbKijS6S8fcMD`@-iLAH$|nqN~>F z5913&E-^+F0o^MY_DyFt{fR-aC4+9)j&{h)mPQZoGL1sDNZ`E)nv3Jr^u^hrVjMZu zMmx}qPk<%Ew66h}sJhKEsFnzgYgW63g2>(g_oOjk!W?yT!R5^K!C)_V?i8y4kVf1WJub$eGsWFyvXzZ6r?X>@3(zcqx4j8fvT_H- z#I8$#n42-E;fTihVGHWT^iP}Vm(U^LYSXnt<*!F$n%28;e70hJ9s9B^<#H@d4p)4q z?>bgek8&eyHoN!al~hj}b&BEKm(LOB7t3O$tS;MHE^MYF`n3zKH=-MkCq?WbLGaBZ zpKnam@kvmL&CJrS%l%v>g!qD!h48sHkmQyc;6F_BXzAL4O5lP#$Zi9tq5_P9y^u6) zw;wT|u+Lfc-nK)vDB^88QINkjO~jJnA*M7tSp$ta_^o=h*E)m#T1C&UBtNFL-!R~QI3ocW@Osx0GDKpx1Wp_ zawmmH4YTA1D+omQdX18A75<@VDI&$sF3bhal`dywEaS#iWzhYIwmkRi3n!?L3BZj- z&o0jfQYIYksmq`b4rwS{(Su&B@mx-&b*HW?I(h^P0gU(3LxOGuLcunkeu4dMGN;!@ zBn`X|gin}#K}cR-p6Q(b@uz{!E10CYU5l#!2jllVn$$<RJDzAZKPk7yOIjHw|BB*h9%1ac1q zI}-whRd?&}whAe}D@C}NV9`W_KdS^AgM=2gUJd}1g+Efwdsx-`e{uo*^-tm~Y1G0e zNU0G-T#w@V1|4$XgO~b9pX-MRpd_n3lzf-k($YpeKq*y#u|obQ>D!ewOLf4x^VkpI zi*93PoxgdLwgf1K7#r74cM#4`)_aCp4tOkE&_Q?fdAw~BRPn7jthi0T~Y6W?-+Jdf|ss+bc=t!L=xvzY!BiyD&#r^ZKXo*^ zevbyWl2clltN+hLP+;FY5rpsG*fE4MUEBSfysr3>?Ssmn{_G#C1}|lKAw~1dRA}wP zT$%(m=w>kwok&G~{-73}_CdIBZM8hsm!&Ahs;z)Y|LZV(e8xZfTfp** z!MKd{niLZ$smn9@_~N>k6xWGzodW;kDOk6zrKP#Gn_xfCAsIb_I9nUPFCRv=E&pcwrtLT{#wp~kY@~gc@+#j>`0+Z=;0@q zA@=Bo`MYffhzYGB_^*%rah;ljla%Y5ne!lb|JM;y_#xGAo8g56?SxPG*Vk~zTaVvz z&5PL1|1I5gp{Q60CyR&8pmx1oBVJoY6s1{lX@)7s*{qfjjxgt>Z~}zWp;CjPoFpRL zWowA>Zz=Or1`z`so+LX@2FBD4e&qE3;T@b*sCD&hd%Co=5jnCoIxF4?b8*qSM@|9y z`3-Q5`>B}RLIB4d&zH3Do`RStp5dkvD)2T^J#$dI)j;BE1h~$+-(o#_u{m4yzZc2_ zokAY3)isyqN&Sn(=8H`u0~Et$e0=t^cjJ`|7jGjOz0YE8=vtpOAKaE zyWjBmG{pPISm1clzR%T@#m#vRKl#vMzs7NXIFG15<^UMvfsJuCR{%*)>`89v!C0$E z_-PaWI?cef!Go(!TgJxybzfb>;4(Hcr#)82EJtJExkk!glcGb4s=!f@ef+7cJx; zfnZ2KNdzc@=>}eMuHvc-hEGb(ea;4#!g@EeFRF$AvNr%38hW*1_o|cL4?MRVNj>08 zDSkwY_L%bR<6p%Rm<~1c06!5Rg(>bQUSHp|-{;wy5=-%4XH%0))nwCjx9nQ;Z^~Ie z-G?M`x$X+|PAINlp#T9CTo?ha6J_WPwooTebCAKu(h=%jm5%V5@x%0@JED^IJ;~z1 z{hFTJLOUCqxf=g7b3gu67DDdhu05B7c8o#}jqT zYMAk**>bBCO7F_YB9UZoi}*)N--Rvlh`}sy#)j?v()aRd=1q%uRqTb~z{RsrY+Yqk zvPIVdpAJmY$~sXeU%mdRkO{a1j` zbQ9@q4k)6NC_DtPuhNoIc0xopq% z#M3!24me9m)F_a}<9_uE%PUF(I{!s$RhB{CUX{#i475{DE6JtHIY2Q15Uq^2Moh5( ztDpk*3j^Ho#*P(B47t>!rt*nOZibvvYrtLf3AZRr{kQ!nh8nRPQkXZoF z8dh@h7Pn4Rdru)TK5!~qV_ea!8Rd*P1*HNv1$0{cOL-&miFJiX-I;8=&E?Z2KH=~)?UK&YBCy)0_` zUQO{_W5}9xYP3XGU&&o#DpVu*?_(_lzeU4HK@POT8e(UizDW%#e#Tjl7+rYw`H4E( ziZn#lMyXjJ`II$A;Y1b%MHpw#zF&x9MY?9gwYURIe#}F5o!q z*=z}~0azrWZg0{FS_x{KK}>6@D*Wqa98$d6jM@3GWr$T?Jjl$?uC5**+ddQnXy%Op z+KB6Ze+&DoHRM65!DyZ5;C^W7U_2RwiIrc!S!|6Ixmx#daev&W$hW;ca`2*=@(W8d8)^vCCj319?9UL5ve%yI6<*{RiaiFZ{HiYiFFI-%+rt4}` z=e(>YxZF%5hIxeOexx`eNwE}>#Xu47OW{+#oFHWsMHje810xDv40p5GaW7PUTk1c$ zl`bR*IulLzh+^#lFiJyd)O_J#)oSc7r{xz*HHqhH{}x$#u6^6;NEvM%yn#1}IGyW# zvxP^Kk3G~gu&5@#=)hA{F7WHigYmA!R$PXPj+R#WR#$uwvSz<6^_BMf`J+pNx?GStcK_B!)3U+n#I{e1EGr8)L8!*yE6Pci zIQ0>(ls9H)91sjh-rpYrqjK2E#Ul)gl(Tvj&foUV)rVmxk;A*Y6+Cv@C@QYmkG7WQ zW~yzz&u2}3G^hQnh_nZDy+^9T2QO63fe^1*WKvums4f$T-ApzDdKFA68_`A_{ zatxtbpbUH$Y2AV2_7F9>9(2`R=-*6iZtk+L7GdEid&f8B;PJu1{J-tL| z-`VUXpN|i(1$B1BYIP-FM?TtL?;C>DAo)|iX#&REl%Ae|0K_;vT%P;sR}PoKhs3TD zs1XG?Qe=mTDVLKc!~?^VU-tYw)Tf^c>EelKhmEa0eYmR?>*79?A%zWy67R3Ez}_$} z{M0IpVk=ZRMY{fazHo;RXr$(u)^kw}P%vm9qzDTB9WDZ=_KhF18qf8GLHIa_qWSPwT#rO4lCC%~f@C7HX+)2^W6TU77v+q>H20@lr(>j-Jh@PgTPP zfM^c+bQeM7@N~=^=$~wrK@zFL>5#oJay*fO~acsfj3?S&eiySf+ zH9VkM^43PXfka-Z4%^^Zv7h6YF*-My5y6W`Km)_i-}PJ2YG?o5iUV-nEAiC#`3pW? zY9c)1t)(QK5o4KrM&ZWDnroI;e}$hhQL~Rr z@)gALf(mk?Z;1QOhYb&_FE_Moms(42f+lFnVj|cGYby7HSIpz4Ojb#(eJ$0dn13_t0Fmj%}j@rCjeH{M2&CF$%oc? z7)@jb{f(%85oLv+;T>`>rXP+?MT-^3J{w#zH{a|@v>k69Vjt~v`JSkIB4kp+xSl9L zrv#)es!e=0JusbmFP6LZ=XW6SNDUta(6aj&>5lIVk$#-5)i!k-BMF7A<612{WA%R=5m=KCyqK-)N>LewW3Ip93V@3*q9yss6Ida65n(5;;1%6xI3$uQA z7g*WXF&>?#5*i5K?R5W;+>H4`%9u9mm+-{{%9-aCE)BOYaweb4ajU*LGf7|iR|6&l zSxw>!oYBKLB?MPb_r&c@uww z)@G%(Ba*uZT;VoW<5UIVdx7(2t3l&h66io}wg_DDnlXsy@U}9^)}Ud}NW{_fjkVbu zjV)wzNnI(bf<{22P5rrT^f%k$9~bgtG^_nY@2>rkX8EhA`SZH&E-Hn^EimHYL<|qz z_{O&~jM^GrLlHv}hRHikUpp*^TAFJb8k*MD)~8Y@x?WgrU~5ZxU}3I);#-T>U~13g z^a`)W_IXwiMR2FA868Wznfg z(pOhMmzOuH^*#tA-Hy0U_yDQOynLYsi?M<7Mbk~3eU9)VIYXW>Ot0b`xQ$5GM~qlF zj7S{d*OBKq+A#18sO#hLJ7XGrz|~!NT@d(?F_@+mKXEn5`kg%&I>lpsy!S*m%DVA^ z#h}3k2#Il>pc0CkqQM}gGF2UbnU)2>&-`J{3aqW23*%lX&oavfs`5lr}oko_Qub}r#*E%Y7-rcYG~&{qJf_zs^73rjo9e)MhcTZvx3<3 z4=ySvwPfyqZ|soiWBL!09c2AA{j;mE$-b%f8D}8!_6U82=%&B0DHzBmiXjyMd~cv* z(VCZ!^gq~S<-d6$UaV}_^UjIYEX^=@L^4t#a*HA81fq+F@bk@FURob^S=igIRhw9{a4&=tmmPQ4L;%^J*!kyh~7oQcBKWZ%7alSETTezbZ1l|n@H9|l*4=%0S!jJC)$B#60+(eCMJtKA%$f)_nN`W0GezUpB!;k>MHJxHz#tlR90JT3EPzO?0K&h*%li89 znc8%lfy6ts{-|Z##c)T!7~ih1jJfzHJIN0$4iA@0t-*kXh_k(`;GWh}3I8$AseagG zciFohB2^{K%W7&!g7-Too6`d&y@sQ+3oAR~fI?)y)afe;gJdW1O^X^D1UTQAKrmhD zxJrBhZje{6S_j3-ovjxtn$urp40aC)Xq+is^8dqka)pmV#ntd!_jDd~sUllm)=x<^ zbvd03s{fdrs#)|M!HR2@!a_T`JNxgJKo1NpIn3tnx4!CBSPyhHH+7}lezSX^;t~`c z@ZrW4bW&y%*8nNKLlXqa8pO&O8tFyS1uyEqsa|`_I?OJf3b16JRfjj-2K*IsQNI5! ziGi0BXC}(BKvCj-Q~t=ft?k)RWtn>O_a}5eCTUiZn9Xz`PG6_kSimD~{C#@}GMr?# zdrs2|qd*uCA)7h)*8}oOGg?U2!vZ~2g2sV(aOxh;j@w&p*7h+v51Ia+g8P}|#F}=~ z*-f5;7h#ehY(@kTt43HuI#8bNbVvj9Op9ubiM`Z%O!$|v`P)fIO~83l4$!0fbnc|X zqB;~%lPxZIm1q9ExhG8gsaN-_a7PCYAr55DkuJ7!UTGCsF-Ht3`PycAS`*Myz9+Db z;L7(vj04uV>eS|8j1ad*;y6Nyqba=99|PXokh)J&S*qVm3eSWBp%<3z2D|l* zng7cJ{WoG&2BGI@BU@CH^h338lNS$PNZ<_$KIzcX;Q8?ufb_Fkc8m+-o>0H%Kp;23 z02u7pU-#X@+tc6957Vucrlp}ICdU^)lI?kHE~m#2ERZfbYPnN49L##Hn4nEapGN&b zsuXc=L9U{;mg8!YKX$jVkw%s(txq}YAV6S7vi3S{;Lqmezfki0-1Ipt$_J>)#@yze zAJbtG3fl5YSvg|Y*Xn)hbB-yBNL^uhtBf1R0bqa0P32v>7m<=6+TS77%K)meyayt7`{;onpCr*CQJIy{GB=f%gTu1!;hR#w|Z;!*>AFUtP1i)LNX*~TAmcTZrl z+#t?EM_qLqZ+^*^UMi56nK=;@jLEQ~)r`Nk`EVuq?i)EncWtoW4 zk(pOfaPed|hvdhHvSd*wLO!RuvN~_8o<&aO$)c}0Vvvl&yQJ@tJ90w{XR58y&KUr7 zWo-s4NA<|%22kA-T$F^xDr`>HzFl1y&^dU{!>3u+vvEDof5wGu@he^ga-3&)Zd+2R zXhCRW2e3TNto@5oTI26U`4|u4Iw= zf-~E@k6Ix_tFLuoRRqJ3w@_ZiVr*W53-4N?0AawA^{ijOgH^bV<^6ox|E?^s9CktI zw`SR!rkZBIJ~i!crX$aL(WyBSYpFgm=n%A`_LCa=2{~Mn#X2;;gS_@M)S4^UK0~Qr zG8PszL=91CowpB{H35?OO#S`O4_!~P-#=z=y7Dr>9hr%+`y@J|8~qGB>W}nbp2a{D znU^B_YN%V=vs+~_ zwUDo^mwJPDp@{hWfP!p7U{WYvTw^K%x(4uEgcWOCcmPZvDuDQd*Aj3#_xV3=y`c+p z2uugmnn_Uw!~EFT;jpS{ZRE%wiKc%Zk$?QA2nIUaVfA8Q@()z)zE!dwBd2j250d2q zyA5f3Fn<*adAR+j)X7Oi3M9`f6}EHketT)n`MIVs#c58382*su1zgp{RLH{85@&sN zs{)XVz!A6WA&;H3Jpc$X0bk;Au|~svbB!#tentF+;yXt&!UglptAKtYkYzH4o=yp9ZKRMM49vR~rU=o$ zP96a9Ja5kL3;Jt}|Gc0G1*W)Hh`Qm0IR{noNgVkj>$lomeWPE~%PrQ|>Vz=$M7s8t zpJWaF_^6#0_8p6sDf-V71U8i9`)(Xh`H0r7w7l_1rG+QHPnxYpjp6|KWE6O17?Eo5xk463?y6Ca<=0bDr}vn!3Nl z2-WrW8dj#MftNg*X#zhQsKdh*uN`5y#n@p9K6SA(ai(_UtXj!eKb4;Sj6=4&PZZg1 zeN#m{hIB#T4pGS=t94vJk(>;=ew?_6T(DlPS66%H2P;F@k2M}1dFAz>W&~zc*`U@n zLLz0N#|!9mtYX^Mdi5A<>q`14hhGiQYZ}2oZ*8L;NDR*?i!?MezpPE5g0m#9%!&K* zaYr?$@P0yH_39vqWjHM(io$=fdQCiU0bQ9$Oy$QE;+&wg|3#KjQN!gaeVr1Ri| zmABax`8-aBFdJ7tjZBy((DbA)(uy`A;&25}(WdAT6KV`ULFU zKl5h(xnr;Xql^HCp53!wp#Lkrt3!udaWB)js;iIW)p9)ZC))Y^xkrmu#Sw6)(V!}H zcRQ~~3T}9aT@dTK6lf|LqzpBgE#G~k9ipB4Jjua|_z_2duBJp=;Ol(6PL@=#-j8@g0_tz*qp z+FtGi3*e4`+D+87al}VSte%%dEy)Tt&QO&Hhx1PO3HQoyc(>kYgTUSbo!7|aqBsD~l_G=qsXC*EV{HK$2}!d$quZHH+8pJ9f}rtZmx@K70*|JBO`7-lLX&b!C# zcye*pOz}>P$v|#H_-wr{|Lr}e6!**;`s0(Pl=FD6OQp+Jcj6ZH)xhRA4N>Zrd2}V1 z*d|*&ToWve<@#!Ar9g77s_0Pwpl^{zK;I2dC3Db)uB|Ol(0Y{0h%Ow_vX>4tML)>t zN&A=dp`XGxRu&Mo4}~+PxDJlTS!6=9EBPP z9NciqDk{fD8on!>HZ`8}t#7SX*MWp2x>j5F$5(tEXWgpEN_8(b7RuOKv-1Oiz$^^4 zoICxq&^lNUA(BQQBg`35lMZHm6R6n{-2$1-TflKQ&2{vP_I3U>6z~Iv{=`{eKS0dL z`Su(CHr=kY@K$Y9ZYXhL5@o4(>oXvFD39ESK2vLGXh@p|cuvg3PQt|sA-hpNYZD1n z8icQ0z*AXM{6Q#G-;#eiT2g}>TX&Vr2buBLDV@^+hnO4&m7npKN+ zhvV>WAjDzVeT*;T{68fC&?{OFn8{`0FYdn$5bP&Ts{(nsnAJ9KPwk7=+c)dm4V)wh zLdckqtH2r6>p01CyTix0#l%D{GQG0C%_jPALiV;vZs%aArt(|B0$ZCcP{ngWT#Fkr zG&X%BCPxsLn^K^ae4jO%GB2HUtIs;P3)lpnUg=BESbux;|4g7OJAhB?$V4|ee-iy) zo&HVq^x`Tm?!dVQzFBGL6>di)7CLjTT{57rH1N5bebM(g<$CrIs?y1jsMf}K=#!T@ zknB`8exklq%?*uc*lUAaB-sc@)H@Jsy%qitwH{^7w3mYo*K;1x>!1Jvb?bd*fCT@| z9Q*yqa^nJEiu+T%vhc4raWlgovG`Nwn^7Q!MkdyEUCGJcBn@=D-*`dg^%UK2YU*&Q zc3WFsXCfZ7a93?o)4-fbL;|mn89^F7bJ)@b0TL>4oaw)0!(BTf1_-=|Ddmw-(V4`g3rGAH8-mf_jf4V*Y`i;c6MUT>p0cE#%^$V&-E;5L}yk=4s*KFjm z*<-!jIxsM0=ClMrBnMQ4o}Tl04`NS7?b5v}vxSzcQk!-js4^HF8rp0(=m&!R&9_5g zJEiKA+(5rpCsd(!qwmI`n$_3g&N;Ms*Z#)pe~sbig)RhGJ>44B517A-Y2ACMou*&n zW}EqhgiuhFu(_fBz+GiA-@+zTu`1(f!S@ahg7xj?xrgV36B6?TM{VM*L!6Eq!;#H+ zti$k9MN!+pDPSA9Ng`fp0<7W7d5*<3?}q=MafBd4vF{@t8Lh^D_E7$F)ef=mRIs9= z^xjQ!Wnpb+m|v{~>WwQ@g=i*04Yw3B_`@SZ|rpL|AEgws#W}ofLK>$@rQ_SiVh3}gS>AiV-+qb2{JIDK zyuN+aDEx-Y!y$%WP8VE5!dFGisA{Kmfn#{;DxKMvUqGNC?8C}iiWdMd%YZRS$}ei6 zc85^#fj7y3?lrnDU(5D6nYsQS5trq3l^=9+Q~mPSQS?M!V=5zm(@c(yZuQI#Dd|OG zl|+4p=bh>=3M4ZrT7q}%W(5Nr9D zAi+o6fti`Lr;nnuKk;C}#Z!9{v=eybOnR$h58&F^ zu3wRkJ)8Dkf(G)p<7 ztYserGTwVqlyiwnn#wnDcvzwGF$0(@NbBd&?o!<{>HijbsWreEQq^15ssGjG2*yG! zKE~B`ZI4;pX!%a{@;07qo+qvf+d+B{JNcI zX>b6K5kMv`biB0Oq!5gU6zyQzjbQlf_NNytxt)u@4uC z4J~v`yy{_P_vVulnFnrmeZ`F(Q8~E(pHp?)_v-N3kqrIX)d6tF(#Lc|D3XEfuyw+N zF+iu1ej~%Jar55oQ8%k(t1mZ8Ia?Yz+%5F6u71?6EeuIAG(WjOJ3VV5+~_`R9fjb`g5GT%XR$sd9(|~0mNjeQgXttRP=WCIDK=bI0R7nxuSzZ zr-_}uRFObDLWJ8BAb(dNfYdFdW{sM<@4~7>wFpd{61#xu~Z*L#|QxRC+DrX5bRYb|3&6fKx%+nX;E#ik5J@z~!1c zD_h%%XG)n0_=lrB+hXOJUAeWnwG%oUh)&|Jxzf9&I_1@x#x7G2^smEQMiKoe@@5QF z+WN&i+IzQ#l3Y{tzb!8*r(ozL&WXM*9UDzRhq8Xi2K{=9OXaX6!e{0Pr zTyO<&NSR&QI` zSdHda&Q#c*^%Lf?k~wtP+E|w#l&hUmqNenEpX#h{t(Q)0*Lm1j55N^u#5vH7XBvc_ zk6^lUT^m6>618>Q4am>DtFA$P2Uk0&1~Pkp;F-p$$HQW6p>SI(ZENeu16bMk=}5a3 zsc|XPTd6+6m(}+qh@R1%@F3s%y^8t8BnA{kx@8Cp)g~RUUxIgFH3eme?HBCy`+;F) z1+YTr*mI@dPU!JNz=Gi9=F*}p5FRPeFP@uYNCXl^Vq--*!VB}nIe0|iH8l_*i?BGf zpIE+qAx=J%3k-fH!o;Lb4W8)YZ8ziU{;UlpDQ;hSN{!^L_3&_suYfs^&yKzoIhn@` zm&>RC^O zszgVg+lTL9_XNibffAw9T7U*dR0Kv;d&fJssMPuZ27j{#jqZR@&c(`F#nLStJdU+6 z|LvuI1(sQcsOG}Px=pi#{J-7fN{pIoi9?aWF95M(BHForcm&{b##!!NfdjHlWcO1~ ztJZe<$<>XOB9;(l$_yFSWUz6*gAV(8AfGCeu3b-#bc?*=Yt>eJk6MpBTf2`Iv-jsI za5>$vF!S-O-%Al`&dzdp8{2-Km_?^0sORYb0|p0dGAbe>mD};lV~}O(h}78k4?i)xxrz zOjN2X^qsYtLoKYt+CL=E0)CBEV^r33C}%3gpnZLQOW*+wPjD~V>3;Y6!Z5nMf`MG3 ziZpU@VQuQ2hWDLcLK@SredL+U6dMh)PK=m%@93rj*9`IchBxu>P0DaP zW@Q$^MEQaj^_o&kD3zc)y;=AJ?;GS0ZU#S}o=8 za|s~5*Tku=#zyv?j9n_&5ZSqAzGsejcooGjIVT?S@Cd`*!HM6P64pL_4Ty}ou0tIl z6dA&25#XCv@#tPD+O8aJ4>1N;0NV2nGBHh#(4aDkAyd;+ORZaM1B?vIMcdlaaaE@MLzdQ6GvYe7L!*+R^2!{fGe-E+s`Hg00*kG2&fN1tR(kRJQa3A75jB}HQ-MbAK!ircC> zMmFtQ#R?+{$Ax2BY&I9})A)T*r(`~J4W?F6Go<6iM<-0FY(O2C!?nn~g} z8v2!OPx$~ny`NIol@Z9%`PvHN<8uTM4>Hqli+*!+Q-GiUxoQmQ@YIx^1(CP%TcsTF2}cdG32wr&M% z`I~l+aNH#kdlnM_lMb#up*-e<bC;4nkco}U^Ydi^I(e|Y5-W|3q^7J9g+XN>?8Bp-p`l?bDZ7ib zK9-P!2Ko?Ksc5@uekPx@E%!XSuv3~*cJRk#Ds;$90Ctcu;?|_snPgM9G1TaCcbTqQ zMk~Y?(x*|g=QK;nd1f^rl1bQ1ei*(j=MG``6z|aWX=24$95H3r_B^Lha9B>i-c^Z$ zR)g+D+9k!ac&I#no-Qn?DtSKHKd=Yl1tMxnOOAULPB?KieZcEMI!}#j{YlHtXYV;i zbjp;MaVZh8m)ab!mKcWg`K*#Y7E=pECjn8lN^$f7(bB6ilnMKH2m$C9J1X>KP#`o? zTP^svGaG{BhC^GaoaWNddVz`oe0=(>oe)!VPjE1 z%8TwH{>NI&P#y_nL`tk|ARax$h1(<8|)J0CEQ=Bg-OMdxvfNlR3~PJc;P z@7#S+nc_YBvbBQq?2$@VNyx`M!p!A-0@OF#>7rpyY&mn)MvsPq?b64_#wtdFPOZtT z9j%d*IIgpjrKlaWviA0LTc`fQs)zjG;XdYP&#gfNK{CSvTsZwoZa^1zZ|}W1z1mRs z#>k2toga(k$RqXT9 zgs+^CN~7P@gR?ZvJ@ly*(bBiyy6?2;rk@??PguS0>2<=kG3m^rf`xd&rdz|?X9nW8%P$Xzm7$#NVXFZNieZ7nWP|wxREF?>)XS0o+f%aN9WZm z=~b_I_BcS<5N6#?E9!2gWd0OU``--Ryw1sjhf?X!11C&h|(Hbc}Umo z@fq(kB&|fB3BloMl=zM3~M}l2$ZePZ5g+RT63xB{PLhH+WKa{{G`jxel16$ zgfkwWZ~V)T`Ecdv!t|e}=hlX>_oaPYy1W?bh?BfWK4rM#yDx)A5VB(%{2o+nE4iWq;DNGJ)Y*Yc?CBcjRqCD%jx- zzLvcvBbn)oMOG;NstqOtOw9m|g8&-ub&v-p{ijv9a?m;8G1`0+5*KD9(xu&b5Nyl< zS?Zf&!S5fZ(G5Bgo|qDVavz!0kuw!4K3*Yd4PETq%ke_xRmSWHP1SD?D{tuzwt)b% z1fL1VcGaYiQNP@4Bkk}zg%Wh=>5d~_dRqn)t=$o1-pc&%h-aq4?4oR-QZ0Xu(r+t# z`}H*pP=qQK2viJo3ZbT=DQkOQ4{m*bUvC!tJ>t$ zVM#2eNs?uA1>20t>cyLWF&@i|li9d2E5ncd~DS413z6@wJuY`9OE@2G2Fj?%|0i_XaxHwD-uVYu7-I9yKAfpn6f4 zJdlGx&!mQEzcq`eaYxgI;d5G7w~pQCcwY{DrW&?y*?9L-BS%S6di7gXB9ENM2A(yZ zw`3ApgBWROO98Hn4RL}e0Rz#O$<3)ii#_9%^vGO0)O6S26i3`h%KafM4My@=htJ1M zvuhmZoI9-Pb>5Y`yq88gnpj==X`+r^GEhw#)Fh9$JV;O|Dq{_^nPVVD!TE*p;0J~$ z4`X|H*7cgcr)%coywr^tNw-_QB{sq{iEaJgfFH27qeU@)6Ww+M=qp9VA)}l%JAKt= z*Cmsyzhej@TIOIOs`TQ#a+dOVt-=hfPd+YSiUn$cK$|`10WY6DuUdIG=N$t#!Iin! z!Oq=$JF&bRJ3tRWR5z(BqZ&k6L%@n6lW{M#BF$cEF@xIDhF%xu$|aF!TJY#uCr?}# zlBSRAlrmJ)e-)B_qSScV%&uOw1;C?P6=gz(Lm{@qRQjhVTS7B;tb%)AZYL~^bZ#=O zKe)^f|By~fh&Q4lz7Vc4c{fCBp2n;nfYPV@WR#HM7_1ZoA{_)d_ZP zOece*(qodaH;Pr`gKLT#b26X-h@Tn(U4DBsEp_HNEbZ zYtW7C?l0j!6$*n9#C@^w;SGe6t>2ra;j0N(yqD(yQWW8^`&up5XoY`(vL5KWTyJUO zYzh9Fo-XSS$)k>fI?V~?D5vhXA1gno8dyOWN4b_x`MeS#x9RD(NJh!qkXLudd)L7o8K>)KO<7w4`9pfp3v}Zl9=rf~`ci#4w?5$9bUDHJvji-VNnHFdRZRWHK>P04Y z9m|(4@6rEbPcY+b(A9f&ek%Lf6aI(a7}<~RD&=b9-Otj_G(0d>zusJmu0b2yC1FUq zt1fmvVleI>9KG?WHGubV?hO?Upbzix^hO&tLRQI{p7Uc`rm9oM`Z zv=GvC!(gEB^7-QI)_|utvZX3dvWYZKIYMGiX^OX1w!@;2dHk)naD%RY`dd8@1k;J~ zR+Q98qCduCiq=Q5jQz^?Br2At@(;e1`=ohvIQKOzyS>kN-+6I*q+dxt>7O1Fd$Mle zHE*1ng_h1in8}6hE|9ur1bxCvX8mC$Nl*B?5hPX9Q;;KAtK z$xuqcwubZ7#F3PdRto*zXWZ>Z{TLlQ5f$zct|b^WZ#Ltv&$+M#K)JWBd(9r^qt#d7 zR6GD1wlQeC>+kYE{!ttFFUH!HTN`@iX{UV+yZ)PH%|<-xcg++N-@k$; zQfpUSI@(w75vo((0~SFp42_uYfy@+zs^K9(LHWzUX8w05sBc+XHTd}%nsEuhk*-tX zaA~FJsVeUSSA<_pDmGlqv2@;&Sn$$2B=URXA84HMf9-wwBUIo2e~A=@ zB9uLqEhHhk7L+~P$R1^1GWK;$B_iY{yBSGCV;6(5SN3fhJ7Zt7?>pmr)hnjgyVvI* z_`dvf-8=W3=XspxcAn4YIhW=xAI+kh-_rXeMRH=LB&vF~k~_DW`Zfc08|XrL!+CU$ zI%B!~B{+|W+YRvvm9;;xG-nQ7)E`^L&YG88>Pj@WV1Dp0h-#^A#5{!PL+4=GGKz;? zOESf2 zT-0h?TU&XrN4-8m0t#k}X7>`9hEI`v4RE-Dtyc)|rS6Hf&+;tA zog9-Urz>wc^-nUf6pV+2m}&{!6fntl zBdbXortkAan&iGL#<5lR?9DWYoEd2w=r${z&7eZj@E+&5P+lS=`kFp%mrsHQF+=9Y z+8Ar}a9uAmfAgUg!(B5=D^Uy7(73*P zazQX)K+8wJgSJxInhL8%{Py{Y0FxLb9=_C<;66LW1Drf9FnOX_xkt;@9psytE4!XZ-Brffx^??0(3dDmF78ZP)XeXQSKELT!DX3 z+tA^G0{!Ov0J|RnMa_HlYR?HqH#zy2HdOCl>0B+F-f%cs{NYN}iEk)B>eu(x=qpFh z$>}f^+^CRDv3^`xblg9kSw)IwnK9+XOMhD@t9p2ExxMw%#aDcMUBM##T_D-_mj;24 zL_RiYdC75QEhDQ#Bq)tRm^>Vu>E zwvDif2%8f!E6v%F%v}n0`fIRRtLU5)yP@^PHdEjLPVom6Rq|&7A~=t!J~~r_)pxK|1xc-;{LieOv$vlM z@T#>S!D`bS%`kY2i-U#!X zn6SNEWFyIjdE$@NRdmeF&&fACMnx8ERBm>fiVP`JOC%DPFc6oY$T}Q7NF|8HJxN^0 zu{GX)OjF6#wAwGaY2k77;$O~mysM!J(x3Jw#perGK~(E2EL1tNXB3aTrycnGGDJZ7 zPN}|1PJ?A6QI7 z&S|$rx6pMP!u8RT^egTw8{PbB8mZu1;e!+Y$*gDJ4^CKXu&<48ya{@rwBeuQH0Eb( z;H%?L#9Hm%M?ZxUXe6g%b->Bp^?%SC&O;MV#TnV~{w*Qg=ynyM*bb z<{y?A0j`k@$r&B_57?cZXP4RDN54=rrMHtHwbuoyxwc2pu^qwQF||%xH7YgxT41lI z2#SJfmW;625f8)ccLqb#S?nZ2%QwFGY`X5XYbQORi(8$B?2s03W92(qI_&IA*2|Rp zie~4NMNeG4eQFtkU!vC2NzzjZM%}XbQpj1<`uNP=%Cvv(+Byql^5Vx6GnS9r@#~P? zTJ68|=FHKhXzVkpFL__RulVjpsbTgOgQUBNrk+5rRMB4^D>wV_)`+zrhv=>pO<(pX zd2>sh(QG^f*y@|J@q{NFWz?IH4}7iFpm5Gc^pP^TzFQYBfwRdH9hg$#QZnB zRw3D@-!Sm4lZNID4mCYfrv=LwR5m9sA`<#wE*F^toxgwlx~0?E`aN~GNq&8Xl1eZ~ zdGrpJx*+Jw=EQ@Wb1#INVWg`M-sQd;f!rwl-V5by2EMIqYyIqdz$~6IOy@x%(SvKU ziBt`zLhg*yP`4*4&uGvwdWvB~lD9l?^`kRUlxDMhYpV}wv-zjZ**M5jfU^LGmu8vT zjCAL<-{OZ{`aR-FPb9fX{rLcweIEcg2CZ#{;}QLvN{E-9lWE9TjVfpeNg5`|bv8QE;Zf2*6&f8&j=}ENs=o5|o zR76WS2VQJc)1_srbG!rA*q4Jwo-UE&s*0=~Bm(t?*$fxS!_iZ$eK%)(nDZo(G!su%9-U^-yJ?P_?7G9ImW`@=<<_#14wgh8 zx3cOJK7X}gOfu}OtPIWEsX_e}_UmaUo5e?O=bu@5<()(xnpKym6X4a&Uz42|(oh&O zYf3|hej9bXts$QYRpzBvN(-c1p%Z8BHA>|BLzX)+IHmoQ9scRPRj7EsCsvk5x=*V;La4@MA_@5%UX93>;(|L_z;!J68MizoHpKkBxO z6e|o@`iwOntv_dK(^0?lX$&kn4RuRl;*)OT<*l{_(%CXc$zcZcyt4B2aDFngom%8` z&!?h&PYQSSC5BWk%Zl19Xwx%?A0_RPSx|nq8F0ar=s9%GQj`=BI19F`j)z>i^k_heMRjwIwgAl#y zF(;~}O{VnF*>`R)iC{OUF6-H0#{5yiw(l5JOay1|-ckLMQ|g^<Noxp(i6VK-(`3dXvXRlo)lZB z79|&mn3?vaZ<{xXOkxC!&oBru73Y@X1PziK?sIF^seRz|ILj*I7E1i40v>)z%jqwR zBiF*#MVX>x`b*sBMKSlCBQ&K;`HvD2pP*uu@jY^s2zQyaBG=&4oZ|jJKkg1%6EE%Q zcuy|1(<{sdHjyfDq+)o{ndqB4kK(~el&Qjpu zPO-8v@Rd<@zljR`=bP7^ICp)nRdZZ1l|*?6SZT2OoAneGn-1iRVA}^+R?$<)N#y@mGe4?$WVr`cPj^Z=-KInuvU*;XqMSXjr=yi3=gq4=M5rLa;xIfSf zaeZrR`Rkc@&2X)ry{v1`1k>sHwhtd=&-{e>uz`Kx-w6}DEEuh(pT3rM_&B?rh=+&A zVRdTtW;O)EDCKnRB?U{W=Fmd}gT5(w^Z@zU+Swej?JbkR%2yWi-5QogtIv{$bAE66 z*DR{}5pgeQ4kbsQ{WaGzImF;|a2`-r)k1AX?QDb!T+J_~qwJ`yq@=(~bsV-E$5EnT z9cL~1#|FEIjvj^c$~ci9B8B0}R_Cr7YXGT_!Cu{TGln3@R28iX9=E-e@xF6sbnPKm zq80=BC$hsg2wUz_-*0ftN$~J7hVSX>)@q@s#98!33^GdPL!|C=jE`W#r5}t+`10SN zxdi(j!DM!GQ(yk|i;vDw6l%55Y18U;A9LtuD0H6@dU|@Syt_N(e_`|M$A7m%#t(4P zM%IxdzbJuPoh@{5y!lezP8O{n5~W&7L#j1|Or8~>`}K=onEov?*}OzV61Xo@$%iz; z_m!L^pJ5SWl4(IwR)I(ei}(fLPyvjKU_$BzXj5>o0%w}l6-`;{?t8o=!X~+aW{5%1Q-YF0hyQMy6S9<9Sw2X+$o z9vp5sB1*NYtkiS9basM|ruHbjrM{joesfLLJ)`6dnk@9zpKyg{hC&2X(1+~Wj!WZYuP}INfX`(6=$h_mFA#Bxl10kQG-VRHZi{Gba(x*h@dPhhi z>7qs!k~cii)#ERGHg@p#-GzOh=?Mogq>^On7c+xeA1G)k z7)mc&F-mz|(;7vl?Kho7)S##+APkQ53G6=mw=cC(|igV`tTTUG-DgFtaK zk;F9j0?k&C@!|od1Q#!kgz_IfV09=rT{Im2DkzG-W@bje#A)g7snbj$$;rvw38=|F z{_L1%+#1x>4vRbH>j`{2^GSl_0_FOFZ#4w}jJX8>%x(Mfssq$!XrYc1{FT9)pD(Xs z0!0kPsY%x;=OU4D69&*%Ik-ir- zhgbojK1zj|#Q};sn}1&nnV6W0P3Eq+%Ntud2=IBYJ?t$L3cPeuiT^{sNvq=n-Bzgv zx@W&&{ngM9r9mW7cI>cYmsb@LX`RDc!Erf7MHlQ#H$527i_xsE;(2!Yy36WsaA+Kv z#sJ%CiMbk$;qyqeN%$mgV*YU>jV_Mx)O|@CzgRs;Ea-ZzRsX6dBRM z*In${8Xp@SFn}M9au}&^_e>$%Twa^GthlTu!ub+-TE{S4F^O-)J(aA-nrpC&)HYea1MjM=9pW8I?l9X~tUx*&^ua-p(epz!62q+k~?K_sb zq0$<}6S2^|x;V*cA26@Es2y`*pEqs702@GitLXFrqXHLXtbj`QRn9-qnb4lIwddRb z{bOPefy^kf!J9R!o|u?iA0MBvwoVi(iDeu<&wxG$;xl}G%%4);zNcYpi*Xp)#EOyI zYVMDZ4Kjk4GKyRQcPY80ye#jJl-p;Eb>IZ*UjHEw0iGwQHWUEH&Kh03azGDsiiR^I zv)aR5($8(nWN*;eDiNh^iHN{36yISb&AC!jGxBwPkAB&4ImiAfYfld@NeVQA3=5PH zEfg#*WQ3I5V1#V!=qfew&xbS#DE{azTNbc5dc>2$hunCAiqjY1{-eU(XHWi`c);%g z4NW#?_pMfW`vGVR18MVz_i*C;9B?Buf`vMn=XNt{rt`U2f1933R3k z#g&Lwfr7lVkRmXTkN2E{z9MgKM+eFc7h$9peg&9y=)_s7L3chWmi>QzjZ`L)cxr7< zI^D%RF~8U3kcj)N1(>b41iW*+$K+!K5k`7OwabI*#3AHhAP6S@&)Qm7d#xAD*k%KlA;x?)H&%k)@qw2n?-SR1$X zW3aFthVQPW?JgQV^z{cG#s%b!`la-A_@RN>wI|WizX<$6>5Q+;2!+H~b^^83bp`5I zRkiUwT-8)nRrORdt&+K+_ho=LOwG((;^5!&alF}Y*H&67rBfL<9|9!?*p`k9wzjj_ z4y+-vxwUJ<3&PV0*$VDj?-7ApbD`^-Je(i?K?$QS{I}o5-@dL$9u&b| zU0`;c6t`B{1Etn;6m-WVeGW){n$7%JMYEw z@+CzI?S1?-o_v7*PYUG6Jgc$}CVZDZ`j_G%c$&o(EiLLLdo|KkwHes&lanFyrMoZ% zEqGB;kyS#`<{$lEfTl0|_6yH*CQ6~8xgdo)l2m`4QIDX)O8<;(j6hCC#GUrs9Q&QJ|@ z^NK%#A2dM>mjSjK3ij^}sya;8x9b=gh0c3z$2m+P!m%waJH!btCx2t9U*ZNdyl@e4 zs0?2enFGtPzlYW(2aSkO-x=y#9~ob`cSHC_<$C#g-%XEE;9A&bM58bEK!W~p;ie7f z67z^<(L)WRb@iI45EEo)5F;QZbq2=7w7Bb9#z49@AG+lMAy=!ynOPkUgK(f~YS8Lu znYd4fD72Nx*d?{&iaE+~9kkn|q{FxYFCJ}eZ4(nPH#m*=&?Ec@RUavi?rqsR&pdy4 zIPNZ5sI>QngV)+-mBQ1BeTR`DtDLs4&j9dB3wSY(8iynJoxH(G5@I)aeQ~MO6pTl$E!CM(8hs-z^Z4 z2L&w_OPA1z_{(!=XwH%9)NFcKcgX7xvxaM|6#cu2+RHc`tK9 zfYENlJU1JB=i@$?yUjMHVf*{9ROU9V*&VnXzvlgK1}IaJ@tv4{QF8eFogA@Ua7c9) zWOkQgnXo)(i>y!chhy|{JtbQ4x1rT%T@b3!6TX2j8_zlH$Nt|vsGEQ8SM>gtVK zsTG2N%jC23bzUA_awfrGLqb~tVUQo&6K|LKrmd})5eU9anroy+x4j7|(&R#xEeQ^9 zDqNYx;aEJyaBxa{K@-6}BYX_LR^HuIu%mu##W4wt-(((a{hbN^78K49zLcB z?WeA&MJ+i1tomBY0DMeT3~NqvNawD9EP#wzzCT{SlHPjlP#sLM{N}qSy)=7 zGrIQM1U)b9Tl6@keOt1?oNi=UkJ`ZzEKD1zm=pU&3a#+x)z(p>P_h#X5>~^f4hj2m z0yuWf>&AzAe&CY<1@A?)yf^QYEslb@K$(Vs1JvHeTGyolt)_V==C<*)WOsz6N}Q|E z@#*&k7b&}%xxTlz@B42R@zk_^QP;nB3m#N(#q`Q99B1=q$D4KG-QWJDTRjhftOs7Y z=He;ATfn!aaSjfL(-hrwyG9!oY2xFPs2-Mbk5(MjQKVUVrQoZ_W@Fl-5ngrAbZ1n0 z8~1%~vKv`5|J@NNqZ(F&s5%v(G<&Rg5mPFFIS?-*W&YuS@v9g=G2_0%AMfozz3`Zz zTVT~J1UN{=W@$=qe<=gsinWuk0oU@SrqB}%9R7W3E-(pswy|f+qp=BNoq{?&!(;$k zY!3CI*;|8bCX9@AHs7UKXl32ai zkqmo?INpD6783mVIcffIWbrsN`T|Bq)x426!oQzZK2ART(^nPQTlxCr!i>z1PCbad?t#}s2f`Y8Yv$r zZa5t8j0bdbGKM}OI$$nS^HoYN`*BiI6C((uvAL;ccv#)W!h5CBv$wmCX8J7MzPxnM)@-=8! zAWz2cvmw3e4F~Q5;e`yAM01d9OQd3pKqdNBY??M#c1l-wpV*!+VVW=5h0!y1(J2RWfAs3J z6Si*2Ys377=F zoL~?D!H;E)^sF-El$9~tmoDn=?4(G)(%^@sYmQ^pryrrpOY9VRYbY4SXaI``5uGgf zsA}7_=9DL!OBHQ@jF4G=F(wHe)gadfUB%KNm=eJiKs0nC1%iK~U+Bg~OGjtAhyT2R zOW34+21p~?Y#SoyEih2GbiZ#i`J^w|A1C|JbkNhuiv+FPvNYAfdC=STLd($SxTmOekW zn3S-4b!&Z=ed$ewhdaBSQe&mb)*Ss08xa2ei+}x?ycr+B`t_CjYZH1nP}o_u6t9#Il80gIDb@KQc!gy%{(HzS$a3csM4H{ue!I_3vmI1foz3u3{m#K zN^CRa0gZ7jSy)(n%wypB^f@Y{l&ia~^W=h8Oz84&?f*S4nmaP&874EiT89{Rxj_B= zsx%!YJOKGZWGg7<6%A~Q&3EIjKa5+HQ9?`naiNTI{(FwGMQ!Jq599w zm$3z~KduU8*Z|oh%W0y$f3N~GHYc$QRju4xXW0||k@gYYRhXHb4@%VZyTStS&v5H< z!u}#JItIDRiWwg_d)qJu>+>~O%d@#ulG`BMs$Yk|y`k>*|$8o7CD|kNG5@vz&P{nfLO-ZYxuU@{8{+ zI2-$=u`g`&Ve`-unG;j;`BK z#?j3_mj3OFwT>&bYAfpl8MTfZYD!8<)u?Ha{rIbZxH#zKa(a5Y&Cn?qyms6eI6bBQ zb}-k+oN!Z9Q+BybgCL_l={>egueFCOl&31O8vOF!siWYLCB#M)!0#hlh@i!h@@y9d(eTj5RA zDk!*!8z^U(P~T1m0a6jdB&lwhfdV$Xj*c+cml;|D`G1K5xf&Uebg`f{Gov&>hvu^8j{Tn>M_hcFI(@4FU)vIIW&F^4T}wfbg78*I0J%+`)GAQJ=>3ezIaGf$_n1 zZ}9ne2wzaIf>Eca)->3cY|6TQ?`p`ZtP_kfSs8CC1mnFJrCcPo)=%H{wn99X;QrRz zMm3APpqj6*%$o`Ji(hSPnZiFXGNMDD(_-F?^{=6uPw9A?=Bfu45^hUTkakV&8{PJP z>VC7ik3K{5PQ8}zlFk5UO;wx9^z#N0^~-QlTs`88C^o)Kk+&&0C#Jt)omX1HvH4msPEH5C!eR>}GGVaTz<%#-_%Ig=VreHLoX5ZE zjH;1Q1(B89sJ5|kaQ3ugvr}rWZqq0GtMAFpZ=KZstzk9(AbIZ3k;V3iLCp`^4<#Kq znb67|HJx^{8e~=RQa7lcdlqp=jrn4LrQMC>giUx&i{o-FG^VtV$-&G5(i;m8dbQH% zRUQ%>GpRtS$0%Crn$vW^EO* zou9JJTeTf!=jAZFTR!>?QwCq@d>q^GrQS-ZnZFY56zXNCYE=-Cc03rvS9vcMga>Rw zIeg#`mP-N+tgyoM&_A7@A6^!ei3-rG0l5>+H7S!_aku&I0N)7&jdi!ShI21FRSi~@ z)h_~{PW+hHRRrf=eyyrh-O>WSn)0+!U96*{!^JpRbuXZa#zhAn7nBnb^gv;{*Kxr( z&)Helfb71_YV8ngC=J9@FgrONivPSDD)HXlnAIcPfnwpcez7*%(0Afi@|-5g#DLd! zdso!$>&~J=j;^Em+AN0U=gPNM)JI)F?j_DE#yblUNs|Rlg`z^#U#W8=0HAid?U|)% z2E?5|oCTwWrI`9=GZqI*maFMHZy?m#LseL^N}4}MGs5fGL93#UZr4;!t<{vrm!B=) z8C73NmcfdIFuis)6g$h5;mW-+YAvE68;@ww^#VKI@PQ0@#Nxc9n9#8pRYUO@qT8M( zS4iGmQLmV2!{h5qz|IN$RN+l^J1VKY+QBmqWuQhf3 z5}`2e)!v{RTFkSQhuY&nE`W$E5JfxrM*lW}zHBBRJyEeyd3S7M;cMu~;OAokP8({B zH?zxuq{iG-2z5=UcF36KgG)x@qN3-hC!>|wVh{*~LNrHt0T7&CCf^9;$V}N(3O-e% zkQx%MXXX5XOf-01t7bDWRBBN#x9*Wx%qSM#6XrbMyyvVBVrh9V{~;?YSb?;Tz``~G%C|5qTzc5RI@3)x8RW8XZy-IG*t?Jb`9-12Nj%j zR7AA5U9f(CmZBb0_c=;W&@m^vd1Am(3-(!am4oy#SO|utp^1$*O3!Q9>PIGVox1Th z{Fdu6Q8c%zL27pEgJhZeUNuuYCE zFO3Lf;-d;wKNv`P57lF1dyX@y+=4TXPtMN=g{-XsQG#dBNhvgY?8eRk7FhF{glMB+ z%rh>*T+wggY0Fo&Qdi!p%M8ng2DiysKJwt!27whb?qEypS#`yj)0dVc9QF0|cHf_U zpm%-hUW5-bvn|r#p`NGwn3LTiD)N~u`dPzngc&nl>5S1ts$luC8t1*PHM>V{D3$E#CiO#*Tkq=dh&cFzxug2#*n&4 z37}R-e2{$t^2Kv01>OSu!saR`!n9 zBniySr;$P$-ePmX?dqx8Z$lzG^qs3~i9{vV8dUjfIJjgq%5WE^Iui_EeWrP{DQ6Ya z-qrO+_rYxN5KWPLPgsFD5U0}WMYk^T`lpz+OrxEELLkQmL_P2FrdN}fM_+#njXk1X z+O|nKCw^@s6eKrHiPY*S4a=$~cH|B1De6K{YG^(ZwF*0&ObUaum^`Jlq>$|6?uzoSIGD77Q(gaO12Te}g z_JBc*3=PYuzu*51N71}MzVPIJl(6IB`9%`F)zrJ;mY!@rVI^VUxi0I7%k{SaH)N}) z-gdHY6Ka#En3k~X9q2&5?Fk;c<2%8xzKpDI+>9$IKQZ6yIgw|7OjbFK8 z%0&XPQ)#L$T~NW#D3F~Q`}TktO{8YJJ5p{QLB8{+{8>d55L@%&3MO1_ci9pxlaq&q z0)=8)Ju<)t*bq|^uG}jttE>IUZ{d1&2yRKVuBxi*I=kZ46q&nr1*uVIb7v>HB>X-el1x>(D^DS-*`uQiNVhgIe5BAY27Sx%+LK) zZWJ2zTnHmR)w-UTvfI4Q1sd6m6H(E6Cb2#s0(k=d#u55*rLnr2G(k_7zou=cWtYYM z{eUA09O2&sd^h;Gg6nfzBmRZEp$=#M*9U{%1~8!k<9H9Vax$~zqxpAoa~&f_TE=)H zWEAb^;azdu%PT37dfug_$QC8V8zMroj*iQHBhB-`2~QDIl9W7Sp5wl%cDWHe37S6R z13WdQo$Eg1)*U=roYq74 zR&{JijCeQW538d>eGI%@0e?}B@Drg^8%N|^iaA_U{%R@(g%*o(+h!E?Fx#50ZKRd& z*ua&S`)I9!6!gq6c+|LQL=KLf?XKc~Cbyo6^a^cVAF`~01xl;#p@D-krwKItuk||3 z1E9((pxCbI&@zy5zPUpVgux=%`3zI@&RHqiruJxjLr7|k)n(+1ft}$yo?^PXbABF6 z7@8SNE0qYP3xI=Aw9>t0VQCl80r+s7<3oWWn1@lu)3)em_eHbApNo&JqI6VeD`H!{=2=8vXsWO!)!)6e5w`)_(Ud>FGv(_*L?vaAzO)jBO zMUWc^7t8G;4U4PFPr*I{+8R}`40=(jm39F{hFhTLZ-KO*%NovPAmS~s-j{la6pi7# zvoCaXQ}gNrqrEEFNx@)T8spri;>Q$TKaV+Lmka7L7yV7ap6_4ML?TtCm!}zL(9{cc zyy;8m6+xK2>aE0M+oUXR)tzPcZUwgto4htErnN@eV#`Kqk~XS>5JH-$Bew?6L_YVq~PL;fTehYiskUP7Q4$d~*DCJ^mqq^;_sYIy4 ziK|&YHfD*>ocWari;uuA|&HTai;LkWSb&HHu^d=G}(%0=A}E zxjx3f5NEYq}PmUTs8Zn;_q- z`grd}C&b*J??d*tgzE-L?%;PjX;;^`^0K78cOUO)kTo}c7*xXBjruB4ER0GT-D`iE z*$c0K7!!T3-EJ;eaB_F3u3KR>u2*cjCW|>Vx%#E2z4S7M@obTV@Oh5o+wU)H4T(A% z+w0%Y;+TlyhQ5c=(0FVk*dsQ15l=g68+Qby8%Pi5_>dF2fWrjgu-vsv1Wu`y4lAj6 zeMF?@*uB0~X8KZ34`#PrXMXUtOa3lm9-c|&Pa#f-L1k~Nfz=x$gJJ9rqll>CwG2H0 z5lJQ>9^tUkh9tEU5RzgR40lZ}IK?bRbIhMYdZCQYl{kcQr3TZV9+cDVr|@Pf;`#P_ zajjOa6t#B$PB{~kITaH4^hj$?WRKR^yXHxn!G}Edl}l5)2w3~8&!k^9FjmDyWy}fv zj6t0**J={W=5FQ}h~USYqDHJdTry8NeSoNzQ~S* z{*JikHzw3?j#DNWWoZu7*()ViG$v$*RO;1G+*Ksg_a5o`%%7Q{$A_?zMBMDc86bzl zj~T63mzs|WG8k#<*3V|m>4)z%K1!5WssUeqXOvKWR@!aT;&Ns9G1<*RL1B#m3wF6= zpy(+`#N_dmiXUR9Uv5;~RvQkP=qcZcX-=knk)B|~^?w!Ji8u5S&I1N9J z-yAO(#+2_F=$E?*G($EfZtix7aA%ZddgI;orCg;tG^(Pb2D}7A%E3h~XQ$lZAjO2H z2xpHTJyRPqwhIhXruMG#D<4wDPb2G_)Gc{|RM~hRCaY>@xc*oJJ|&c|vSrF@#?n45 zuh8n=c2P+Yvxxc|Gml5evw3y4+1f2a?xXJ-S6{`riTK$nSn`7vGbO+jX4g@p^%J1h zO>7Lhesf1YbIEb8+Tv=m%(s}Y&#^cxtu3#zs5NziXmrH0yHPdC!^0V`_@%;mj>429 zJgdznOeIS97J%&Lh>OQO<)r&2zO%-hJ8G2s_E*a}cjjD0o(Q4dy>7;<^^X#F(0*g> zPV?gJ0dwWm^M7JJuTq)5{$2mwX$PbE(cfyvC2}hkljMiX_X_q_qkPKPw5%WV1=-KBlAPWeW6gs;mK*MEX|P^Bg4&$7Ryf@?QHE{1HlI%We`+FWApH8-^p>W z?p2J36ltJ`I4+6DFIZUPBy1-hxryNCUXz&i_72%+k9;}f@u{l91GdKG6 zmqkBRWB8crXml-Dbao#p{Iq^Sv)AKUM==jyZ7%9)i_ zvom936^EjQA%|71^>F!;t-*iNm8>#@b^Fykz4Z}N}?(O4*Bev|NvCOsCJ? zd*TY;E>i_R?@hHm z;4PYu0t9an4%`=_J0t#EzRH&NqqW6H&7Qi9PhhtcM3Q4%!uK^odJkXEj@wTtwA#h+ z5KLLI`a5(6?{QW5>kv)vl(Mo%pv=!7{tSolenKK2(*YxVtair2$~HK&blZY(Vh-1S zN1!!iZPIJ$;eV!ya4h>&%>)2;Ipmt>2?7%T^-X9EP<1EKU-ggx&wl|9U}y1*K#ZEb zk(nUoB9llWEMm&eRGmch(62FxulY}7P`e7un#pWI`(gf!b%BVuo`E4po4eGP1GLB9 z+0l>__Aga7G!Fp}w6@rOmS7k&0Tps&$hX?sE~5{NXW4kHryumIJvT3yjoT#XHc<{Vx8w$W4|ONE9#4=@Djc#V=;->IS1H zCz;$k>^$$?CxQ3nKN&yVHFY?F75|%p1th}<8Zm~TXEjKHg9*?-Rfruh5uPN#ecIhaQ9#9vVi-@=TQ77{^3Q&0x z?a0WHj)i;aCsQSSHTt`Nv}A;i7Ifk$9sdbSD*L7*N9e`w-@T>zhgs!>1D^2WT5li$ zFLynH0>x|57g$2ELqkkHU}tGNGY3&xZH1h$XA*x*dk_a+1u9fV`wCnLIM7AO*vjO( zl*it4CeMC5w{NIdlhHG|RiA;9Nm>NIe#5}(g zO$*W>jstcjxTuf>WXJQY4N{8jw;MHW*N8=JTUZCC-YynU4`Qf=bp za%&Yf)q64bB0)pH$QUF63Ia-wIE51IqIy@jzt3b5yA650w*lE55RlSMr^57txunXZ zE_BwUm^zns*;WQ_gM1_YlxJPI34OWNJXa3sWoRaJe1Hn86K~b0Kjwt#^Ys7n7}%6^MZA@Ih8{(0tO(& z1~3aX&f*M#7|#d;f;2|Y#2oSpXPN_uWd2&n_wO_5XjY7kRgANP({(Ad@CA^)YSq$I zj~$MC`RBGL48V8GjZRYc2s(g%IeCNDu8LNP@E-RW9bNs`lmmOLc80~w2|JUR#VH^` zIw@ip`uP~?`y3=v!EAG-mDAp)dZq>38y_DugzTn|iwWIqld@)q{S2kZJRlYp5jHVZ zev0DUwuKRpPvy3s)15fC;!em!68Ba548$HfWPfuLP~it547&vT@i zytmhYFpMqsEs-Sf!HI~ZvNF6VyikaxuebL#W7|W1`$~^37EVxSL(UuB=gRz3St~TJns(<4Akk{*9Y_kuE9v4vfV`?(v zG6rm<^6*%{YqZz@y}y+jsQScy>!J^K4V^f>;4~vmFIi(4_%gD?-0(KAI12=#Q5q^o z;f$kovpKZd+NS6{ZPE2ck@Z_YMyz&h-wmp`qD#1tBz92)q=z&|GLW!;)r;Bi9$TP_ zd$TJ9yH`K$P}oMr+vk}-vNrd3(ZVGt;~0SWjlMHV#1jsH*d-LuRCC=tf`ohTDk4v$H)E=%c4i`b8s z2n=?9)Lla^`a3w3`;Nrb;op*&WUSe4o;PT#E{?s_)T-oOl=^a5a&`}Y zs-goLpd9CbnOEoPB-C#2s)-erb0;Cj5^<@-r>qfLrk>WK``rO0|KRELn8Mw<1QW~Q zwV-HUg5v-E&iDX#qPr^2e2S1b;By`NmyI2qE?tq{zNBq-C1FBa>L>G#UvB zK{07`rjB=3VP7C@M+i;wAlJT|eYSCou)&X)p-VkhV-O3*?eEVO8bZ5z(-C72$$t#0 z>nOBIM^884m8x{$qN?<3u;mj{_#~lP1-2?$6P=!g^+AlRgFZ16Dkmy8Ff zRv=%-e(Sl=1Ow{&=Lgo^z_&pAaLPO&0Sgt6Az#t&wiZX^zfD6*BK{F?hReRQo5z2} zuhyG~EuSZBzAakDTSFsno$@XQOPw>(rHJh);0KQWwzi3gyz@gd!;M%;T@{uE1w2>P zQy;r>0UV~;@9v}Rdg!SGG$aC;kd^Mz9@g0dyG;Cvr>5Q`GbD9AJdzyu62FVxq?z45 zo`g;k)EcvN`)L{O^S@QgcALGWnufMU& zzq!zDz<2i=U@p4KvoLH+AGK}iF0xeH^~Md6lzIu}h@{LMwkh@RH9yHkUCfS|im(S{ z?tx)Yui2;gkX1yLLRxx6_oR-IVfqV~juz2>Ft<$vAh_E1izp8`6u1DQPz5bkHnxgG zutUyDndEJlM%gU@ngmX>q9;MdV)RBAik}Uj6OI zz|r-CT(xp~R|p64Qv?3b9T{g}sj4|q7Jcr29{oo8kJn{x?N_sX!bToev;EfbZ{t#f z0jq;{G`|@^#_fNb{QHg?6)@k=Z1SEEdSw6Bwq^?8Bs7p2ou7G2Ij`{DZM?vPXcw`?4x`GjAI| F`+t%&%R2x7 literal 92476 zcmeFZbySsI*EdQjp$G_qfRr=}NOy@yHDU#os|uDNDze>oXZbTk4qI5;?Taj`cFaByfeaB%Pe zDEGmgq(hB5IJk%W#=^pK;=;nDa@H0G#-{pkaAN+^D#)seJ-8_v3S?Dq2nw$)K8vA~ zQhvb|bjEr^Ndf=bp9%BLuD*O*b>KbI%>qB2+-WSHzz_R@_wMOyzWf=@L7TSIa@c&) zQh&7QF?hAnU(a&3055n=q4IK2gbl76`-zy2Fv3&aNX4gFxt<7{p7*;2ef#?GDl;<4 z;a+<0E%r4M!i86>5b3Gk?%tM)L^5`7zzb5to3vKWJPg-O<{;W7t8M<T~KHK@|;mNpE*@Gdia3>X5%{E z58AF}|9h4~bjJq|t%Piwp35|GCKBQn`yp%Je-1~8gm6EsJ>e0Rmno^~PVv5vLqN)h zZ}%RDp(1?~>UkI<7IEgc#P$fsTY&7b=T*8D{Gk>+&6lewGG!|}IQ+wf*B5@ze&a0j zVm`9|)vUxX!MaM1#p@OHn`EKB?C?WVeOd42EuTQQyP;~BzZ~T+;tSA3293+oqmdZeXGhGofWE=`xGOdd&5zsO~1 z{kP(@971AGsGwb5(9ZJxZ}1L2?y7Yp$Gi8{YM9N{l%EP1-h%At@Kyeb zmR%rJsZ!B~P$7Knvg?XQN1CLU!zFLS@OGD^V#wF*d?@DU>s?a&M?5~7-$HawJiU^? z5tJ$K#y!L+E}=f0VB4fuCYF6Pj&<{WaVaudpLsF=M}F5V$dfU?n5i` z+)eNz7a`S^Z62IuOE`5j4jt!vd$Mn}U%2OtFTXvFLnP!RFH5DodzZN66 zMyvO?+f#1l2DD@uaU`n8@ecAi+ z{R@jFqaD@)mj4^g47L$ONT;3-yA^>IlNF*B;{ipv_j%k;+2`TM;-?fO3ON3fbfnQ? zli~J}GGQfQ4PqqSbb8noEL?F(uW`dSBKmq7ySsW+x`(<`X$f#71MnyV+H<9{UuK(T zvdS|kHqfNzCn%W|V6demNGA(xN)~6Qq%UN)$ji$!DFT|yV-@r(s})wrt~K=vM~4=u z7uXk=PAI+0-+nwnR6zaCqOc`>#7LRdLmjQyv*wGkG>^24AT;f*ijC4r-ob=H{=2-1 zd`)?md>Q##CBuAKIYwnh6@ff=wPqFXjE~uElS`la$Mc4b#_RG&O2wz1W#ebZ=hmy* z#ID~PFsF}*iB=B7)i!CFR4yJ<58Zk?pEQ_rw0X2SyJ@(oIrGNM#4N6DEu1qtn2?)_T$?(|*Km*lB?7baU3 zOAuR5ZPnr%f)2hMED*4j#lJZuonghC(l^=Xmw%FR(={>+SguVC%wj&UPnniZyV(?Qjq!eWjdrSZO7-#Yd>Xig%ZBUl zk~T)F?`0ob%*M+_4K)o)HTtrG+U=Uj%5_ydjVaZ|%Jk{;X{nn0ih2XdD*c)DpXOy| zwZeOIyA`{1y9~3Lr;yXvQ1nwGaujl2QNOoJ!F5|{+uy8dZ1b!fH}iI${^Fb}UpQD3 z3k;_vj}7JJI82O8R4f@|&uz@Cdg~LMz*As6Zeqw|m}28|#D$>y@1x82}N^_Rl0T|T849ylNI$o!26yhBh4E3NyR#rnkL z_1tj$mfsWyHISGQ@o`;>J!GQd&UwCWyqouPt9)a5(+YdVzOy+H!%v&QgQJZ~C}B7$ zFC{KPHTj&M_LZ@S!p6^VUBjT}DATZ)Qs!c0*%UdZvRfp0tmY?mB}%p95#xj_#a(#8 zt*_cXyoP+y#h#$HrY4pm&!WuUlYq7dFDqL?$GEnlx7>KyEztMxEvB{xERz4mD#GOL z``x1&K9al@SYAUL&QNqv&|Cqsz-z6gu9Yb!8Abjn zUXM55NWu4~*8As>q+K?rlU084Iz1Qu2m$`qbV0(K?pg`6tX44++)G?#9QU{g&b1HW z2H|;mb_Mg}B8sU`knwKW(NljUPV&y%UM6i}7?v5B#{2h6rB3tqxlUfGX;umw>?a8) zN3v|3)yvqZ^t(wOW<=NUehV zRwr|A#bE_wpi>~@4fpm`b?c*-J*uNM<8E6&^gHx3^f_Xn^o#YcZA186%ied8=5*tsC_y;mf9pW`>j`{~Wr za{I`UoC@hw_6Hn`Gmk5>OL_|mTwhq3{F=<2eO#Li4ZhGgvG?B7pKXO;?rqNDH&$lP zWHva*{wm34GYYQCF?865obq|O5PTx~RJ%JduTg`s8wqh~5iq+AM*M}GfWeG0NnF9J zhD%@Irg0iT616R=e0u7uujDu7%#D zb@ldkAf&d$A`zMiC28t&IlFM%LcYe}5nvWbfkqu~O>fX@i)l}~S6|N@(_hUtdo_8% zGpV#k-=cje%fQEnYg&MZqsNEi=1rCFq8;=&{7f@gWQ}x#t(=6l)=A{4ett_l_Tbjs z9HGpDkk?(v?L-MK!x*l^1!25XKkre>#Oj8G8d^p4KwnkdKw27(4qT(aA;A;C-2+$f;KdJ5_^<1?@HB9UclQzC z;CzkYkp6l`27JQ)!oUmG=FcZ$#8)_E@ZV$ba!f<``)M?qG{nEJ;RC>Ta6*d0;^N>_ zQP)~u-`vK?!q(i1W*6K*wG>mcfrG=PguUR!6)1j#{-=zURBctIrMPu1%oslES?K69 zIGS0)`hnwhl7E5?8I4Vv=8?sCf+JL;RNy)iZen1M0)S-4nv@1Fl3-~88z z|JG9VzgjZ0zk2oWP5#xTD{^ef{c^P3#|2HW9;Cy!% z0L_oa%lI#%@uQWP%cKK3J~MtJs{}p)m)-q!f_Gs2!ofblE3dX2uVVuaP7qG~jgXQf z{O&w*63*Jiw*%h=mnU0dj0*RJ?!76m{mB;dbWB$~!(ZHVMD=knL1Zh{r`=|Ua?(6f z5kYRT{Sz7ohUaR1Mv_>X9Xgh?tCZt{Ol+drN2;*koC*eE>m`-j+5 z&{(7YGnV)C+(4k9ahBrx3Kbz~nNtOR>u78P^|D0U^O``wj;+84l)dNYz_+&g0q9DCq)2`ah$9bi5a5vzo(nb+hJ8(Y3hsOQB6Kto z>sZr(UYp?#%r_Im&|o@Ry5QRntM(aU)L$)w*iPYKqu0U)j#VvcqlT4x3DpGGYW$#W`eoj-SyMr5< z$Eh~ipGpfog#>><&wq@7qL&GJVXxt~dkb)R`~Y*G%Kjrg0?HQ+Pe+cqJ<%y8{d*f<(zyb8{t+!Ips@9B?J9#h^OHQjXpVx4%F zQ(-k03*{euui;_yU<4pG%dNtI6SM`_nPV~INbpFHP%!tcDeqLbIxyHgLDO3}FB)+3 zZTgdZM4&D$B@3#q%ooYXjWZs#P^YfVzxx*cXIzYuInY&Me} z0MquW0R8tpUbX>*@dk^0s_xGW)05+|NEZfzcnn40;4NSaJ6Sb?%_a(|9e3Zr?6ZzH zu5Zr>-h0}2g)G)OQ8&n03@|FIAh-ks=#Li4Nsz?;{{+SkZ*>9h&1e@wN7$;7W;vmB#Mc{!MECkTQ z*836{ENuBl?l#I7O+dX}da(=G?JATnvbn${s9*oAOt2eSWg(+(@p@Nq^D!- z19+IsBvtb&>u6MqPjfuJry>@~z87I8Sp!1_vs=fDzECA0KP9zC2fiQ#4&fsX=>ocL zp}YaC84K7u@m3o}D5P>spx=Otat<&?m^8ROJw7x3#A_4A1G)71s4yO=6;uTqK~k|;d+c;WX3L-hgX)7B)6_E9!Pa>NnChe}I`jFz4<|_43x<|A*WCUpcno9q zshn{XfXQzS(uW7;law^4&zvG`HwAv~*KC}FA>a_O9;@=}2J{o2S$+BR<{bd&UmbuM zpOXtV?S#G%1;~4V-mb0I@?i6V(J6DTVI19S6BU3}DxHt@2dt-eVDWCxNoF}g$*;^^ z{sorwiw(+Ism)_kMx|P%xqpg{(SWIxe|H7XE+3Tz?{L>I|>|t z?B7U$Wb=5>Mfcy<^lwCaBMWHbY$g#5+Yznz+A;SHG(Rt+3fvZt7b#Bt8(K8o^9-p1 z2bTZ$&{}H{5RWc+cl~c@HM^X4i{3Wz{9hw`%1xujwYkGzYyR{NUG7*Ue^bUYA zjOn}WFEDyD0(!SH83GI}0KJ>7R%u}Lt^rgw&fUGK{fM-< zoXFs1}D zW6D8C1~erGBRC`Ve1wUwm)I!IO_HB=Vl=~)@W5k&q-D!U3a-hCRCvrq|8vmDbfrL1Qp|Pu%W~6BV#gF7cc{RqHSUHqHPr{0H9u!22KW z{f}^f$(H{JhyU-$UZi(vqz;X%>!wu!Duw25#y^+K(r}}#eWZZU*F%46h1IPCQxQ3C zV%T2j&wi~|2&>inG-W}t=Zq2diLF58>f1AzE{aknIJ~0y7zfeyfI_26^Wvi7V-G^l zVhlO-bT_;qI8prCU?5v9@sUEl^_m_A_RqajT)e)9&K!3Q_MQ@=3o1V&(v!rRusHXL_Pl1Xg2|G(iMswJKri$f7WBXxmu0`5fidum=@W^Oqt{~oB_J73VcPq z>Hd6cRbV9AoNo$7)3>|=23qvQgLT!y7w;Y$k2TBoo>AdSJ)>4!aBkyP?z$0Pt&=PX z5g^*f5)%jTP_o;D@gAap@#ynCYTxe7tZR7)=TFrc_m;mlmR4wL6l-zcqgCTSN{kyA zyggc!?w{f`AhLiR@Oh|6Fgum0LuD={<9Yn)FTx7T_Mcy>jpiDXAM)=!Hy%m1X&?Gt zW<9dXsQ)9bHfxxI>IWm+&SYffV3Qd4Dao^2tbN!?J9H16-w-Dsn0xyRNDU-XmCSLY z$JTOZ&Sy88Elhppu~r%}6LY82AxQvrkbe5BEYK%Z5#;?G%tlN%7pr#&I$BAtcFd=n ztmEHRWe&EeIzMBfEAE_YwMgA%LwvNEfwA03@`G`vT2iZNjUboT@V!SME7SG0kmjU2 zhb+I_l~ArD_4V@G7v-aB@*#LaVsbBw&3fgZu%pKTE#w=)mt~-6_`?S5+g>c5PYbst zv~RK{VecIaN6&Tp{k5OyY=o=^Z{gH)yg=nP?4$@LBr+&4j~!!?I>WTgW`qv5uraua zXtLkw9uK)w7jru>nnen_pAJAv`V37@I}DdGeDY4X9%9W={ir?i>|>ZC(hCl-Oo| zSMTe7;cjdoYieF9aj}1M4PA>T^jO|q%rVq9!P%ZUAyBna!ZAp(rR#bC(*?c$>@{pw z^{2|x?$GSGaO@LQZ+o}SpZR1!KNe;Uw8kpE_0*Qs)~pMP;IM-Z+3?n<<_I3_qCb#g3Y0=DHEuzd7RU zAz(ORt;Xb%pm^XctPE(R`0CXLALHHjd+=xbeNp+a zupWH4zId}6bskJKhjsD2`@sWv z9_WT{%#6pp(0*1NI|4R-y`$z%7rm~U0fk0)@_gmWb+Xjhs@J))j(a5nVnPshlgJoR z+emqV2C5uWk$d+Jw{D58--eCnz8Jim-=idA&OQNRGCH|lBU@tP(~q2w5?x{jxwgsF z@fBt02q;l6F^?IKBP0i@0mNnq@;l!O#FBE86{6|hNj&Y_qi0|*{}cjDH0@90`H{!^ z8Rgr9dm7TF>Mwq|b3c~(6~dc8R^|`{r07Md}46 zt_CrEjR>5V6bx1%J4;C1e&oNm;YRx?w7{OPn}hjMwus21WO=?(TKh!#s4+u)lw$84>`DCXTJEI%Ug$F#at5fAlo_4}i@ZVT^(zC4c5oEN>vdsg&yJ9H zTvHa!%DAr4n%t5P*!Iq(v+M`T_76?yv&yyHhMx%DDo#AY zROcq9+El$>iT`SfZ_oe;V#)UFNycj#e)nU3!^TRBCPji8&fhp44?J$FBa@uk=+C<5 zqO>Y4LtIZg1d6X8?N3U|G+jDxJiW{yWmGY6zY2MoaF|`$q8^+uTH@e={Z#YmnA$5y zyl7Fbsoi(1*z4CbBwXL7MG*<0J@WIn8M7n-_2QZ-N1VuO_kduKf{9st?_V9jF~jL) zy7^7w%guH&2RBAtP{X!*yw2Nai{*Be)%o-I*<-Go!Bl&svkeB>Hcx}|T}V6%Y>AlL zJL)HrPO!Dz-r~w$_d1uBFQ{XSZjUvevYK4l?tdE_inVXP>f2Z6IY_%C30!s z+c8G-v&0>C^_-jBB=TU5>T>&dwo}B5)6CjshuVdmgQ4avh8;U&w>g+|^K^rx`*SJ3 zjeF{*jP#6c7<}%Hpt>Ezoap`eOl=_C3?hlDyjVd2%70Yu2Q9IaT4jAhqGTZFh{pVE1-Sw#Muj4yZzGX1~+>Siqyjip(N5S$S!a_@COp1G{a|?k@tT5nKGeUJ16ACHAC^0 z&OZH5k7A0T<|)m+9TmY@J0stv-DLco>b~6Q`ugFa=vDtYErlJO+z-#a2l2w~2_CW% zq4~!Q7&xv*+vI4FY>f|Hu6i}srNUKB)!%OC`B2}Sb4SWKEZsK~mlbL_8=0Eg0Tbv-DLOO!vD?OeRNT)w#NJ&a%Mu(0oj4tj@# zcP>hC>NS^$*(#cE9rqkgNKy*4%{m;%XWULps@YZ6t}p^8ksKDx0@y4E*I9}%dMaHy zTyL_-WVf<)@wy)02s^|$;eXQkncsSo$#NOoNHpix$lboMF?5w$r1q+@L-&+#>*dZz zHy1=Vnw!9l8^Xvu0}q4S34Bjmq;!jc?+2AqB#s#(&{W2TYoVRYIDSatK1(JOd&Q*5 z;VRIks9qQlB@r;)sJh8;YF?(g)>JyTi0dU?4)zT~BeXj9RYvVkFU<%idwI?l4Vot^ zQlVWgYZE-~8=Of;zKvNzmAI$tgW5z{OJiNcwly~VelEXmg4Z`J8b$=5$lSEVBLI-L@x+Afy33qMi#)6uK`7Kg zT<+no>WfpiT5j^nhZk)a*|Wn~YXzMFYGe9WHlf_m&29#IZhLlek`k-8ej^xrj3#bG zw`&FD^xJtsBKLR(q-XPeUAaE#{Q9-tBjBb!er+oxaFn$fo+&dX98*`9s{G5VSa?aTHHDb0 zL+oe#kvM2Xe}4JiVUNe{$L2{7)|#TJs(L#ctJzDo!Al!=k6czG_sz|v)BBKy>7Dby zJ4*mqhR>aM!Sxo7-|HsA=o?Le%OJ%q3+bq|JbyF0{;JM|jt%1KIikeasIiPX>eqV|nE-SuhB;@;pwh8|t~{$NQgVVT`t(PA&3eVr}o=4?c3(>&E7b;Y-L^ z5aYkt;P4CiS~+o*Gd$w7yZD?NQNEV!`vA@;Te9zx?q!`OYCzP+@n;7crAYk3SDRRoRaw`K}LXYQx zkegJ;tmLsUMwM!NXyHl|TNIB?$6dzj4W6%gd(6`(sxa6n@3g!toC+8z z>H-CY&lwBeM#gX7^FkuL5g9mXnm|C>aq3To7(dL+mZlPtznHT+kT=wR$rpmJpC6Np zQ7!X5#{e!{+#sf7kNGIlAz2y!lYzsyh@s>7?K0H)geADSV4{e!>vnTWq0*kn=^Eml zDPZ!<+Hp#&Vmb(CFNE+i-d8Y$6~lXTS(LX(k)`!)m`Fw{9g)F!dHp_1#>$M3P4UsT zz;}kLa9d*5erIjv#kxvtpw^R){=HY$Hf}zTF!sF}6OU3Z=73yRj?rccBq7IT3Aw28 z>VKAU-7|(3zqi~$oP5;@VN|&ualN#w<@}Df5f~gxBD#DO@k`(;-sb8J zQKI=q#t~2RW1pb^Gi(vw*%Y9;@RI{Mjvtd zEdNjaD9`Q#ZP~(4@v16zA{Jq(u4o3xQ?*n3>p3RlD`{p2(KwmuIg<|Y zNv3(QC0re^p0wJgNK6beIQYi$z4L?QktZ}c_Eir`w`2||S#zI!Wq=S`ouc#ZARdLf za5pj-G;F1BTn}I76*Wvlk6_`0JU?KEiyZ$1*Q2zUK8{mFi$3)pQ=$ATN|zcd*f^qE z2QQ4L8dL4mwpp7P=be+W6L*5Q8H7VB`6Z*$RGVBJ`cXW&ueCSYx;SIcMMD=hc*88t zG#jBICsef|&y9wjS6QDv#6R05AH0dZ-D@4RKs$RW3VFlpvI3;}J~qySL+j$h>DeTs zw}T^I2(}}OWI*LpXC)KFlWrK3C$zJorul?F^r|QNq?KfPSkry})HG6Qs;tw?H~ZL4 zJdoe-c3a!R(mZ9B9HUsfLXQ7t=z7vT0VV%>_jHrL!MeG={-)fj3eRCQFC^l;NB4}U zC(t}L;3j7*KT1^7DLDF7-bToNF3I)SqB=&_mSJ{v@L@K}GWk#XPCF{ko2 zTb<427NI1gREq@<&GldsUAOV{#Sbh4hq6Uef0(}^)!Ej;_2-7&VqFc7yTaBh$u(Yk ze3-v6Impdd+;ej-xMzNp!m*M6IjC8RmWbZ9(vBc4#br#e$IX-EKtEY@lp zxL%!-Wx8+PhseBeh)8$G^}yagbQuW#QGlE?K0HL-bd_bJJDfsgCM#dgdz-7h*)_RL zOewEYl*FU>gU>B(rJsl+SD_Zsa7i2H9dQEM%4+e?#~@YW#sALh^QZv{n1-_9rrP=1 zE$3hG-x*e%)a-Avh}@1*%74xXNjqCO8xx_HDA8c^h>>!GepBj!Am zhlIBNu0hUHZoZt1fe`llUuFWi-YP5i{x3_@t?F^4YBvIyLzH(A5kDvSX)_WgfH42oDkdoxCh*pMmxW=s|UX72kP~cd(_rQ z+6LEQKiysY47fLT{)mKHepHi03km|3JEe@GAfsU)3Ano&ju7WCq&r^JL*@2->lOEe z>199bsBxh{tha^nO>hUIhf=R%tJSgLhFT6D?NpN-l<}zOY+k5{#kO^EchYwEv0xNF z3rc2a-ns3k31d^(CUkhz3mj8^L4Rx7`Smf__%p<-)SN%49KNeup|ee z+t))uXdvUnixllmF`{I!9bMI%KpCHjDJlG%K%Te!J6~H>$2hw7Gc&D<;<(<$#L)^I z+OTsemeto*^0eD(8lwhqPy8_PXdan9>4m0RYVABYQ!+fwTT4`-kHsKv>6;!TV%h2C z6A{soJ=%5e<%nS7ih zhB{>2;j_p^XL($itM}UKJsI}xdDZP#it3*;Vq3S4T_LOQ&MewSALGoU#yAI^FWOyd zl#@Cnx>KA6DL{}!&Mf#$$Zy19A?2AoF5nPUl7pE66@UhMyilPCC8%6qWSY_9PN)T) z+quvYZA;>nk10z%Ja8(ma4?ZeQ^%&|@x*ZWz9u<#JjFmZ%miwi&v+1_mD5qLzD)dJ z%dbZ-a@($<8Cfk>hSb3SD5&=*uKu)La$oZZX+!ylBA3B?uu0CD*gSzEEKJbH7NEc8FTXcB+CXvekA@oAefQh~BXFZLR= zZ}yZfmVLS;W;-s6G5~^Ef@gjn5bV~op+>#F?X^idmj;tkY#fKRjYN4okCh~4Q5)0Y zqUqq>?{Lrh zgeU0u83Z*`0aEumb_raxr|w5DSj{ z!1!b)e6dE1i9n=IaSL9?MQH-0ztxEZZ2ZjPcuW!pWe5O$JO8?&U zW(_=K+$45I4;z;PzErC+*(CH6KwD1KzJtuJ-y}CL4QA?a4Laf#-K{Lg@t~yIt*1r! zLI;vNdrLM9(U9+N6Bw5n^+pMY)OO|s#`oNM6R$1yV>kCdqw4DS&N8Zzs3}s+xq9^5 zI-T-gR%Jc?=%{6`lqjwi#h*2{S^RWZ-a8CQalnn+ujxrtUxA=-(u+d=vyp9}7Lfw@Zk>-{3vY!7*~2 zGrl|YsAIsLie}r^@>Gdb{Zy+fb-Cnq|Bgg7o#ZWuI!Hvnpl0LN>mO`_MWPfiL1q|y zuqHT%$YBAG%+bGhy%rTsgQ%Po>$PP@U<(MjHJzL#CcA&ytF#y^EM+yD*D6phrea)h zF0Rx7JAQr)`HZa_t zJctg=F9*2DfmKfhQ)uFmM2Otf_Y-IPjHeRR2xjf0z`lNwkXCov=ybTXf-%z>ev^A8 znBc(qnxNK{K2e$8&LHTRMab%GF!^xQY>G>tQ)fvoU#->ai2p_eSU%b2D>=s`UEhBb zd%b+}m(P?@>I|;|ck%i-y^$M2va1n|l8+zYSlncDYc^@X9sTWIEkEhRCnX2_ z*;bF%ric7?VW+}Nj9RmjEq5cn9fmErQjynQHzF&);tdkH;7*sp`7K?S3PL$MO zksR3_5{SYlX}P#=z_lI>b`V>mdslP@J&iNIH0S1&)`oG_y060yCAF4Y*{zyvUQa~n zf|IwM`E?hueD@9z^TOwYJrYhMS<=W{D-DRPK6CoUe?<^=PNkyKHoGji`SPL8gpQXN zqrg5$2fhPy=VmTKSi}vp+OakZ z3#W_!#6peFBIn+_S}PW=vrq@gY>8-!3I6c_DjN60pNNykgX(Dv!f(5WkK8v|moKvy zd%8jw44Y-ygqT_w>$0Aqo#jO!%J8T-hrYZZb7=HDCYgPFB|_Tx_j$3y!f(^!mg)t9 zbOQDfM^zF#xC40CkE>(DV{a8^PPQ0<&sF+xaX&df2%73#a%>emx9t8}>8v{PW{!wN zKR7LJH?~l-=8ea^Z0~mH70gA%)*jrvm-9rjANwH&7f1Xak`&bD%r68I;&Tl>?TKZ) z9*Te6o}9J`u^nFdDH}V}HCJvH=z4M($-ES0^F~y4Tz{01F>ZviORZGHVV|7(>U?Re z%$#NZn~a>)8t)|PImjqwrh~)lEgel*=s;xoDUQ*6KO(hozc+P*BVXrHOS8*bwnnLqj%skBU6jq9V`Z$9wmaSI zWHCF@2NljtzgT4s7l9jCF76YMKwF$g3I+bc2AD$lHrr!r{&wr#opu7`)V77M%KmvW zb|psZvEll!9HGIry_A%n#BG)!5}k}SJ@4<>Fb3l1{fIlEJkT9a`0Aah+J#2!gU5W` z5O^T;>L&-TZ)7gvwp?ez8-7-aYue0{Dt$3jydiC{;OqRY_G zJM-hFE7_9sGPm^!5nn}CXL3jWY|;^wC)+&Jz}GaT(aB9pZ3sllGEmV7V;N&YZ}u$) zPa*E-K=GP%L*Kid>LhL+4qUWNc*wO}k;>DPc@P6x^v|xAzH%3Kx6HRC5?Exc3@YjOJhe|&eoCn^0OmH=2g-&5CVhQbW?mw3a+0sezZp}xDLkey)_PLKL51E z`oS+d>J!N)uzv*3r{*i1)|d+)HV^FbBw(inuH#8LABm{3IyIfNXpP}oL!=$lO0WHV zyZDa$Kest(ibp|oKrf6UPZo4F_!;9pt@dfh9ds=;cb$eT`ww8 z3a7)Eb3BiEP-V*yYA!gGhH4g|2W#6&G;I&u9-j=j+~ORGn;fwg@Q0Vp2O-oOw3%*H z{xGoZQ1oz8l=__Gl7KT`wlhMWC6oChLzu;aReR=iSw?P7{*s%bVknE+O267b^G1t8j~f=$+D5jCztJa?9GI{ z3__TCcky_9p!_XWIM_i}kHFqd#$q zST;sAOesayuX5!cli9mOANVGBlobAC&szK7tgEQ5E!2^7sK5Ov#{`#n;N7OxE=}YE z`R@{G?|DyN6h2KLu^vP>ScMe4i(8&He|qygZ0#?X+}6E<_{&SZ^=B+@Z;S)oKW^dt zs3v5!Wv_gT#VTvYka`hZ$#5gGA=K49{Gi10tj7hI2w_nV}H}xqGIzw@^My-zX#{^@zs8qYprvC$OYzZcmmuFO5;CaG8`sDROT~= z|5o`REgu|sEwob?n{FHW2|bqDuE=G1g)ftBV@^h>4Jhn*ep#Mp3$T$>66+UFA@>V7 zEvLsJ&+q9@dxSD)mYluHEZxbd#C1FGZuXrst*y1Yorn($dFohIP3O*S;L`YFU*NZ( zqBv^6J*RpD`*h@F3QiY+v&D~iH)7lv1nWhIbVBlGwli(Z^FF{-OttZkl-o+`Khc4l zhw9HjOVvzRxrB0ArV=+3l^LQjZtX%%`Z^eaw)Es$I`;e_^5phI8IWn?z)o9eX1kgj zO5%|=&OW8rjU{kZuT=W3?_ook%tFhp^3M6T<(B5H{a|O{F-Qf;8A@Ow^Azm7^E6=N zNRAC-<%hCj7;m~coJC07iBUVa>@(t~@BTJ(YyKYB-ieTyOXYT!|m*~C@`9PO%e#&$gLdl{7=~4yHpn$3kcfw-;=F3n?wQ_=L%qu=Jk#YlR z2KD~>GsqTk@!tFulUqjKm#GXhhGwB3O8oWqppU91cLcbrm)^5PECYY1|Hbw2Tu@LR zIb97Kd1+(p=O*6xgI_yLyH};!c8XQqC9egCr_C?WW&xP&u938cS*#Ez7=Z zCT~n5h1Gu9#c;};&{j*)mde(UtV}oPDUSas@&hRnC=SbYB?EWn=qnaZFBhk?be?3r z#&bQsGkZvjyC#V?!&%LxI`mAt6-s4T?Q&^Er2o56CB=HMkkDA$V~UJiZ>};_6; zE|XbW>qk58EppLhb4uOq8huKsP4<^JpuFqSq8}eb3<+ToL&%M0Z2-TNLa8_lSCa{& zNtT}U;R`cbS(1W5+>6OYi}FXYn_ixp~OKmKC|pW)h!^^+Q9^?B~XWH3>)_ zOxj}FJ=rer+f}J!Sw!L)2$n>LW@g=N2OB0s(p#ogQg>gPjpR}}nD&KpqbEL#c&Rqy zeyQd(s5n`E4iu{^EMRdr2vo0wsu|3;upG{dEn-5F8XA?kUD5heoF{5yp2k5t#3ys1 zHdazVpr)|`fjVk?{t%R3QD9Cua%^8W=D!zy0s?kxu9SP37zuc*W-OVjRj(9x-Z2`p zn7AF72k&!8va#Gtm1%sRuaK=!JB4AV)b476=_Qe4(VEXCx(tsj!5ubXkpgm8<7rV$ zCJIx>xg@!jsU~->QTJ3zrzq+d4c9KDV~vztuRWxjcUX;Jet+8P-kzFZt-^a3v)Lu} z9CF150}7!%zVXI5ERQDqP}5Upih0hJGliBp4hh^XwK7Ym9O82cEvO;?;p3} zyKM@K#uv@j8E@(|2RyJu0ySvLe@ZZVYA9y!$&lWl{y5KlkErqi4Ma@SabfO>JS$pW z5M`hfM2^W#dIoU7>?Q!16d8Y_3lQ7{1sKAMUz9+F87hT@oYZU&m;4f_Q$d`fzyVcG z62SjJ5C3)IE;BD1?T!=5$JbZBr#&#$tW^ivln3+gs-xB4=FOkA-uL>#A&}jT>1RyK z4aR&4#_URa_6RoSV=(4RW1|9pK_t*W`LLf7yca9@$&om!&9J1ejvN%|B1~97xyGi?n+D|?g9-Z~%?LSD;Hbq1Ib;Kl*m7{NQ$6ah17=NMB>ir*QF_>7Y+Wq*fq_;63R>FC2qi!( z6eL(hTX(VWG}zztz|lUr1S{C{6s!OyeUC&r5m0{B!4qTj-|p%HE&tGjDQW6SHmvv) zQ>+pu;m7*hw!pC85Nto(tFxjZ09{~y0IP@NcqAhHZ{>_&KnhTqlSqM+2*CRRn1N*h z2?y2>O7>rlI43oEka+_%J=+H$g_CcdI0*x6r5A$8%9gWVBVg5bLLdzo-Fiok9SPGC z2&ccYVoAe_02UPrrhqBp!4m_v4=mkbSS0<0#fF_o{vRyv5)xT$EI~aiN*TZc-uzj> z9Tuu!rQd>uM?fo3jKuNP8>m}gKyi>XL513B0CX=au&6(pC@9{f{gdJ=r=^TT0G1#~ zIuCQ&%hn=qfHg0{s+{I(()D0yhJlrO&v8cqR+t08nxo%kcA-$fDo=}WW&svCFf8T~ zl1N}!FiclEllJ1a{Zlt@ryHh%bl$7o+>F#DoX#}LZOF9NY`mEXe`_B8GKj$CH%v#Ug z*K-$zY26O#C(G?DSbIfrz(-JkLw#w)EP^h=8U;MJt^=z(VBuDPeM&Uwmtg~sG0I^m z@lPECJ|IG-RHj0O$8T4f<oeMNc z9sO4OrJFjD{B_(GEXY0t_!}e8FRoPR{)#3 z-fKZ-0vl7yw%Kj z^^KMk>Q$3~v#7|~0q9Jd76>*W(F(}`GWqXmUS49S;MIpo_(F;CjQDcH%k|Ey^}?lk zDo4x0BXQsquLA9`NrhRA7y%*tI}Gy*<|D$%Mz3+a4iOgu^Zc2tM0`M+1PAD$wh*RJ6$jo62Hv}ynf8tx4KMIn z5;b53Rw=D?_`03=5N&o#>U`V}hmkAMh@<%VJa0lWoHr2T7H4S;jxz-%_b z9d+?n1Tl%tYWVX+1K*e^IbRHQv$grttKQwVZ-OQO-~z-P4lH(iuVp&*AHnmyb;mtR z3E8k1LM?Ke`JCF>QNR=J#*>*1XmlPS@Q%G66II~YqyfOsukElR0Eq_zj7L^;QThN? zVJPm{qc(*H&}N(vB!zMJ5;te;*U}7VId#yNg3tX_;anP8>i}l5OQ74$Mzt@4rUKQS zL}LJYfXQnk-3bltCQmQw$hc+~NA2q>tldi4l{;>ro-QT|m^uEb6eI9@5MbsFEvIEX z0MdglhRDLyg^E!a$k`*?j43ez0>I^V-<4|H+W$OQ6SMnJx51QTe(XZ7%|!>y#UPkP z0vqFA+gkJ1!u-3e0*$t$XL+xJ%JN6C^BMNUIAnn_^^|@;tltE1ECi5?20L4_7%2vf=F1hX^I+S7SU!`vy2-><6RVf7 z`+F3Xl()IiR(s=r6s01fbS&L?LyfWBJbg~0@=-`` z>)GrbmE+J0F7U}7K-_SZPQQEJX$2_}LUknz2GW&I1-d!;_z%^JTTI%YcOYMIa#R2t z9t0lDCNcR9>I4;mp9PF}NdaGL44epoi%A`D!Ii)*Zal)GH~~RSWHWuiFeNk^UlPi3 za(~V5V15T3?aWI+KmNgjP(9xP(Bc0&IG(o_iaBHtx99&d{H4pc-r`Dfi-8}wZUja_ z-A7ao&?ycqf&^IW-8U=@5YPwk9^FB&9Ki6}WPmMp9`p;K5&zGn)NglY(P;iWf5C>Ii zoA->seB*0dv!L zO=4*{C;%j41KSbn{;d-Lir@}JrWpl;d&I*Yy0tJxfV99oDB8Zp$@c+%{ofd!4zLwn zmd`i9TYf|BqdU3`8n>ZKdzMdSPtn2?fKw{l$R9zSCxCxo2LhT{{`A3bd3%)%Eo7A9c;@L9ER9EDQ8KNr(9b6#oAhvp8p!j>C;M^9pBWi=fRfaM7&evR+1`0}XN}$^JV3Y>mhHG8Mh0V&dvJ zf!V=4VVO#2=&bcGDWKzzHq7meOua&L%MHz^ zUrben^>?qelo}v&i7bph}IkY}rC#I-$GRZPd`1K^^9~H`NFb zi%83X$0*xtAB6~gdHZ$UkwCAlpNe8#{-jR_P`4bRb_}dk#(M<=pGTG@eJ$Fmm8L`v zdX4ZAg(T&YY$gf?K`Q%C=|FpYe?KIafYd&Nv+;<}eCiz@7o?+cPC%dLeh=?QkwI0) z)!D9gz0n-pl=sWywJA{Srn}n98esLE8g<1EfdCc^`wv7ZnEuy-12O;J?0A?#MyXi; zp2&)0zV6h+@e?r67|(Vfs#gf2WLn(wnKXUi1^<>8Sx-rRfXpZv?@(mMLRNRn|E zas*UtG;5eh6f$WVQma^Qi7UpMETbFCZe7JX-{(A+4BI3&xL@HF)`t6{)#N`Comk=eru9J?>EkOG*(QxT81n$L777 zxzN>VW&Wyo-p|;06(-VLQ8W5^uC7M(Pv63in@{6VEf_q?xocIC4i~!G@T8r( z!Gh*>b{lOgcRy=zDQWMi#+=Z@s{t9huB2p`w+Kl)xg@D!3}lKItNPtbI%X)Zb7`rc zavPO$^m*DRhHJIDgyEU{Mni`M|Kus|+05+$BM1ri7GeWxDT>4oVNENg71fYG`=Z+B z6zhz#;XsHWU4bH*r+0bJ2!)EIbABs$rt8i3)xaoQ7dsEwz746eAXL%o;jQ(r?Jsyf z^WuB!pMUcKz`HYqmIMZ25yoTHIdS$ATVK=R{EwfW`;)K8{U2uJ6LK@@gJO6jCffh1 zJj`C5CXHMTHcV>0X?%RH?kF+{nk5-_MbR0Il%uB2S?un3&z)a&!igHw#baDtxtgXb zVg2Kd1u4(UB&THgN_JB}Df+cyMXx4I?P z>7NHqn_tvHHyC`Nmq*j(^sQ&ezHDmp8|L|(bU&`sZ-<$}wZd7Q=(z4RLU$HE=4W2q zU5%%D4Q9+Vzap5_Iga6QZ{pAK=G!+b0!zF8XiXaTeHcDRsZ?Mj7`+r&(b^+nvu&%K zSVC7#t&q4$pi8D78O`FqGfR09txC-M@MDqyxJ-%w(FT!{QSc=!0b%r8v68PRAJg^0wZEXKafW!IsrnbFcj9R*ec<` z<}=3GbOXOCGQ_<;PdWQh0^ktB*TCFZQ9`;yoA!$PbiFUUqNS^Dn_U_IbL>Nv%i~q? zXXy$~_%r##cb%x-Lyk46CTtb`P6dhyQ*VwJBd zpAFMC{Qf#WGKSOBGcmN@c}BxByR%EaVX)rbGSF^0#nPVOCH8?E`Diww82M=AsC9?k zQEel`PdhfgyW-O`+5~8=+v1N+z2&*!QUWdrb!zGN18(%ue6xZ5in7s@Jg4xKzQLOE zv3{qHx^`xRK=IkU@EuT;Mf+<2jl=ryfXrN_Fs;HS>Nd(+hJ9pmPn}0;a?04 z99B0uLQwRprZ8{MH*g!O9d@Xl`vVHhms(WKN4N~XDcJe|ivncTF?XqST<@E{)d)~@ zTs8B|px8R^JR;_1>?|Y^4-LkYrvW33cZqS?fRUnaU^~M84qJQq`fQ?w*qd&r#fYgs^P6yR}FK)lR<=7&eS; zIMrDEdCZ0|k5g>6rlEFmh}qd+mV63vVz`_If)}q2RgQ&?6b-@X3M9?W%ufpNGJPEFY6kKxNNW1 zC+vBq-G-$`v>QY;GRt;>_(ew)Lue&!-IrUvQE!ue!byS7$y?cky})I=Fcop>O2Ma5 zsZr4E`kQY!;x!kOA*H(QJgbw7rM11uf6)F^ z6lBT6{wyf)w$o~tnooOPIo%Hg`XkC^1Rz4* z4}xz{@j|`;P0;n;y>=sPzG>~h-R(iw*uWp77>ML<0Y5c29djjwV17;wI_FXiariW(&EZ(Q>$t`+XFHqVZBcj$T^(Tx=^#x+x^$ra!vk!mNsdJAldnAwx=DC;<6<9AiM3m7l4r{_6`wuNH&E|Z zkFnEbl)zhH%tD*JML}wyxo3FwmcL68cd1cel9CBW>R^7ns65^JJj7{Z_-I_W$p4^u zy2g|s(N0T~&NsGhg_5m$BY~boF_+n0Ws`~mPI_fO+I(-{-oks&X8NaH&6t5puJ^!T z6|3(h9gnG$W10Ht=F{&vYV?bc$r2y`**E^YO*Tv=?@!3wZ0EnspVKj=NF$|;&4$2R zn$DnhwAgsox`bwm+iLP1EW9m-XjTY6AvT*zzp2>B>0pfHs38GMl9cb&!)YMd>Gt(tQpM6 z^kXYJxJZJ?=NPN431Cv5d-&8*EVg^;YH1vPlV2?J zvlA=?1D#WuF_7+ivGRp#8VbL^sog8L=f$_01C$^3_v{iz90fgwlL#V96q5GX zXh@v(1SGqsEP04*&uESPS&bK&f0h_)Zax zN7FwZ6{OB?M}e-+tX+wR+Vm)|r!Hezux$$~AY{@?;BH`S&ode=bO^H{|16_1kz-?T zHWYG0{G=!_=|u`E^OCYWyrr)UrXX%juYq(PTR|e*3f&m%oe{bstFm=}0QZj|ni- z$8l5%X=FB){7x&A9O|b-XS-O18=Hf37t<0c^BEM}*blVH(ch?Fu(5EYi4wU>&)t@? zIz*puF9Xke$0U$hD9}>;BhJbqHHHt^x*K8^3f7FB2R8*3$af7OojL;?54j*+d4*Z~ z(|RrV@P`s$jSC86=4i+ea`=*IE}rs?FZj|0cWn1=%%ph>T6BY^6RLqaE;MfifNJ-z z`8aZkd#+f*L=t+rje0WlnH@or+l|ufj`X0a8|5D zRNf8OnI4ACqi%ib3$jyZ`g=#E>G$gu^}bIwQv{W3VZ@GWh2tAG2{@m9ejL>vdS6S~ z1`7)adtqRm67(&2x%_yAo!(7f3H-N)PaF^<-undD>&zv*yFQOEs^x@kN}h(m6unW&?kgqm)6EV*XG zb3TIXG!uNLrHqN&kpZvoS}0Cbw34Hv?P%pL;2r#pY-MB+JJNjpZ!AMUrk_tIHhl^W zC!->`4QPSVHj#_N#f={&O_$i z-T5ng7kFJJT1?j)=TUhf{^qL_ms zCMKfGWFE^lxWD&6&t|Uo#_E6W8}q!UV*qSawp_kD840U=IuSJSZE%?KVN0BpoGw+@ z#dE#Cn?FeZ8|KM{d6b0-ZE%oE%CjPo1XeG59NMfMG%O_Fo*OzoW@F)CNr|%kSVi`D z{u8(M+4D&~o!ud;>3Ohwoe>!y7!Dy|)-(f}@s7VF;H4``it2T6Xy!be^lUQ!@Fv=# zq{TU`^tMnNz$R!OmSB6^5aYSnU{C*%{nj9tfNw6tM!Q5@@OJTex>}oJ$uZ_`Gt;!{ zFb?R`ljYhS4)&5Q{GMKXw;L#s-9NlX&@vp{Cj0a9X4t$ShV@Ol8e0Lo16u(Hv8U&@ zrseyVV*hz`%#Ey1Gx)uA(ogNq&vj2f>ue&a8J;1hFP7*0Jv+SBAb*5_->-zxULgj& zLahC2bgpi~Mir4D#UWE~r(I_{Gy!VPVm=*{-KLxzc}U=PH_>%JS#;hl)r^oQA6N&y zMo2KC!IuvB-3iHNi_|t?c^|aABVM7WtO$Cj`PU`hL%C1&M3aYVBF|jLY8Vs#iSKRC%DpgNyZ zmE_L4@sr7Aj}+DXEGBO0@|!=5EIy9RTSV?kI^okS#(e+A+lUP<)_4yCJb zFWm#=?rwH3*l4*ZbxrqN`eIqGiuWE5{_g@!UhwjPJeDg=t;d@uf`I1-`qz>j+V^Gl z3YU4@kUGl~{Z#Sg8AH2G{ij}b^CeRokM1rniv=8W7mJ3}UbP!mt43@~!Ar2fsxAm= zWv{zsX-`$N@_S)?GtsexV#qR+`v9lg!1^rl2<9}a_5EmxE3UV|{^`;vSvh18@>4CN z)+&9Bpd3a#4*}G&P=n?W@CrdI_|=JiMNt;iWF+5DsD%Yih?Ruf^xWDGlt{ zWy@Q?-aDq!aUN}?)Md!X$Nu)_zun{UoAHuv9cH$;6?%S9T9lIa8lfu@5zl$C|eE$0YidbxR5;$F|7uSCo zynP8~9gOOviREKX)6Q!>{wdBoy{E2x&kyo}iJM=~zidmiHt}Yi=keoDo7nSWwAt#bl zryiw2mlJI#ERYsMO;yQ;L!DRn?A{In4CyNvG}??4z5qmqL}Y{vQ(hRIJZ{rDojvo( z#h%BYj?y@RvTL{Ani6sKA=_+lrrE=B^ICR;XP_FmWtCYyb={0P;JlP!ySJ!m$qO}N z!8vB8hyq0G{RJl4JoeMzY_EjP#0~P%^t5Kz(AF;8a_6t#AzIlREd31(%MK5x-4!d_ zfh;x`XxZvSNDu{OuPyA+G~U#~p9a594M4U8>ZxmaN7DpqZVhSW4p__Qkp~%VC)mpF z3rEsS>0e}t6U`?nXw#C5t z$Jg-`?ez~{U^IFw9!^jBVol}{SXO(_uUD@tDEM{7bROsx zO*P;s?>8=?(cZuu5!8Bs$b!ZI(P)sp0xi%{gt&hVfWTf4UgVG;4f~WK9EtRaoI)BB zQw4fmlGeoWix!wFhFQHuTbvXcYuu~r;3p4IYynrBnQnu%a^~%pkyE8v}k{W(FLp>|WbmN9MJ2?CM&)orORcequwKOb#86H%cM zxGNHS7<{S_QWoKU`5N+-oRhs+su{Vs?gI-MXN1WTqP(6Ow|Gd%QUmuptO42W2T;t) zd5y)CF-|0E^j6;9e!|BctBKZlu)<ge#XWisHx=DWghP8idO-Z}pZG=%vlNrYnj9 z5H14kKYAbe|LFZoTg}IG&VE5irXUm%KbTwS^u4}@onIi% z5&91Pw9)rn>Dh9!lPrfMGe@{As9-K;XXEUr3+R^UZAAN5jc2Ct$iEXY3WDy7u|$t; zi8UUzt(tzzZENKENvluxT1-I;`B8ywP+pEX>>^3OW-&tN)zQsySs$}+h`VbE3 z7$0ZkmjrnjG>3$gtIu(`LNq>Rb0-(<+ja_~m7>8i$dOW0XXJaWF?}WS4!&B}q~*iI z8z%D-6&3A>@o{(|%)c6bLNjL}733fAl7S`$y~xY1yHNr|m?s}uG6kqo)V^pP5;fOOJI^TR zwK{8X%8#^mixPRA{T?`;opAX8X<*%>cq*jtZ@mBY=XkCpMFrL$HyfMw*<^>foDG58 zZ3Tc=Dg!(S0Rhyn0`sYj6DX)_a`yczc!!;v zDqBJ>%TH0@UIgZx30sj>hx?FL3G8+Uvv;;C78F`Moi)dNv8%~;>IcC+x;zOZ`5tI2 za4v&v$;@6SiZK_gF6u@luXja@Oq`Klaq2!R*T}8L{I0~MW2fy&pvcG%ogg8>A~$L# z(Pa=E12ce`>o0;Wz91EL$+=%e`*AyNk>qcu(B&A?5Co+naCVRx-SMQ0YxgE&seqP+ zx_;q7!orv5Tt06xwO$X{Q|NkpL{Qol=>K=|ms`?gJpuz#k9o_OJ|oT@U^rkoz;IFn z3wY5kFkWlIM%4dpd&o9arC|<`_5`-B6wvbeA%qb|&>$Xaq27OQM{@1?C`r2nlOg@M+WB%5qW#v)I)!sXLl^ zT<0y4@M#8zR!^+RfV?qiZO%8RbCR4A7c-6Di4UUWZw4BJ@tziLkpEtRD`3Qjyc|D@ zmfV-Wi)mFA+Z%Z6+R=k!p(2(UIq#=$Ke})S_PTBqnzFe$qdDf9I@G&$48Gk@%V$FS z0v{L`hZaFXD9JK4g+)LhsvIAWMMO04c?t`A;DA9YYHKpy2WV@56-hiZWO=z!f0ii) zvOTZyyJlANdEym!CV83ce*B$dNAh@koCJFGthqh+%FD&Aq*Qv`H$}2W@F!Vb`Y!3G z{1H1zUBz7g&A@=z6efdS(k`vi&rSo8T%yj0^Qs0IamIH^thc-R?L+kWdZ}t^8sgd% z3D$>ZnW+c2w>f#XE$uaBZAZW!jb4o(`j?cj5g7huPkvH0pxzk!jVa2aw_Gs`jbWl)mKPiT%SQVIzRX>yNtGI)6= z&!L-;YF1*aZ3diaLmHiCwvz`$mdFB41>$1*A=JgU5m#V?pL6TFyBP`?bZyO7oK*D} z%KU3t_a<-Fy8Oz9;wJC$^uulp(i(g*lMOnJP+O`XBX!N&oNG*AnJFhxE2}}PRM-gK zs1^n@MZ>$KI<0A9S~r6Bwd-woMMa~kjCkRXPMshrAE#c=2ow@2xACg$^*|(t^R@z^ zOZd-^me0hYt}DH`Z7vq^77GF1{9J@f9Th3cLgy3A9Ie-v;Kz&H2WSVhjKGQ zsP4BNO7`d4wX?g`#p<2R&-tSXFfH$}^y}pH>$uF(?=RXtk`{26O4-~75(T`G;>7Li z%Epjtltk`nGoF9r&zWm(KuyNV4WxOp%6%h87O4>gH&C9tnD!yU92Fn6-ZJw}pr-PK zGg(uOt~X!4bvW{d!9)z^HCipo>&1?FJo-i~*et3q;Q}PU_?*~~{LFUImlt?PC6F!> zqu*idY$(>q!pv$@Gg~50)@5N)?3#yy+T@zxu&SrwzJ1Xo;As?Myz3$Uer23!JQIw^ z(VVDPdB1_UBi8qkxoZM)^wH)`2XUB2Ori5d0as~LTfFy`RW-!x{(}{yBSd^)R3VvX zJ@Cz)BoTbMN2V%|rPWw-_C?yBdE*ggmI44Cg%tBHFy>B>#YwIZc33%WXr_)A&5{L` z0-mg_VEV*3vn6|?1QQp@)s3B-H^D%UH4^S3c`_zjJ%=Y(ms@@-!7artbe|pF+y+&J&=0^9QEU_R)8|{fW2O z^$m^+S#=>gUy@PDZgZ^wUeHH$%_HkW`xj3V>|Nrb!YC*9KeDkE{5&gM^|Tk{(dm#+ z=5py})g1G4SA`Sj>b}cC`K#Owwn%GWR}IE@1h^_xj}5aQ*X{OM4KMSwJa4e}NEW51 z7p!9|4>_$V&87JieYzAvT<6_V^@a-?K+WZGR7i$@;YMU*3sL-x6T~gIa+{3sip&)| z&&{$5;KeCQLYN=FFAvb~HP>2pimocAgReXSO+@Tq1vqRQT{GQt81v~{+L<-{d`HA^ z;861Di{={H&d+X@1U5qr1rV{;lqzS$hZV%q5fChU^AT|WwB_)}4H%^hh4199C&;}| z(o`!A*>JwmD45*xt>ZFjMS(e^0cAEf(Q#`XSGb|P(a z?Cn~Tlue#p=lzbbKPvD1_`O{5;vt0cvNq@G7lr$ZX7$K}B=O2XOLbOi>>58~`+ZkF z;O3C#%8i(xudcsVeO~F<+A?NP!>S{HsU1Srew2~>kna~tO||BM<(QnJtn7pcq^76l zj^BRj9eIXv!0bZ3{fBxi_yGcab@&iH7KDuwEpAzZQ>0Y-Bz*rGwaKP@m`!2(VPJD3gBseJsxxw=eU@!cVrR0$})q0#cC+C^AN{?hAT;kBPbPFofMzM%hgqAyGb?2Z~8RhK&0P9RWI{zza!2Nohw4+ywLq@xsek_J||Rxv)n;vl}Yjx4%Y9&`z*Ywu;zCLj1-Gb$zdMM$xH6SzSBfF?)9(2S|P7B0lFP%SR#uYBB zX{xWw=W%<_i;QMjtbC+!I}((72(yUUshxDYxxjWdM8ewBLqZoPt6xZYjVJ1)kKb`<~n>MLpr zJCz~xibpQy>=N&NOb#oAajzpP12B>2#t64$VE$}D=Mh5p>}8_0&=<6|)-M|JdLzF6 zxU@1Pxw)TXOejRkz86KWFXb|)s>ytd%~zjcEo*?FbT*yyH(eCwbR^aQx2|hTrOI*B zXs035ECv_|Y%s&S+oXO-zFb$bQ+Q`)i%eM>ZeYdIF*!8QJ^+E%jYKvH7RG`c2(-!| zxod9HzwLb&PEf0?jWCK3dKvf?{Xu>2^Ht`VS-+|OAA4&)7ULrJ2Xf6VDD?d zs9mYiPW8RI@qcdhB^fylqa}zpz)~5Uczu_{iLTLSR{Okw^scPBYrSIQjT#&b=`TJY z6n8fC5~0=7z25tH3FK?{tMv zqF-vr4=2N|_AOc&BvDUK^?RGq`S8R4nT4Oy`>-R#1}rO-_2Ipu{P!fY=i9Wm;pAdi zis1r9%e)399s1Q`z`rZar>Y6X(`avhW@Mq$hKh@+EVo`_VdE~8I6Ure_{+UbWuCc+ zr#M{ke@?w&m2q6n%YB(aRmZC8erm~8qLrMua;*ns$PI3{Kooc7akSp+b~@1v7Ww+M zgUn{<*wKzpF4k%I;Mr3tNrYs-b{sNjS$f5H=BgrqgkGSXM;kvuxu-{8Jh>E@kTYs~O&)P!3!}4|+GNC|zolQX z&7xR>o@hCvb)!a0X6`m^obbm|`x7CT2MhLoj?#ADp5aRu#_Y&b=lP?CeCr2+glkv% zR4P6xAQdh;aNu%H^`Lx&H;PHWU8IzNvPO2m7>(?D1yNMfLc3#-#=)cVf9@q(gNbF~<< zp!$$B$%{OhA!B;LU)UdXpCMPRzv?FT=hZ7(TWK+2H345aFZz{X6HeZ}J zMmq*4NEVC1y!epO!bDHSsHmpX#rS%25n0%Hl>luefO0e7d8RME*_Lbeu zwxs%RdkS0A&UN0~LD&?}WG`olV(+?Pdb$#dR0oycJw`fw9)uy6m#)3`yzX}?n(cb7 zUm7%zoII$uJE^@El`s@JMt&q%E&lp$!=fdU&RyKz?oGFy{exVCVKV|N4YpEqVcXA^MX&i_-Ew?G-iF+kthgDf9Il=Gnf6Iz?xu z$QhFg2~^^3&qzHl!;f3?JeIe1%I1_;9Y5GnKAuLxf)*ZT&0V4qa3o`-4szLL6bbwk zDa2|$JM+T*-yI$`!64wAlLaG@ZVCWJh|VE=j=%se#NqwKReOTc{hKvllhT`WW&8t4!@38(F3F?hXKyw&i*6wmva=3hATo`cpEir8?kJ zaePW}RW!~DFJOHr)9!Q!gPp@eooaPRzoG8S-Qoy88JVlGFvu2kePYct4${1o$jPcY z?ifFpHEy3+Wa2YW-`q0<4)vaJE--)qVHoUZBg0x$N9y$VLQUo%_xJBokW7k~@3%rq z;-kHi#!5LJy0}tV4Y^xP+EE>A6CHeHqWJH9_cu-c+v1m&3}SYBO>IND{(% z=f~XV_;Q~1H8$pMxtaZ+$F`SD0td2z+X-br)^jo5wX-r|eZ~GElRHs>oGF(#hi=Js z%ink2H-?^#Cq5^Q?;H7|>UV|hx-Xy!@r)FntWcK^R?_G7@ISn?@z_~E<|ybf<=NAm z^HOQ^&}SB#y)QW~!ag~?Xk`io{#ucIBy|+|(5F#nU%}KO0rt^1r(k9BnoVl^LkyZD z5z6zgl|LQw`}0@Sv4}b2FiZ=qpSB2j4Lu`8?p~@ib9M4ZSJOf9G5dz5EJcjLO$cQE z?GCt2`14~p3izT(ZL2Fyf3ELS-n8>V(}Y4o=s-j_GlZ2hO1BgGMW~7ySBp+we{AJg zkk$(O?r`9#Jvg+~QZdY9u|jV)ulGip)Wc07I54_tPHi%@weX7pe?-bnt%uMhj;GBr z+=GIeY4-TZR(@GmXeYVE%7FLa!=THOvaX^2cQB!Z*pSkDkS!J}fdG}ZQZo3Bm!$$g z4)VLRE{dVQQJ#tMBPHHB+(;G_JfWQn!FXb!gJ5T-Q>)5~{g4Ix>d)bQ`2`;m)MW*VL1L@}+nUZM5W`l};|Pf>{Eo?D4ShWE6jX7~rcF zNgC=WUH6;o-MC!sTXB7qDQg%%^$@IhhXp!rWq3p(u)$;~E-5NsOBVQsBVI^Lc2n)- z**T_Jqe|bcMGn-PxFvzCj7wG=5-dz$faf0^J|`nB?ty-qWiAx!2Z66#D?p~^%xF8p zei;{}8XWg$Zf{mkb8H=PJDFDbB&CqgPvwz;v)>c4Yn0Jsi`QhtN*H$g~N^v&d3 z%}YJk;Eb6$?J`K6feYe4L=QF08P#j86iW(w>nJP07zRt((hGQ)c-4J8xOI8cw506w zRAhNG7&{-iJzpg!X{ySLCSGz*K=r!k6sRn_@=ZTuha*-#U;daOHIjhAxDpZjDlr*j zVMnvPOAND~(KB6zyoDPURmfd#V^w^mbKcGWH&aO2Wp0Rc-JCX&z#9BJlaoKhKQuA; z8)q?!A09IUL$PdX&94D^&9cgq=6_#C2t{MBzQzJVA~j+GeC0To(Xs`0Z@#BC7HT9q zLuec&!GoD;GzNXnSV?GThcd#?1(a%yjd^X<1>A%^MVbyc`32{FMs0iPFd;4vG5dCn!O2z%` zSDE9(-js44?Qz@>2@9p|3-;Jb>1K$x<5cehmP8TtrV$@BF}in?Of55*7%C`a7AKW^p)&NQNLd=4Z}S1vzk->k2DJ2Xhi3hTO`>?F@C1>a%r;BEk~Y$1 z0VxuINZP!){_z`WLv zU#lW}9!Wb8aE4-t2TTUukN*519UuDXa9jVfZ(z)o_u#$08EWKn7to0qim87A14MFz zfG9d4sKx~WT<}J#hL1qm68BhAWAmDZZ7SuerQh|Gl!V{g&n|is7Tf!#6~47#xCh`8 zSM3l+D+!NO}nMcmcYeZ5fjFkK#)}6`z}K zqDi{{8|GlFdJeYaN^HS{qJ9MvtE+0VcD}&OH*zqg?tPmY9eA(61xuxB@mRgtpbHw z4-P~^;T{mInSw8VBnFLqmXXIR(icY@Y}^_17!}vMQI2*e2+m7)#4Ywt>EpHK=i)8X zK@};hw9ER99MQbrEuxVzfEmCdyhgy1=lqq{!@3lZ#{(s0ll(ORkr94QHb@4Cson%% zvb$Z0$sE-F;!RFjE1qey{H>;tgTZuk%>7k}6fK~W0HGjC@arptzifayJhQZKzxBC^ zI%Eg!vqzk~d#$0ZEglw2T#|V5)X~&5_n9}sARqu0nkjwls)h)7jCU~0KfdE&mtTzN z8z)g^)uU7}NOmgsC5JXd#k~#nkm4662niuK!I%u=L=E?N`z@iH8S%!!uyhL#?Mrq5 zI84q`Ip0%OPDZX4my|41@se+3334~Px@yuLlL$hr+(6eNHY8I5-|_{}|05_WXl>Q5 z@l&9A{cB;De^gf-CauRAUF(&3ECH6Rs#Ynt`LvkK2aFo;_4V~?emY{KSPpgdxz}QE z^pVW~F~9M;p7H=}$e$E2b`pt82NE%E(oF09$!z&=h@!K|+OYgibYU@sd@Dk~hE>l_rGjfc9z>8Q1Au}%9BNEK2xOl&_8S>tj@I<))w@w1mlS7b zNNF+7IqAf7u+WsY$}l|Cut|;Jpfnp}y|?dyO?eHc@K1#J3Jb8HR~RCksH&RaMdpby zp2nGeP5E=l<<9kDm<2^wc{>Q_yA0X|F(B4;)98$UScM6-@~`DQql5x`G28*d(*fFYJy+#5w!!}S@1XGyw6(YAc*L&7rH53ddvPiTb@!-;d za9@Nn1}$+ZE65kC3me+4q(89;Xvt`GKN<@FrZ$QOg=%L7h<(W50u@JaQ|iZ$KMZ-9 zCWT|jI;=K&p8L%BAYl3aAZh~C4zS$o=vS~2zB~JMC7%NKSQ=?RzyfCli@d_rGUz?w zN|r+Sz0^=Vv#QPZk&aH~k1TA&11jgD_g+^-hPt5v0^#8=H zU1CAJPx-9rNeqIIZIQuoois4Kjq5NurBhqE^mO!xn_H%Iu#Iwm$pZtr0jV4_Q+)FS zxCToH2sV)Is*Z)F(dY1oOerl=B!-Rs!-POmrU#SJx)+RPf{nUgWiB!}CmG9rpSS#mUtSQ~LE zV6AyE{P(8{Fc=(G_p>AH{u2xlu_TodDW4|l4-Z`@@N9;BT6DkoH=45{6LSAzG*9nD zLmz%|7!z*b!aRKg4OeKbsDPh3e=~&J0*Dyts1y?_;#JAble(;cOSD6*e^Yl9e$`kjA|5r zPe;p;|0XPEIz%?LZfa!QFlod8ns@*?#>1s-pP@Ql;Gw&7r<8{vOals10NgDO1gerx zUd))(wP5Ha6bfBv5O#AX3Q~%36tV2vSywWS4(H1RifvQ7*=aeb(s9OfWwm#P=(bFB zbqP+F{KIKnVoFCW{SRsG(LDkCg zvaI@dsSG*DcRGssqHg1geIGL~kAXXORKZuy^y~mnxg_~p)?7y7Cov&k!58vVfiK|> z>vS9-2;)kZVb>*ZQSlNXkybON0w*{_G|0d8pfIs59vLcSp`NIJ+9XSj{%w;4m=X{W z3Cpy%uWBk96sf4q2C~)XNY3Fg8XwdxopTB@u@(&T%jqR!F>@|yZx6-&>hX&wXHyvF zH9erqwgbwdnNVBWWCFKul6U+>cpdUO3}`4N=fmB z9-D~S-#s+5Zgo%op46CnT{pTOBuf{|z|wdoRdOgy~g;jpaI9%|Fak!(0oXpF;ng=O#q^#v=> zc%TFp2@sX^!p%fB+f3Ud;O)IB()POuCBWFOS{y8YG08I;R0Ek&4kM9wSp|84st12p@_|~~1Wb_4SMYZB|Cp?Hj-xW=Lv&;-D-j_gyg4Eqf<;^kv zOOi~Xq3ylocJhhtvx%FXa`a8Htxd6beoE0!FL28 zj9L&f`oAOeRfK9;9WTh^!Ecq9slW*2US&7^J- zXo6C<;o!bygW$6e?O!2EFOaHPrZ0~3dk#Mc2!K|r8)Yu%UgGW5FJMlgE?}`z zy#Hz4I#5(bho^l_JAYa%+a^UtMKumYV2X+*spJZMG#11yRzwcKX0C{@1YdY-n;}3T z9=zk^m~^>LV2&v4Yf-H)DvqGQUxVd8dY#l^CBxASIwG3y0h_6(I65jc!X^|n#}&TG zGh-@_b2*y7Myc`a=P53!xa@z>Em9Np+ArYZVeVH@a%(8d)2OZahbeU4go=*w7)I$rVR;FKiDwE=^7($#!VEdLz%Gp}6ETcWRl*zDpG8|l4 zS3Za{0eOqLMF8CX{jadFC(MTn-RJj&Z)d{0f~lC+PKR@)CR#gtl!q;v9U}l@M+#6> z%9uL8GuL*1N__lTAwnQ0LqQ9YHvV(DMo8<~7+Zd(3m4`trT&K;O>ia$!WmtqKSqu& zn21?9_BA`608R+nyd!&@?TCUE9uonXh^xru%z2|xQc_%OwQ8ZaeKKK#zZ2re>w56( z`b_Kb=G#%73C(49 z+}>|5HSd54=NY*^In^+&Vw;dXiM``fLDDi6Bt6K7=E&7{$Tt0C_Xai%ZNxpj*0RlMT}b@1AMl zAKAW{MI6}1;H%Mjf0n=-4@XkrrVS(olFZ`9uW9bF?zQ$*SS$brBmy81cPHpO8q~Cg z{Qwc&4h=6U{>kJpoXMlsW@$1|c4)bMp)oan<6S=@iYXRu;e&9aB<9Uk5bS6Xz~GsKn`Tf zAa=xHpcT=+@pA$?0v@NG z`7{=VrO5HwrEjb)8K0oOG7Qj5HgmOxj&JK5NcI()0Qk!yCN44Me6f)xXPnat(KO(f zJkJYhEhaw~kT-_$me8&-CTI2ZfSiPa4b&tle3~;O747+SV5fvSYD74QSAu#cftGmCxe-RNoJHx4P! zwHwoWa{=dzbgdm3I?81f;61+L3r()GQlTsyrb8h+`VnYN5)9R0oyJ&nC&I`6TeeQP zBs)KPdESK@WOuT~g=Mf1#!~>9(~CnW@*o>5?7oDjV{qQ?_znQ%DaR9GTUDf>e21E&Zt1z&>Kw0lSMTh4O z=UZdXNS3}Qa%%|-=zY!(MA0hBYnXA5*^>Qh7jv%u@tC$2cofDbQI4Cv5umY8_q6K+ zmuEIBZBJgm)^?}sZc#%+w}qWVcYqQ!UdM@gVE~~g3)rfg&7Y0cS`Y}N52wE{I=*;% zsLnPAaGO7?k%418`OrRiF3IEeP&g|SlVo?v^O=JMFkGm+Fq!oTm64}$L!TOi%BN~1 z0V3?J=b}C1`G?_fWV{4M+W}bAtX-C55OsTaCY==D3=@u%%_88ZXBs z4wEoGUfl0Es4f5B_BJ`=(pZS*1n+39+O@jI)Yf(}SOjVp{{G28YPe;#j8Tk^qm4lw zeEYPODzK!mko@A%J_UPKnl@t{s@ic))rATeL8V~f;^I;Gr5~vU z5FBnUjz8A~`o{7X)S?cB%GmQEylA5aq*@V*lTnHF8BvJ6<%p&GcNa)} zrGP{R&!ar4qhPjZo4<@7rZO!giCsNoZ|!qkw?e@lS!J^g*M+qXLYUZEwkM+rw=S` z>Xj@{rIL9Qg6$7%9jfnZYE^AMu+~m$B!uG#>XvOEkEGp|YHF#fQny^qtJQrTx@*yE z+jbVnNVBN5|K5TRtyrwQ4BvoSt3Q-D5qQDqUoF&yV%DE5Qi`~@=CL^u$ODq36MlrLNh$->sVIXstbG2RAUB-5NV$) z)R-_ipok_nz_|qb8>e05>@Ybg>09j4>x@g${JC|^FdbJRZ=1`{T~etWAF0ih2C}0E zRB+#blCnQ!GcpN;c8#_0stL~NmD$;ikIoK?+Nlp3Vk?&HY~c%DTH4y5o2!8d{zt#K zc*n;sjPASoYa2Dm;3CV9CG4R$0E{l9Gj>b<^Fn|nfA69_;HB06Sc%pA^hmL9k8*nU zP`$mDgpL{yVa$mjtoD!dCMxN$C-B7#NW=@idWwlN61O`l+d~a#UGxKNss2_jvOt3F z^&WB#3pFB{0RMDH6Xe2Yx+Qo~bQ|2qGZf;U*#09(lG)~6*i9i^L^EaV6HGLRy6=IU zRUt_CH^*g!XyfXrt1x# zml&jN32Cz>FHEQJTUiIHs_*s}(Ps1@_(VG#eeQg-!PrDqSKyPP+av2O7Tq;~2Kj*q zU^#puP!zA41izx31=2o?pI-g`yi%13A`+ZF)sN+FhvDT!buDsn!~bjy1K2eu7`^$n zv54{icVRZQG;cn@mHC>ZNy|uqKd9lfTn{3sJFVu|3It5*#`=r0PwU!q3>!l)_X899 z@x&|ysn)oRnS5U*Nq8JgFf85mK`(T~+kN0ljSsDWAo``j=tB_ zZk1Fh6jG+sGb1K~eVfW6n@7Dz_Li-OY`V}x5_-@`(l3f>{SH7XT@lu7KP%%GH$D$a zchdz7yPl2wh07PJN*$$F{^(o;LVvdDEF|3Zb@1TidHw-4Tx32uIoE&wzyc*Tlj46E z3Yt#sX&L&&hN3CGXU8Qw8z~^!-fQsLb%kTCLw&)_GOhcHo){UrX)gfKTmFcCv6nKo zef*VK9RY(vSUJmX;h-%;dI&bqpLc&@F*wv|flxswIFyGo+r|*htlfps%+&=GU%-n; z3bgKj6`7L&T!|d&vLuaFN~t-_RC$EY*H*1hJIY31dz~&|6qc8hyNG>%2N!Db4pJ0X zelS+;f%vo-N)Dv-#j4E6p^a~irvOds;TLM%y(J_oU`-T)vRRcgsE#@tpsdnGDp-NU&_` zEFR`(giLC+S^W)~T|yQguhgt{V zJDV$MrI|v_ymy5W8&Nynf4YfA16clJDyNHY51sg!g4?I0~u9^5%C8mm0*dQ%> z^uWq5W%M{(Of0tu6uT)ZE|*Z6lc!ip1hB!}tA*N4N|HG zn5E_HS2Y(GV+3(p>ehYSvbD}qY&=}%%}*zItdV(3jh0%Qcd;f7v@^gpmC;3k_Wd;+^o;zrP$1F68M z&787vPq`^DHSMr5DEqqqGq{f3@7fcnJ&LokmYt>XF6LHM&22dF=~@!OQgcNkVrY?6 z{rdH5q5%=D^VcuXmyj@Ov2h8hxlOsRQz__m_4Or}1t+et=2Zy>tT|t{5@hNz!kHEizZ>c*L&*5FipEhd}3PNu_Y?Y9AbxDmW4v8u<_I4)TpFZ?t zjjl6m`A(3IllVUcCHa2x9OH}7xM#`@29}J}WMv?BsPM`*HqZFZ4+aM2@$qD(v-^J@ zL9~~F;G^H;dVn$F?Ldo+&G9h`5&JA18Q+dVEOfkvS zwL}q@P8HYt5DiXV9lPbyz~u;-u+XH>^}cf2$^DY#-rw8(V7}qaV?cQKj6>@iHhZ60 zypwFFxyw(>($(GS&m!NGUQWom4{K?Z5T)dx4Y>NL?X}i%3j)qE>gwulm$@$$d>K8V zn#;z9E0=~jbgz&`n0k&fp)~%NO`Y+_dpF~WNN2SbJ}EvvK3l7Q^|q!X)G~!l$o>v4 zEoDgr1~KySg-b{TGJ-(i5|R?*BUK{bc7qx+G&gs5Z6;U*1Ogda-`tzM%?JfD+vw%B zU*=xe+S*aXdpDBiL;obHbG_8P;Xshn zDO{v|y*VMrv+qR#M$)dsZW&(vX>W(|I$CV9bTWT+es(cBIaEIe$?0kN3}7dG*sFFo zmNQ3o=>K@Izi3`MU#vB%+7f6y&nFqb9ojVV3F%{IY9R-VTcR~zDwG}qxSWuX*d2Mh{rz!sTN+ne8=4P#f_}#~Q34I-Yg1(`LbkTH#2SwW zlZ1!v3wGTcPY84v0rZ6ysd^>Uy8kiZKTG;C5K2wa^k2m3W>zS21@+NdQ?8fK&3bG6E%pz z3wmlu0jGj|2X16Mnhq^ z{yd+Omu4U+=t7Q;e?4-a5@xogaew0A-> zNJz)(U~Q?2=Ht4tN4F{lba@@tUlQ`&1jK#Y@$34dwAF>+iIlj}--#kKLqm-i$EK@b zy{sUUCO(qBWO~q=a}f@Mr0bfOYle}#W1pGDqpuQAroJ}c``J%GAM&4)|FDU4zVxPK-leU%)E-NC6PkZlhQAJF#KPJUM>jsk7;n$a1s z>KT!?kR=!KM6w&3Y{J&?AI5|j1=B))3hJ_~T|XA!;`hYHa8Hf|6E^%%0FGIpHnTm@ z(|M~djrWVKeo=Y3N}5}j2`M}@l>O(+cn`QMQbEbHr@%+KECH+KRSx#GV@1I!DGJJ9 zny+-JB}xR3XdCp!61N=i!AH*o!1?(4ZYPldb2z5{YQ5w4yg{|QIdjhSaiesWb!8ot zBC(&9b6<4FP?D2(9sfW&>wx1Y#xBv_{DpX@qfHClEatgqaRw?6o{zpF4m*i&*9mEI za0t5Z0wtQz$ET*kGEn(LUZbE%+fEP7fcZ(QRw23C=JAki!h!dayZU+EoJQ#=Xw*FF zv7s`rf8?}=V@TUVCH7v*)6O{A_wL?o3f@iC0uv;F#6|uR>Rpwo0S!qITjlJ;#uQ%> zcAr&b4Kcg=oh|g#S9Y`AA|Bg8uuU>+{Fq8S7 z2~^uZTv{*9!1ghhOzvWGvOTLK3AFI@k_)57>^@ba#_b&0+KzkJ;ql6X?uf*?n3}Z4 zlP)l0+EbAOoK?ob8G!g;h?QuMD|pNHt|oU)dOUAU0Y1p$dgxDMnJHY!e7dTA%UGH3e zQr9LVxufFT4iwE#9>>BtcW>WH^K0|d5!J}v_~W3(Dg*pDDct~@#l z8ib_6=-tSO%J}fKlyov%^%zxw=7vq`stKsRvd+cb{gR(JwJSu%&6J0qR5u*0wowF& zx+`>Y^nB0_6Xdno_+b)QK&Cv*vB8kOmixD_ad8-Bh7Hk^<+}1BBCCZ}#i@%Px5CzI zmu;Z`TPzIh1p{zGS)fWMMEb|^geo*C1dUv$=RhWOJTSS*`=tn5?4Cj*JH)yCrc z)*ut?r%#`1yt-fOHuxa*HrTd$ZnngM+J5{gz6D^_^Nl<$*$qg%W(U#TpJ|ex;bP9h z1w>8X4zmjcH!HdMWeZy>fAeE>s?8^fd3X>m_}-Rr@xL+n3u(v;5xG8dZv33KS?7FG z6Tq(B{Q1+><3s;g{)B@_78$>6UM<@F&JobV4Bdr$sO>&-C)9jQRfJ#@R!tAHaN%~C zEZG26j30cYRm0$U%reFmWlK{|$PD1ei0evl`|R}Dvn7FyrAe2eqN&V<+Xsr|HlkU+ zo*Xm~7@8y88rp=0@K7#;fi(!=vI{&_{|Ye0e5M$`9b=-vR-3;qNaHCl2tRVvNHYRU zQP|GD1u|#+GRG%^>wl~nI#fm=lI7;9M1tu^7;xuI&^x?06A*NfFHp?y{>KD$q|yTG zPpUwOee1DTWNf55PCq*+_Z?8|xbX`At=}^Gcpdear{lcQ=tYR``^nRn#!e)0f7s%? z^RvnH0Oun=n*Ofhml~xDi;SWwkW1p~U2!DDCoWcHNGrE0N(chNSNop~-5N_fZjiW% zpkPDzj~^M*AuFbZ5g6;1T;E91xkpSaEDEGCE=19gk#j9FALv7>Bv%38WO=#x^1=_% z3obwf8~B{W_F+<}&|TyJLnmX43`3V67Y}h89UgwNE|>=Pn-R#JeU*1QQ=9IXI*ves1rHdVF&` z6qEzt>W3|&`dI}^D#rLszk3Zm2ltZO#d*&}-8q4I>j6R*s8913^MhTa1>?F)d}PFp zhvdG+hd`19basAeM>D*aOhAl}%aO}sIc(w*hm1_yi)gv}#)hWCs2C80N#c|5T;I=* zGp3xahaFg4b}^sbir%Lb+gRT|9xdY`@}&SKp!_Pf=cxtke@wt$4))>U0U9QBTTQX9 zZ*ElG-Ff!~9lu@di53oqH6wlfZy$$F1NgYk;p`938zzfsSy)!E(o8MuQr0B0>-6qR zWu3nJ>M#E@CCW$xT!)tJSE)Q^Rm7HR&To8wHw8Km8jWAJ3p=`$OqS&wKK6@xE)TqV zXLZ|)qOSd-@|W@J!Y9;vNwr)KD~*Nq3gP3<+GonI$~uGH6T^wR{MrTy>V5e4zDU%7GOhDqjhH}Dbj@NnzR0S_!_x{cMd0ti95^F24_&6Jm+ zVk2*+@TviT{Xc=M$vXe#7{Ad#f5G1@--D6EDT8j}p=bSmirhBPc1c#on&%$EVfcWm zZ0zE)(#dXZQsMBV6Kd<`#MP~y?|v9`9Q<#B?Az95oM$(GW%r-;TId1Od=@1wO53b_ z@3#xKF1!yXm)c1=va6-dT(+9s!+Xg5F$|uZ5gX!9h3_EyP-^mVsojW@8o8-&EC#N$YFK6!4f6Vk7`lefAM;EJ&(f9$SXbP-I+mY zEC?VkJBu(uXbcm>03zK)CzHn{AvX33|3gExx$+P-1qH><&QA8iE&Av~P*`C>!BjPU z)XcLmps)UEfX^6FB0%p1&RW2{aG-NMc0sSLZi?Vd1QMZQfu<#r{78O*Z(^oWa0@=G z=Ug;4#nKmD*SoSB-Ac&8OS{1!yFpfJR4AYsl0|Mxbo@?@Y>e z!hmEizhAt_!VNrky+>GYfaeO|bKdx*{uzKjR@p=e{`af}XAF)9TUI*<2M0#mkc!5+ zxx$q$bc_tL{B>kl01sMqSJ81f%iv$1*uQ67$NQ>K=)txL+oAENwd5q(eJQ(ei}2R1 zcx+L3I%TIUqsK)+02Spa>KV`TQMh3f$%^=p_Q-zJxiFdf_3`eLm_EjOqu&81K9Ti7 zXh(4j_gYtmRB-SY9-UZfKJ`ufioe?lw{Q_;WEqn#F+2ja#wk13r|fRUm+=Cm^r372 z055%Z1poUCP&1)Sn3X2-wl4IH?|ih8YT2eS@!AE6fNv`t{Y6wm8$% z7vO4yFOFXB2(MN=9ti;*ke(Y-oXiV=o~qO<1_eBMc@0347Xu0LHj#ZkvUyqY?;rj!wa^{N+8=5-IE+=P%M0js`bH7dAt4 zet&+-0Yc!)F|U7kL-_o|t08V8u^DI@8GPhbe~yYzA-(YNbm5w4jh71S2HPzXPJ7$& zr-mYJzcz)fJL7UU_Sc<@5}f6aqg`4wA<{JTN9`@{qoqV+MO&(zEoVC<#;~x;bU<`c z`?zWX4OzzSK(aDRRwU~VN-IfbGn9)WVC8VADK9F^k(7-c=^eAE9GT70qDXjl?tsD{ z(EBf_e|xC-u%WJuO9UFAg?g7ksy2=HNXiR5yP%17j^}) zP@ic?NF;PZHmp5r2WdIR^)VtA01&G66XL{eie>VSy@{Zz^B*1^Q=(VV8zfZjP00o} zwy+#L65TgR0d@cxAO}|=OU>bTK-vfd@_q8M zyFjGc6}a&7bMnzI#ikofjhE)+9I^gc6>;;{4IOH#0Gv4&fse*`@*Gb=M9i2FkQMsN zR};@j<%V{74@Og8ibIKnLejO&&IK}X{fi~nV{&r{!W+#*OB=lLH$}SILb+fKY4xvK zd0}a`Ek3h?@sFa08U46~4!Cq+%uQig-sy}5BNb=F>*^}GF0MhA%*+*j0hZuKerapP zxry=3e;wj$J=;1Yx-o-NPjOOPep$CXwDs=MzHJxS@|{u**b~vpR5eI%t)qXtBjE^D zeU;PMpu?+x?9&wQUpN$gXC?|+iNDiyoVI{&i;G}J6LfnqAnD=NrbWequCH7i=6J!T z{rHz+JQfz0RySoeh?A=0?f25=U(F`7mQwTGsIM5F7yYEM`Ov&?csno+jd-W9 z@n?9d4O1bcN(VT(47C z#$H?AB@(R>EFX?C5~rmVZjEC_M!(BW+^#m@!MA|_k*^eguLh+8qjYYw#IhvzEisdeF4bc{n*eY`-QloMrw|eO zaJ6k{{kmqxb&!`eRoNQg~7#{F(>n=KAw z4h4Uu>4JJY^Zw70qg4?jkTYiF1B23XyGpXV02;OSSi0&b7Y|RvCLE{rfBEMCDgc=B z(c-HE0CFop4B*z@*?K;vN~TnqqA8_1XN(zSm-B;2*myKGhAZDK&EQXQfrB15{} zh2K(P#Y-Bx%j88L|B-b7t8TcYR{z7d5OVrs!AIjyS03TcHlY5%pB77?s*w;cq5a+C zakL0`c~h|mrDRJ=<^1z%wL2X^9MDHT{8kVP40Yzaug=wth-|)bQ1$jkz{5Alp1*^o z)3vp-BHPWGe|Ru@+#pDN?Mi%obIotdhUV&e*6;TS!JZJh4f4y;UbI>q47@aYyb>*J zsEjA~xwGN&{wEP8yj1l;3kkP-<|wVcR8`W`WcO3CUDeW%p{XT@u~_(drkZK^c2FtX1Ln5Hp|6Sko5_SU9ZY^+;gCk1yR$L(x|mwQc?{S_n&F|^&txd; zos2V>ua$#CU+Saz>cFvVC#{Q?AoG&Y($>698<3Dp*rkfXxE+*sDYVd%EZMLtkO5ME zq+9~GYU^v&Mw3q6_450YrTYk4Gzw%yzAu2Ujm?c}6>ooo_$R;5Zs^gct9QWAk2xkQ zo%?;$KjNBNuG7$i99&{NB^(QO!t$B$^M#BI7q?9db!UFR={l2lxEBnJ&MFr+2 zCPNYLbn7UT@$pcdf;7PE5iz%tnoQ6linGt$zUPbDQbAgu;weDFtkMid#LAuENnUB{lst0})+ zF}DwLe^WbRe`dZ5YE+7E<}n$I2aXV92BO_by6}U`zYJ3?JZimKLhTCo-7X3d(v0)e6W$2!TL* z6cpOuNcG(`h=m*%3qsFvhQ&$MM2uc~dd`W2=6jV|D=ih|$X%0^oi_$)w%we&C(WyYnFy#0rnVJAhMQ0H&lBUcxqgL=9tVCC&u44%fo$Td zVSaw`YmMXvM|d+fZR@eO-TOyJVHIko?_aYvoKmITY^^DU_K13C=~^>S+!IZ)Y7x0g zXopYRTdtQ%P^{W{O>X+#q%=Bo;tcV*yjhnEat;;4I$ns^ z?5LbFJDusOQBO^$%I-o{Uhp}$(B%1wmz>DBY1cbIO{5F{U%UW(Ba{WGac0}^Z&Zjs z$pYAvRe-rin;OGrD|;bau1E!TYZyW-QE(~9aTM8sI0)+JqfKpZv5q5>l;$^@A;syj zpU(1$4`*c`L)D_-&PlwT4baHE4)HYVcNCX65XNt~oqnM>V1dl(rAKa3iXyj?#-!C% z=awRNBV4PsgSlhbrg+9S3)ltIh2SF5Wup?swO*OV1bn;)5xQeRbcEBeuuG#RlaGU!N<~b^UViX3|oZCnu;qt5N5h z-qif#W%%Tv6Y9r!6I>!<3HbF1u5_`Hs+M$y9_gY7MeChfwvTWx<`5kx1^>2y;euDR z`8e#VHUKh%IC2;Ag+ceSnF@$V-b&jE-G9LkErBHvR}k3(GOV;L&c)tC0z-5GLzc(e zhJ*)z*DI_;Z_5($?gk2Ih`0v*6z>pTxKkQ4f)mk}s*dNX^#5H#8e}iV*5AmgpZA5e z+N*64dn4kW#!;;C)ieHXSu2+Xy{77QD%_c$9&b;vTU1S(US&|uzuwEWR6NEHpk8UJ zyK|ZT6xY@A{zJC>B1Yd7+_i!NZCfj0)S14~lGt^KbYilRTu3sTnwD1bK1Nr@{{ayg zSbHdWTd&W9N({HB_`QlUS%Ez>PX@p5`uawN59OZzuZ~=0uhl)dx^u&4g~2R{x!ZXH z_5P^&K+aVJ(T1B6w}#918CGQGXBn)INa};i;k9(h+Ctx?W;$IBDwE2SZ#ZZZ-_z%w=ys1FDNF8e zGiDxY{}B|Rk(>xyXW#o%*Ofg;VVEKf33wRq&Q3^n&meJGSi}QDSQ_ZY89$)#52Av+ zeE#?vQsS3^p2U(zw_ZX4ZLWN{C_FrMJv~|Oof6FnL7V891St_mBs>IYb4djB6g9akdF6q-Wiz~%R!&@^S? zL&lj<-<(53JiY;MmV!e6)^)Ps#3`7QhZkD=Nn@uBJ&cD-wJDK*-xz~O*BoD*R*l#N z-Z|svGTDj#R1{42MtP*Sa}QZtIfKj&mmFuPa+WcX$2qeh1Hb%l|_ULxX*P*TSeSguLjj^+@yAv%Z zN^k+(q>AOM6&tAvZgS~jD)PO}*N$Iw_O#QTQ;U(Eiy+P4x@I^sS9^QM%u9Y&ol&K= z*eEu{tw`(`CwFZfGvc!PILGe+8boulUtOoo?7_Dxv0RjL0A>76=`}L|I_hiK4ho1x{ZHU9P8Mi zr>xKxjL+KzG}}b3RwN?fSpK?_Ql9bQMyGzqzHu3pcha5qRdJfN5=g;521yM4KdwX^ z>PocfQL*7jWtUeVEgKox*mB$ZjXSSvmXmG=B1{ByD-DfTiOhk?(Hk z*7B96loD+^Huls;4>@{~xhD9WYmo?tow?6lk8VJEPnRrc4BMN`K0={3 z4}Axk6@T8SzR0+_>lDAYzVv7mJ06)BWBjx9u0gehD;P!v#S!WIW_=b}SMUGYJKhUX z{4Uz#gKb=Vmi#<==8^1hLWHEGB+d1oYHE5VQcN!1i_Z27uTR3@@1PHO z$yGI_+qhpj+@_X{?&dIx%JWkLwK*=?A8i!IOnW79I21Av3C(1iXrjpBB4_WUYBp`C z8XMI$WF7WJ^4UaNKN8W&NDrqdnw@ROmq?s#{lL80U@cKk)2gS)*I+?TPb4gHl^?Z; zs?5lq-X5-U`60Q*zPO~kQs*Jq#A=-=U9)cU55|}F5__M|%nRdeI5p({Ch36-vI>Un zu5~UL8MR7ap(qJ9{-UYH>^Ji%oN4Fnp+$`V=|Zx9l88<^sxHI5m&F)vGoqX>SQ&@gC$#d7rdJN2f+- znVe1gdiBQQ(2cy4u`0UE=2EwjPSdE5H;SZow>cFv_BK}RD1vl3E6@R&|;L-bv1vdsrOxL59+8hO)Py2BF=s;T|QGW?Il2Bx;4=s z*Xs?;HiZvy{08vviS13ibTI0UE8mgJgL~+QtGp@J4YD;{wt}W`*_3KP;^ZG`g&Nj< zHQKgf!^Y9U{bFkR)~_ORjA0HDTO5rUCiMH%?C8Q18;pq#d1CUKX>JQ?H)#)9{(gt& zT`DX0J05jV_qRGYcmF}MjH|&r&x<5Oc7Mg{dVRx?sUhefO9K|F+P15$)`Ha@ORmrg zfFyb0vwphCL?%|!t5fDj?RzOh10D|qV|S(cts3C=qX!G`eRtU&;G{cCym5^ak#0@j z_#PI5CM)v544i)|_WV=(GtnjTpF!=)21qcXcA>5Kh2Jh$-AHCz>vul0GVLM3FPp`R z6D*h$Qc;S0!+5=H$uEPv04G`MHeN@ft6`0aWihDhje}5Yelb@o_;FIA_R~t0T56gS z!9~hEM4zbni@bn<|M}Hy${y{GB$s;B7OhVnQI!^4Ge z(XQ#l`Q@#KzC@_>9e3c%pH=ptfNUOeEKvU2jQmd+maaL%4_Ak6vio~m1l{&sOOGRQ z2n(&(3-#N}gBisShkkcPxI|>ag)zd+XOv)EmE}pC&F!})j1e>|FH0(NJe0Fo*8eW_ zY&&VN>M(;@R?mjV#=dL~=H)L{ih6pN?8uHXKQ0K9j9<@rzXO{{#|S)P2tCcN7G*=-qUzASD3Oq^Z?zD+FY$0#vzOr|i$28JHG2p$Lo*)YI zP*DR*x_}D5a34%vMx$7dGkZzpa#|~*b|bMhP%%orcvr$A(Is*W;UkZgK(ch>9uE#x zaGBn8vP@CXNym^52Ksy+FyP@{K?}o_Sj}}I?RzP2wxE4?ZiDJar$+aNWOmyKm;UXw zK!M(aRp93<*g?ACzvzdz4>uNcscBs9NIgEu#eYNa;0d;b9GH@;4l3JJ4t+0M%&d7m zN0`><84klVc2<-Q3;As69W;m1+j5Oq)Vh4eJZS2EVkqDfvEn&_wP^u`O!|fWN)hG zd()i9Wp<1_p&3;X)$Y`rfl(xIo!=eL8WQw-gI=KhmnKty)t!fp*CvJ4w^JE7v%A$@;N@FcvT3h=X1rk_>Bg zoRg8$WLlXPUrR$n^6SI|i&UvUK>8{>Tq^Rnh#dpK}H()HUV@tq`2G!f8?DB z#>VOBdFdyR`~9Hf(oASy~=x_^d$Fc5Tb%ZRJ-2-hmXkgcYT7hbAWl z#)@nca9X80K>Oi){hU%m4DZj*jgk+KTjk=EXVHI4`EiY?yr$m$ECP?DFf$}d=7G1i zrNw}3PJ19PLr~Dzi!~s7K>8CwzEhut{JpK>_0-{AjFV`T;@eyczaxjB#_76kn%Ne! zsN%=jYCpwowS08z4?|Eek5R4oZ%`yzB4sXdO{&qoTZsE_3qO2~sNfP6YC^o#*^l?rZm8F>bS2}kaU5jph8l>^XWEL|&osIW!@Dd9hR6f1m{|J(K*H1rs=6S;^56`=kEj~) zW$eKQ_&hvTk;df>@80RrTpm#jx~`ISzCEPaPHUo%EFZ>D9Q?p`D@h{Ks12*^`9F`F zW877K<-R=!DO!lL+S`%u| zN{6?^x9Es}ohYV~>AQ0pmlDGMcfnCnl>UpG&Pv;xnHQWXV@5Va9xS|vC9z@GNiE*Y z1cP2Y{ z>!8BgwCaCu_yy+#yq1hYT#$5na5Qn2LX?AF``e<1@=)|+bd{Nf#+!c?X}hd1m8%pr zM11a7hT7Dp2tL9nxb+y8aA|7%Kv^a!j@bLWZ);&8&a5UxkRc)iq{h_=A4rwf{S(Z# zP5wWst^%qGWorw9f^@fp#G$*pyBh)N66qEMq@<<08>G8YKm?>gx&;IzrSqSI|GV$q zwOD7t;l!Sq-Lv<%bAE0!3u$QrXT(6Ma@Bt6vJ}3h?(DI;fV_(BJW{7hQm;R2d!)PS4PJvpLUw=G_}XB<$JG zRv!K)gh<$mCb`N=*ea3%J{e%ZkISYqR_2Bh9HnMT!I?>o}qB1kCLdYRl><60{0c->S((#u+yTqlS5`S>-wQVnt8W$7mE?tG~3 zm%`}{mAR)wbw2EF6j#*p@5{hS5|rf+g(|1X$i|IJXS}}*8S$2GKBSHyRbIYLB1KNU z+9LIpdE1bxf1i0dO{(UtHlEFO_GvUgUHS4ng_8z1JINbv2GgaEAjmH{_`c`~fxUp)wbHy)O3C=Rm z#ui64(>+_Y^^q@^;c7>#4wjKhlF%5Y#%h#$KK!5~2zf_mBWm;=2puuIn9Ha%St^M~ z$Mq!lwtPKCIWCSa_0P9-ZL#b`o+pE}5tlAfX)n>uX z4n|3GlId(d&qJ$*Yg`;G{D9{wsu?Pya`$8Dbmw5|b$_yHimudPTWuKk*QX(AT`=ZH^#K;vr!c45w05v(EmUUl^BDy!o>@Gx;ehwxT(71gh5l z*Lwc9K(i|nK_~2&*24XiCZ&_j4pBC8u@dhvGjv|0;P!r0t~`pE^Vq&|}4 z4?~xeKwWE~e6=WG7dI*=p|vRIF=b8OpeFXIV>%;U?d!MgFDS$acB@9%&k&l}VGvK` z_y{o=q$C2>AxMPgeIEFoTGDs!0t_61?olDXoKn|vlfT-9!Du~WG{?OE<9i>PN<_rl z>x^9FaW^9R=jx);emq9-ZT#Vp@Vh^)sz_u{U3tWUK%~oTyQo~RczZ8+eMa({mI3mS zDPD6dW#x|;wzIS5+oo%H1>J7dQqi%tePDZyiBam&+$D^P5m7cClhs~0V3)*kj_N%# zr;@-W&$(GjSnj`}BK00Pc-2H`Q|I7f31ZQfKRes@zh7%H7NNWb2)=JfZa2|JcJ2M} zV_rh1O_V301)Q_M#-24*u_Ht`iB-DuH^_qZ>&an3ce8f=bG&|ca`L#D7uQD z<@C1GBROq;LQd1<>GJ#Jbcxnl36rXz7e^KE9|$ zwqR)AQVshc|7%(a3jr16QY<@XckS33Ng_p#e*TEocm!cJr5kF$b8{x03q^qKHeH+A z*Hu(WO6N?o04=bJ{<(?AVptGEfvPknOVYewh}Il2?w6?AYiiUbmeybT{ZYdbF7dX% zM=3+tSW^-gF42oL?6%0}4m8}^c^5-`SEeS%5=Ri$3_38Xj|Naw-PVUq497yT7}AnQ zIH`}YXeMrm4mb{;B`)@}3f$#{F&`vGWPG$yI{FkU!#Ix$*ju!>M1FcSpBITSP0c_T zv8d^9j_g!dqYBy-?o!-5E&xVsMO_@sV?WjS5X>K z`P0KyNkyV_HzC4cu$H=Tw{;8n_0A`@j@BD&!`QgD{FXRp-;>$O*nY=gh)Y9uiP^_F zn6Wp9>VYAx+xpUnj0r=fz+7=_xj*zVGs@*v^Zl(oUAs%Dn1|5)&GJ2e@z6Z;ZOSk) zKiBV5QSOLpF*MlT^RtZnwqu(=3SvA4W9|nW%^t*q^o7hynWS3TJp6(wb_N{si~M^2 zYc0(aR{eFdJ4=hRo|9(ybJp4UE&h5JKJUw6d-?7fJ;^MU(IGZsVvY>hjbf+w_^sio z5Xz%rWq7tmCi4QF_Vi-TfY^a>31HTi1C|D2aCYfI#e* z(CZDR7q_Ubkgt8c;|+VQRsa`ipUpO60tNctC*gtQUMMh(gM%v767mRow(Q_GPA-je zF!5ftJw_FQhD(D|=2nG%U1y#K?*PIi>caR>{Od)- z`3_Ob!BSFjW@EhVdwCe}VXqOVCW z3!iz*@XJn+zvmfrTJ2IoElpp^sHEfAsMe-p=H>kWlsUKG9IGH^)}=B!kW z-CzQ+`#kj+{c40G)qsLnfxcONT#;bL&&8&e@Y+ zM-OtbUh&L{9{t!Iw-%c`L=AnV7t^bxe>XY4Bx}FdX?320h7Gw}krrOf>Q>EvWV|Y6 zM5g99<6}HZjxZzAm5M!*xOi1vC15@PfHS!Z9yhdcOSTW&K?XmN^{{4lQ@Se)<>@XYF; zI?b0Lxd@!IS<}WaYfewRY>l!}lyzo`4;y=iy=7iFt~fpP>zugUlwdjO2csHcqjGd+ zUhaTiG!6tcNk~^Mgr*Jkn;~0)_*&!2O{;IH@u@Q^QETrYUnDL;Izq(A z3R>AT1Yh5PC8H=?XfJRFX>D_#sC;)$V`F32(9XVq2#X61cKrO+(H&S}90}XJHz6oE z^4O{-2A-@#t*fY|^zEPKtkWtPLku*NrHeW*k~#V$7>OeC;KN)u+6b=W8mCln7rcaf zsfto+ANAL23!S(guWPjE(F%A5g0PiDHCxANpCe=W9v%rxk!Yy?dZQSTg7c{)>r?*%hN6J?R?TI5~J3T84JyanyMvh3e!2!<0xpN0~& zt7aGXT~v5FI{XDa_)oWxp&Ur_GaGm)5WxkC+#LmIc-%ZfB9FCN-9t-N7sSrs6Z4cl zi`@)Mb~h8o0l9QI4hS8g}{hW(B7dIh>{J59G+0{Idff)`< z2}FedmCuq|YK=#b7p-W<9`n7{o{E9f^b72ikNG={lF_Lm zW1}k4*UO%|2BZ+aHV-T2r$bR-tR4qy?qcB_NMm4y!#Z0J#B#<9P5)%F`bpC9bm=zS zD|0g&5;?NJAco_)^#neV^0ro>Hc5S#sr{UFBU{INpVDBaQyhMEbJ-)wNl*jr_cisp zz}@Uqx`NuX-!H2>;;+_?bp31=yGd_kvdcpA3x-)B;3SeICYul0gtvAd_trTy)mCawH@wdO{==7=8L^=9aqjX zm1FpZ$W$uC;_i7JoEmB?PGPgz*<{Zw+gItQ;ftNtK?B!Xo6S$|AzymRyWFPFL%YMnNpeh8;(_SQmE(gTOM%W^|6FKHSGCXUJlp(($`J?W_Wsew+CTfr@Ww>nQLlqT^cI`T( zGq^Pp$HtyCYvdPDL*a8 z7|x;WeO2LA0?=%N@&klAE=e?*34$ytI>v7FOMdU|=h#L)*2YcdTG#zr&B>ZyV5K@o zx^YJ-#9$8bUlVy(nuFEJ>-D&$vCloDDc%G7U%`itBG`>G)f{pJkLNHO@fSa`5`HQ4 zd_c4&0DQq%x6%t791DMgC$9C46Lw0q8Ir&M6i)9xiv&8?w0$@a`2gB&&@XGTeF6F-?3f<>tRuZp*yX8hsVapRH!fLrGrpUQ&myIP}3&WDv$R*=AXQTQ#$yZ zm8FiuPx=gxHW5~Gkb{u*cRc=xKhvs5sJe&D+d+{;xV0!JKlybg{wVRwlr=6ht5WU# zuyJ2d6{Y9#r=4!G&RfU#S2y?6zMgTMz?(vwS26CHdMV0QW(;5y7)JfzImlT(E%Zp- zvf}p)%F5>^*xD7}z#A!fl&*j7@>DWqJz%g%Rl?yB0bk3nNFTg>xdcSk9GBf2rh%AKmRs%~jW1Xbz9 zb#)PhX)F0`lnfdzf-tY)!u&sz$MZ$14@yhUax8E89xumy5(jNY6jl zrOIMhLoYF*;%dkENS~g6FSr`amtcmTYKTJ^_6VaQxS{H+AhcBw zl!3jcyFx}p%(3ho62pGSe7re-FmV~)><0^L3Ti6Xk}+~0Lz4xAI-hz3=Jg1tsO>$! z_3(yU&5cj(cSJ(EEEzn7v`Ca-nGaFQAw1NS5o;T7l*2BaTi6}FA zF--@sQH@W6QsClZH7(DHeA#+GW5rDsdV;)wCbm9DpI^Wi3eVabxnW3r!CE{2tILcX zB{pO#^6=SR@Yml9pdK)VQH|mWGWHxmYyCZ#h--+R$+^97BnhBPnKo zFMTsnX1x2rch-DqI-jX}!xwl8Z0AWVHa5WXQm3jkjdx z;^#RiRvBNMm23`iSKq#zxZT+ZiePmd$KFtbRMulpI4v1-97ZjiUq@=bXBxlz;=i|v zJuSOy3iS;PmHC{J7CCvphTxh3zpwd=S-4V6#^P4rb(=4TY zF?vS`TDnSm1WHqDAK4S*Xill=i6LK}A^z_1Jb)Cr{^$vv3$)V}2)9s{<3hrhR7v(J zNvEW8$<88eZ`vc%r} z6k@-zUdRc83VDPy%OU`AY?4K(5vyF=lk$5*I2(+ zI}MnK7y2s#Ew5dL9EVL(zZ@x$3dixNm_*^7*%yU*$6;mv(2;l_JI6!Grl)B@pIE{R z38T;J?3HQ@IA||5`7FPG$7Wxp{4;Vx+iLy~Kwlg?fH-c9e#4LQ8Oi=h%ibT&ov52Q z7c1`)#=dQpE7DAj8Z@D8w{me|QQxmWC_p*wbY{18aZ1Zuzz|hZG?cC!^gB0sgefdh zvL}_oMgZiK6Jo5!7pRC|7+TwncUh;@y8A9E>lYhfPdo}83YP4%(cClz0Z>cT$jN!B z#=uP>qk(*{WmMVF{j~7WCr^|C53H-^#g~)qN5u45BMSzqpoJRVRp2k$_J3kGeW+V8 zecU%8D#8s%=~@%Bh<*zjkWe+0B7~ixM7Y`dNRp%fii6E=M!9J3CQf6 zPLW&tlaL^1uU)te8LP1#Z@SMM*1IFt3F0&DDrzLC+Ss*)PwbXOI_~b|vI(rn*@!)| zBD%k|M$9MI=4&DUTx?w>&Yu_$MYd(Glr)yr&S2+3XUiw^u>gyO>f#i8^DKk4{`f1 z;>2MpzVEG@G)rX>vX%jbDA@8kpLATd**5SDbCs0T!(n0frHpv|P0;zp@)fgWKl`Af zm}Y3dc4lwC*nOquDjDSTC2m>pn13fKq@!o8r@(Y?Y3JGic(ptt80cT6gJQBONi`j= zHiwNR(8rlr`NR+HWuc}hk9+1rcT_=1lr%|xXw9q|J`V&YU%fuo~|1%1GLok6R6uc;!Bc~bNmNWhMlCkqcVH5seABT+nxCpm`dEnHxt4&|SS9yUn{ z$op2Zs9rg00zsS=CHm6D%eG#4Ge+|4RlOQ1#LI5 z1B{UTogKo#L4duwh=~tTiCjgAfkFqTiN^tr}5p1y4nafEaj8|QGaa!Q8c(pXx2Y+}+&{Gs*O0CWfo z;L_t_pI?$T#1)qu_!ejqlDVxwfIn1C>yv!k6`o2fVTrN$|+HVay@PEz_{L%p33S66}2RJ&BE_2YZ=0xC?B&Y)y zu1;e){`0%bfJ~MIIj;41ufdUtolpj!PomSTadpzGJU>4}gbyNPNfWnGV2=6BQNI^K zV)xe^BL6j(ir`o_g}|USn_uhQOd&q7;*Jd(N+D+Aa;zPacZ=J57&P7F#K??0KbPsP z>1i8RY<^Xdin{;=Y!>L4peUH ziJVgnCT_n`q|^%loRfo9G^}E-S$x?h+o(tG9=QT!pxQYE+w- z;0y@$pXz2px||#YMBXJkRUy40dUPA2CK64AUcDn+)QGT4V&MDjb*-m|)rrSR z-(JA%{QjN)>TW-pa{m`FbN^I;LEC~mK*L&D?U&lng%SM5WAOtuK=0&!y2FsQsfGeD}ZiHQ(q0 z2PDeWT`U1JMKVwbINkK9!RgeVI@;Zil(dPnHV!A|_<*GXa;SyO$a9-fD}wX3BKX1g z3q%3ddES`ck}>-Dd`T9H?~snveDZ_;VAm}jKlvS~(JEf9|NQNNR6@`usV9#3=HCmb zg(gsScS9dqp#A!=L>>*UC(UdkN=ZtM>f_Q4X9$L`nV4z_FD@<)s5;)~ya00#telsd zFyL&-SKh$(a-XN0sOBJ`>v|L;Vr+bKrBJCWkfAe^*A|b914Zs{j6>f-zt9NUav3Fo zFuf;9M#+<$c{|()fv|jBy4Zc|Le4#6Xpl$BOb&Ea5(7seP+=?8pr7@0rl7ayU(_1u zfKNdUe}eb-*%O&ZFbskfpg$>Iz*wM_Zn$uFbA()2SeUcRnHTR@*J_@InqFZijH$$P z*{*rGu&nfNr0+;{vt}kHx=Uhp9llw|yxo|YpK$+)J>XLj+`jNN-H@Onxcg5J4)luM z;SspVBzc5mfGThFxsBIldan`0=&?JxYC=G)>Y>^t5qs{T{ZGO*`H1(@|4j^unZ?0U*Xp}IVozS7=!r?AHfDOb! z8!RbDJ&^wu?Em@z7=}*|8Tl`glaU#$C2EF>(#sc(F88<;C$xemDc8ypPuUMoPtB!! zb?Z!KF`cirK+h-?x?2v0ao7$*W@Hb0U^lA(z$DK0wUTa64?DG)?Rc{XtBqCu%JC2A ztW-WFD|2C3Rn?f2?-R=t-Z`FP`?$OKpu zYB-pAV=^Jp8QI;^QE}DfD9IvSOmIH~&hYN9o=8ec&ld={yPN#}l|S7`I(E&%D)jKB z{;z?0JtA~)=r@MbD%X+X{`5+`-u3ike#kf!7XEw7Q9yz}~F8 zU&l6gHvIT9$&~X9#t#0_d51&cp-^Pyj&5FgN zcY*&UVad+#ca_Oy^fUxG1fqkyr+-}kY!cK zp==5hQ8R({+1-7m8ST3tlvGkvI;ScA*?I9_EzigR>R{2hEBo(T|6^GMlA&6$ttpxC zfqn}AwHx_K74@x9bs`P`2S+=#mGxXB`dJ@30uoX|8n<2cEW2g#Q~efwg)HwgUNFvr zZ`1$Rlm%>TDL+tA?|YkBAm2`Um4ep{@p~%8FCbeKJn_4Qd=sw1!kwzZjYUNv5ns7% z*0EQf{243Wp=4~zM{N9*jAq1 z9Qc1L2Obtrtn>gi_Kb=5hS$qO#AnHxZ8Cnx7-Gm79BN(Svh{{rUEdb@v<7LZ8mq{v zucDn&j05``3;k*LC=95-YEr?%J>~@N*r>`lZ8!uBs5PZ6FMooIoeCFBJ(d&G8?slb zWZ3A`vUcV+@fw3PY-TjEW)&cnE&5(`FgCU<3bqdaR5PSqh+42)W%-K*4t$?nc;s}x z48MG@cUS#15OSfYv*$b#^9=`1SNMk_=TNPG{Rv0v0fI;zL&V!1LRb86(Hep3J&59^C}#qV4?zPrHjTHTl~uKTpW`S`QCt1{s2MP`gA2vD^)P3d>B&v~>$ z@vjs0poEIBlP)VQR5u;k!g^XVeH=47{3Ywwz@auZd;1)W6iwFm(7|8y`XiMZ!>NhV zSkaNm^=3&9v}m<B*|i>8``eyNPprNMuo;4+KJQSE4IZ;ijd-K(_PIoaN4(@*=V3-Aa@Nd-(N+JU1A zl}{02VACc?KoV8vN2P877a|mg*goqmOi5<@WymU_bI5}#eRwgzCs=F!FFwIPOdAT= z-VHX??ys>-m(H%P@Mqe>i30dv4`S3ZHiZAxzp+Z%>F>c^@_%>fU;F z)9w03C6;8OkpPr;yV=5fQPV&rX!p-V%(_4HwErJ>f|d^e<~>+|zmEn`ES2fOfX{!i zRFEZC1`_C9jwX3yUC1(ZTIP^7Je`tgl!nT;e(vtdmuWNQX$~gEW@VAehOL6K#y}^g zpM0){00-c=9)5m@nD}h-C<6vJIgRb_s~_00*-oS86R;|P}OZ|~*oIER$f7JSaz+>nh6jf%>>-fzhOz_wF$!)9Bf zh02YP&$;z~ur0+lYycwC8USlt1oM&@7~)^&#F||0yapgRuSv%$4MGr5bVujEnux{C ze2iug;3!Z?%q!{0ko>Ub0TB}~i8Epym_by?;*5KDQ+sc0T=r&{`wWApFyy&g=grSU z-BLRTG#b@D6%pw4HnJ67z`G~u^(TQT33P^S({ z#^nL{kqK((!|@(PKR|Q*bH+5#)L3ZM5#;YP*O}}s08ZJWW zO<;Ns|NL*bXv7Q{cP^arsv6I~Qs9`(+#-KsV-3^mD1p1m^Q)neU^XexEk+ou@KDl! zz3{tWdWZd22><`Fiys;eknBe2J~)wmn8lS9dE;LO?e2{ecxZm$nZ;EXPMS^+kWg=S zn~2xGB@ai^Of|#B3O;T|K$?0jo3Y^joDfq^RMekKQBe&vMdW-yR74G?o(5w&%m7NR zH>6VWOLv26GsheUWZ|a@>@K%meo^KvDm>iW8Tm+P|K!OC`g zg4*o8LD+t>Xa6pe`zCO7Sn%2kOhQ_E3d8;!+Mh3OBKlw-n;3ytx#+gd;_%O@L4T=A z1+M{xe&Tc*^^!9yAgiM@GYo5N1TaL(G=Ac-%oJz zE9tq)V~^9JMq1|1QP+UaajxP}qrm|GU{$Mka!Y&@CoDr3zZ8R3K|&7{qd= zW{Td$J-`sushSl>iaOIz!UbWHO$~E4iYt0R-k?007@7YMBrMQYoLrm}M7};rbY&|n zMUK5kbTG0Q9f9hB%eP&(@tn?^Q%HP5WnftRM3A{lbE#5aUeD-X9{UP{?%wLr?)E6k zD&svHy;>XI`bPKBgZmT9Q^Wa~5%J|KsFuB(MtJd{Sks`GW>{Pc|A8Ba3Npwjh=5&j z*P)7dz)uk|(tzXRb*;$h6$#$7u;H##byr3^b#YZkBdv7E9!!x`<34wDPw8mkE18&4 z$Y6}5TUM?zI3$Sf2B`n&|efhQnc!b|uB;5uBefDLd$ zM?zIJk-#9EQ%ilR$D`;(RPVH7#w#~q=EyeL6C#Cys|Uuex6p@ob_xqRjAU@U*)ijc z$m>%cw|v>DBBrYyg*0;Z917(8_6H&R1H|52%&u#Lx8oA8&ZyCQd`$&ze_~Kbogi z0GA7*LyXL8;3VVlQPu@Q8-Km?UdO}AO(@>Wjvd!h{4sz6HY)B3enY_(&(W`DiAic> z(!=G(iA^Kn&Pbocn6o=wNe+S~y2|38@goN@9~f0dy2juR{mUOPUx1VyD!^vmyqjj% z{(fyiWw)X1b6WZq01x+W@kW0dmm{Vq%PvHN?GR zDmxlGKZVG1KO5zP|GXsKXgD{|SI&RB-!5N`%T?KN#Fdbs-L&V;;&4vphh_^Jm|5hY zEHp|4ow}m-d=(5{RSrh=yAUzJCsPm0`w;_!#sHqEzr^r zklCGPS*-q7$Dl#|^biKh!oMN;iVo~Bs!>o-5S?lo0*ZKVze?yc#jU~?A>f2e^n7T* zL_f;@uqA~_*r1Dmwm3UGs-@JhL{n1Lc~fvr3kJJ-d3pU>MB^T7PDg5R3%M3Cl7OPm zKiq^u1)K#A#2~Z{`zRx}WLX1Cx701Mve?%`J5YZbj?{phZ7aEQ z2J854u>wT|_$N=0d4prvP;l3Wfn{J`W#zB|~ z@dG%+K6~`93c+}R$(c!ok@mwHO!~PZ_meeLfDJ!QqJ?Psp!#m1e05unDD}U(Z$%Jr z(n)6hR|P20+9SBHA|gmeDIh?b219j&PoNHxeq3F@Xu1%uKs*V09~l?$4yADM2AZ1! z@FVvM^SlaWHT+Pu>av6kN(NuYFo6I#CGxmp+HhaRKOrHzoS5z?Fq7lDvp@+(G zc_LE4gB&lSk1ieTScu>wAm|79-7KE|#EMo`P~ZS)9bP_J`|+?{d-uDD@Zl;-8BG}b8gX} zP2=rEACbWW&Pz=WaDz)($W&f{ugs) z=ro4Rs<7n8P^x*dz>4^?crzd3Ht2^u{15`8%ZbSY^^`yd9F@N#0}C(=%t&A)8>Gag zuX+?vds)BXS`x=~ylf?J<6PY$sYdbg8H%J%u|8@7LiK@uD0*dP^qH>J!6jU7F2#1t z(}TR8K#vW-OK7bGaNS0-cr1QlLr(#U;0u+xq-})RYHBy|QCq6opczkUW@H zIZMB}w-?uQZD4;^WJ{yR_nBev>sYFVtdRYPpry}na}|KCL zbl7_LJ4=@k)c^wP&0)sQwCLm%e)oOBt+y83_vx3*_o9zr;K1Dsc#sKxgc#PZ@{<^h zpm+o;i!(|oUT!-hkk^uG?5f#~oMtq$K=~q7SW&{(tR{!6p{7)=l&;J+C~~0mn`y$V zw)L52N-5EB$3WP#>zl|d-z@X^IKF{&1z(BwbyM!a(a!32F7g4MLK9gr*7%fdAf`v$l3*is3gv}7J$FS*4%51(YKBZPVh~QM zk=0##p!l_Z97YD5#Gm9}U*WWJO^8V=yAmdtlXSIT8Poe#yzCS;^!D_RPdi{Gf{nyk zc{=}f;D{G&7uf=APwVP)-_G-QJ%>3?TYa0e$$DiF8&1iFm1pP&Puy*{31AV(KFYzY zEo$sIfxCu>9fm$IF^Rli>-F)#gKm2lg4JAhxrI)KRdHyD5@$EzNLiBBkAdLS_?ej@ zYW%O1#5SDbiXxw!o`ZpKk_9EU#Z#z6F}5?wZmj-O_?$vmm0c^MkAI_;rlh1et*nq= zuCtE}q_9&Ry-Qz5FDCCoYvAPZ@P7nIK`(lAWS6c&ys7KokJZ3MH}#rkqcq zK`ozZm{Rm_-$^+ei1EgLn3>s>Oj6~N4aC7|$v+M%h~unQIj72NF*cn~`nHwaB_|PX zO7!C6M1A;z^Yq?$voj5^>rS1(pM_WE%Xa~hyf|5i%}{>0K@vH~5P9S;1$LARGb-9s z4q!gYvTdcNoNaQI=U?0fD`wh|M#@G3!kvhDk)VWgK?#rKxt07c;jvJ{2~puZe#jWH=YD={B6<~Ki@~=WdKM1}hLQlWz zqo(a>SwUIbUO|3SN7K`)`YaPFR0x!0B5i4pa6>4de>^-x_R$Om6FUxhU>o`gUlGi# zPQ~KPtdgX-WP|bO2)+tMGo*b2fGFmO=CzO-S&j&X6tLwn`Qk;fIn-o)BZ|j4B~Cge z31~yUUpiR*an9`h-rm|<(4`u>_HMAP4{R6aTC>mAnU~$T-VLf58txmuXo{@_!uMmk zTY4S3zjcV{2ZfQDNJSz>13gDhw+pZLQt;Z25*c1r^TBJc#&2ViEh#1mOhfndhEb$# z_uwe+^#6$m%eccmba`)*luk?_xzmkCC^0P`RY~;j zfQ0l<@uQ;(>8HUKvCAn`k*zeoY@&Y0zkB=xy$QyFBZd<@cC~N~CQb!X*?4<*<(? zKp?OmJA3`F2BKI=f$L3Vd^zx`xz>DXk2LOi`!Vyl*+GZvu|lY##zMnEvWAr=I~N@K zVT7L+?W9dm^&rF&%9kGavLc_9_-svbb0&<-Ev$f;M=Ry#fJO0DDpGaNgoO-md7M;$ z0a{BWY1xemWmSg4TZAb*?>_DAw44%sM=L|pJ)RADtlYNSEt=Q=psnFPxQlblknip! z4@wP`b1xgkVY}}w(JKpI;P}5^ z`#xK{arac1CdGn4T-bht`qFCqD@n~>m#VOPK*Ng_YZyf?TZ>XWK6%LN_r}5HhQ&ba z`&rZ$RpK!65>Sb1BWiR#XSG;3G?DW915?d(G!15}t~`TEyo>ukv@Fz6zpyzKZ&*QO z@yBUnJ$)G+j6%TBxagE;W?>;GYMgUveCo;Tb&|Z?g0XXkc@XS%u`K{dT=9fiGZ;a` zK(T$__3`uLjf#1@7+glZ8J(+sVWAf^O1Rvs5#Dt|;E=8~W}+3sG24(u*(-uVmm!-X0vPV)#;C3qFZGd18Hp4os^V0) z6eUq=-Dep|@z#jrAPKRTi!2t_8*=KiA0@iuQR*v|zr!U~hA^{4jtuWZvYP&Iwf?MS zLh1aq=l(NegI>|ZMbqdCe=-V~GFP*0JU|vYF`#iJf=aODRkrlGz-4Re0TA#xfLj%M zbCj}WcJCi>O8R{%5dMQZ7WMk$2lc=N)L{$q@Wy|QANmIjnYZsv?)@Kc2$Nn`*V!!c z73$vk>RDiB8tPYzJ_{SU=wv^6deX;&Zfco(hl(STMwK?aL z9@>;nZy&YcURiXRa6d(kwkrJ^rZU^OXTY4Zm)q$WOsQne1NXx!npK{jre-!!yj))= zLtjVNU~H5r!?yH2FHnQjFQ}c~MM;toz$zF~iN`oosv8|=_fM1 zqLNQ6uNsN-BpIG^0Vh>R~B*xA+hJ8p3ac(Oa+jHcG_{;Z!~ zj;*O-v*#EMDJNSxUCkad1MeXV1ilS9u}e$DKPGC0z`u?f5|zdw+Hpj>{0CWzj_`PA zXQ<}hLzPZxh!?{u-j5pJf`c2J1vnPl;!0CGVlJ*RmWEPemrygB)lmVy1Qbrh>e6uy z5e^)*j4cgr+ewvU@+A0VP#u##*h@9q;ltkyhL?ShF1!7G)LW#~FJH+Jk0vySJH5pV zIRzAzaBn_);HrKMaB@*EERUkQP@F3hfHyP$1P>RtzqXL>(mx>NW&$Rhyd3hhyW{;+2fT=(L+i!1_-R)7FRN9OG#U_t3UhPHU33gKMuoU#Lu?V? z4Ezv3Wk*+aUURz~k~P~6bB@!t=IwnuBjMjDm^Q?_%}HQv2aDN0-P(Cr%n>-AulBt$ zpE2;+tg;vQ4xaSeOnm+Bs?k4xz>q*CuRY@#y>h}l z!+VclL!ad{in4N7rU@KPl48E8WRCXr8YATOIZJ1rSIS$&alm}W88ceqF!Pj+P4%|I!f+LyLLuRPj$suBjFaNndad0vvoyM}7X1vZ zfU!L@$LhA0L&e#eQ*rLJ&-D?Hj+kCOexO4b2>O+Eoz-hPIBG?F8t2LkYx}b?B5y<8 z!{AQ_jY2p{&%X19x<6)*cY%XOGC|;MAi*h0|8?*@G|1i{hTUJ+o)0QEF7Bu%{^WYS zUh%lbX}98MW_)ck(+cqN#f;5p%@sK!Zp@RV(>#Ee&;I>*VAHj2z91H5uV!G(Ok90= zRD;h<{1MDKRA`pd>A4h*fH&$iaq65qD0Hw;FKy`M>QBrJv7HOObb-bvj_QtNP!{of z3QVjZ3jzoE9;^YMdm_Jm8qMO+0CUUUV&ihpDALAZOrEuU8XggF?Rr&n6dxE91+1Hk zvisdXhXDhp#{97XuGju<>)h;j4`Rtd&eMvj1D%+*28-IKdSY0_Ff_9)ZnWm*7WlKv z3)J{?REdggxzx|Ura2T3zL?*L1$ugb&c}`pKULb2*IbdyB~iU%bR%At%OyBa8cu*2 zOh(=c`S9e&i;u>!o38y^WreTo=s#6R;%^~*Li)g)G z7OvH*W-Ts`xPercV%g9myRks=I2kLfXJtt$Zi#9YDGoXq2iCl(FmT=wuqd>rk<`-g zd~UzUriYrPg3(Bb7aPGCb=?+|1S@mNhDih<1z!_tA2=po3P=HGMfy}HtmmTBh8LFj z`QF65+uF_LpBl4SIo%GY`uL=z>qb*qTizo(OjceT=n0Dq0JE#E^d0^`k^?x=N(IVx z%0lN6X6`!+M&0jEzJgo6c+81oYkXD zCAM@jl9_3AAuW~T8hjkrHcUm|)dr5{oQPqK(T!l~k@JXegm%T^oxiVX6Wn_4^I`V4;I z#_ca;d>Jsi3g;#H->@j(0PMk@xX9!Gu11Uj%6eOdZ*}z=YzdxuDMnoHy&e=Fo4(>B zkmdMPVO1;}QaG1W8(#yg&lGAIJu%nx`FG#7S(n+LVOA!_uJ3aeiv}UmiCS)$sP&i> zL{J5V4MSa(n%igDPCeRTz@H*u-KK!gEmbpDS3N{e$45S>z?po$v@9Z-Oo@VjWEV@u zi}D~%^gy&KSe!Akp8Z<*@iTONV~4&-Htk3G8|E`o9td-Li^@rGR+U{(t1*e^RV2`C z7wW)g&svu%1CGQ0E4TOL(Dhu}Ga&~XrMG*mB@{S5-`?w{2n`xim?}VS)prV(WwO=E z(8n)#vx-G_CD@RNMX8@w3KFN;t}6XeGmwB2vlHT0V*ckjbSW!^K&jc;I5RfFfiX5Po7Wwicns7H2WAqh&*(8wPLghszd$Ezuy z{TdQX&F8WH;!%4n{qxB@h~QGqv!=hDWwge6Q2C~Zc}$b8OVB^8fdXuSH`afT2VEu$ z1ldfpZ+S&kYDqEl-OD&z2piF(cp>D zPFx4>h5>ME3gk0)Tc}vf4n@+6XFBak-}WCLJL$IC1$TdTe9)B zWrQ#&SpM;LeeeP_s<@UBKYrnE}DT67HlRLD(us^&DGlUv6b)K zGd>w!XQm7J6k=GOj!1uSzh&2|!-g`ANT5fOJq(lq!E&Gv+gJ#S?@h*z)@xiRr26*~ zX&wio)(>K~_AkxA^;+a=BB#kC8OY5lxbQ`%n&G#C0EUul!e>+X$QF-|IMpV2vtoas zlO`iUk3vnO(l~2e<*^a+4nZv4I28P~m<&pNZ{wHO%;s_$4Xf*U8 zVD$c9Q6toetYBfgzdOmf8Nup|buK6vFHJ_2&q7*kYYf<$$MdmM>4FnB$7F>j`@W42SiCB5PfXdKrFvOG zBCK#+!#|0Sq?o+$?pHFyY?ESCmVm*!pm2MW<)&Hx|F!qkVNq^t--2ub1CTHX0cj}# zr4iV)QUZdsND2ayLk&Y%w1DJL(n@!i(%nN2N)1R!H+<_E_ttaH`{My{vd`=m^k>pg^EwTd?oc6N^| zmBcSg)Mo%Gxkn=yyTaxTa>dqio~X9>3S_BPQQdu|qezcZk0+nPY(vRdlx24hj|tav zr{wY%S57;(2hyyO!%oVngq44=^t65p&zL=4IZRCwtl6wO>o(iorOr*p_lyhS;t-LC zK`uQhI*Wrh4GOD4NdL3HO%sWHrNkI1IqmVNN-F9reV7sRs#*yJ1$nE==`qz#%Labk ziPB;il0D75r#)qAKaxCAkRAr#7~r-1{8B@|w%PTx^x!PgYk^}|ZKli3U_@G~D%(Ew z^9Lm^$FPfCC-OIwnduJ%E+?6zp6@pX`h^)qCfiuB3n2_nel*`=6V`u9e0?Y{qci@t z-u<4aj-GjL%LU`BlZeC^!48{o*(*7x^5|oW9+?p9??_<tm{ONo`C+R&d-vk*7JTLSC~!^0t^Q`?~u$vg(!q&ALS@4JO82eHz{D$ZGreB zLTGcaK|j{;{V0Q2Q@35h{eZn_R^g=gTR;DN%ZiD;=c!>GM}~63d%uB^+$9zXkZEq3mG$>$F_&W|0m=WZ1lPN75; zzvNH4cabml35AX1J9ZFh*BRHvv9m|n#0$4Zq?}WzRd_OJefZ6IV~7;GTmcEhz!#~Re#WFW zf8TRkQQq@;ur-6yo5cg<`pv5hy83o+mZ5l5;H2i`=SB785Wo}#)$GGd^pXX+gzmry zRROg?(@^Qm+j=ht)0hmt{l;q#j8Fn9N7kI^hA;<`-!=kV*4R!+%gj!?HhisHwe|%m zIWaP|;Sud>;W^IE`;z)1rBMb#@u}w96Sfhq7zAa^wUIO_kqX<@JMK0)o-RpWr9Tfd zvN9_+mTnVdR*tRR&l1;V7ofe!R%xjp%yHo0Y|ThjWOC z8~gix>PulSrw$Or_hUYG!{(NSc-_&QeY?zIW|AQN)v>2b!OBI zt7mj{#q1J4a_wn|4gIlJw|HyO;$Bwbq3d>-OH{};I<4Sq7PsUz+f)(}Sm zIl899&jM=mtZPrx+0&FdBF*}rmvM|&Gq?qhoCsp<@1=w&8^-SzcHXrw8h?P)qKPcrIZPjKR~1J+&G7e)}x` zR*^zLys&;bPU=J>l@8l{eS_4F?Wwnv+G7n9O;ms4N1v)i;?l~?Yn1}cl*X=XXlqtU z9{wwXkF|}>f?TQ8FExwl=YsmBpFETlc7^t#V zIj`{`+)YslV)pZjCU-+ejH`FzTu{fC*LA9w7+Gz`+~o~)Dn1ak4yC+leNPWxIe9(r zyt_Wu4alVTHb?IS|x-nIsr_c3PMmIYEj+KRZYEWid|}c1A(uj#<&ur7`2asAWy3Fv<^I}4xAWq3c4uUmaoDnB*6o(ndups! zWh)WL^uR(tukJTHG~)CsH6`t}gMJzK^IiEpsI@Wfyxh@c>MQWU(m>u0+xH3F;Zxjt z^oem|k19=JZ)@{Z_*aEkx%0+Y-D;PZgNh$rO^>7BJ#&UfPeEEzLl=ohIC*F8LoWw+ zh3V8~T{b(_9vl1dVxAo_46WF_UHFkp)@a@kHELyoCp--FYhfg zeK)0mV)Lcj5y?*@Glo9}+s2xvpkiu8bm4^l#4(MXSLPjJ>0Gr>6Yd6{S9DKwvkH12 zC$bjjBL@o5Z$V^x<2pg?H!7SQ@_{TZmA17}DYxxAAvJD;7KcKcQ%?Lw>%H_sp4Ae; zqjfXMhrWeE;v>Sx^k^qWwatYR7cF;fL!V?aIa{>5>W1Rer%^khf;u7Gob2Is9PmV1 zX$s#dX4)ohfOrL8;h^VDlFOaofoD%h6@$a*HWO>J zCd~1kx_iP-n}F8XO9c!ZGTT#NsV6tYbwd71C$RB`3KOgF``Dxrs~;q7w;vSWbw2FA zT1S`0#1uAJ5g@v?vNkBx)zNdTt;wNdvWr+3nFAt%djkC{-nlSo=)V!@%YntIPU%41&6efK^IWg4yN{v-i%s?8_sgQM?Lo%D} zPMv=F1c!{r7)O>Jy`){sx0yo6O=ky1su&TYm&KoMlm+K**W8= zjc6gWw~CY#sM3c0j7|-DQ9YOYM6q)j;$yavK6gS2#`hZFvtv9`GFcS&jwYyfIIU-n z1@xXJwrCm$DlzIAhp|s(E9ZKEsD*!hBc4;_xv9)?l6pK(0-j99S}ehSKoq**f%p>d z&E3v8i=M;Ub&s6No3m-8<7ejEpm$XP9335Rehw+xE-9;} zeI7sa7DnTjF776TuF>#G*1U#zHgvA);$(G)Tt~iv>lMb*LdAhsf@eVrNCG9n9?I0O zyr^(1$sG|&kBbpCX};Px={xBHI~M)Z>pt>#?J>;>;Z02?#7d)9)06M}h6M|vW+q)o z$({D+-OUt>;X2PX7qpG$KRC_BU#{tD7n(n}FJ4_Sruhh*yxLYhjoWHlG|_7ALppaO zkuXQ}c5TJLGA5p?b-U?Uz<`aWXsq=^@>AEbPS>S^mGR<8m9ClzG&y2cy5OigyFFzb z&`KrNbyG{zwp1Wq<@RO|Dth01(g1PlOPNJH8h_+_2DcVeAhuU}`(FH&;(;@ZGX$xk zk~|q!R}ZC%G&}le6GfaYxPe#fUNMg3&FU$L5MrL<*w23O?XKD380I8I~a^2^?ckM85g~?m(VpEg@BNhe-M4J7hApo0U^)fD<=s%< zjW?%C$)pY%s511J8Qft}18Hd+BNqZvtb5b$G$X4l#x=M*sNpFGZAN?zTm9dI_}SE8 zL*NWKT&oP(#-1a*`MLcPe}P)aP^!2R$>4qe0>1zyB~`~Tq7t7OL$o$am7-6&O(nIH zK#^iGvyrF8D&BCHkY*Hxt6QICRnNzy^6_%<%^k`rmD3pB>^eO$%XjeOneT+<3rJB( zaGZbPws*u1eG(2mX>WOfu1&E1_grvd7hWFCo}*i0shU*0rRP-mG?YBHu_>&`JZ-R% z`oLxQsCQNrCK9^-RD8tJ{4I=%y8k8mhkdns0bWzle9OqGo1MZPgH^Lg_mkNYb?Yfi zo*uXEuIzN%%iDt2fCIAd0n$kJV~-V=?Mg4wtqx?UbUZ8K$Zh^&e!n|)%i3)ly(>MjlteL#j{E_7?IORuK);Bb5w!Y5bdNN=ccFT! z$f|U!Yw4DlqE8|h4NaBkW?NX%1`-uH&JRRvA

    iN5KJsyrP`hkp_)N%h5wRI(K^V zZCUsv*I&1#m}n&4=r*9wBGS(#%Tt=))-CF7X50gSU@4BRmxQ3RoU>(;Hbehs_f7JCQ2*XWDt z9}s421?P+E`j=61hqZorT-&}mrBN;d2@k9GcnpGJ@uiDFoW$aXl`C%@QhIj2w9Hm8 ztqm>2IWTmvuh~Ri64^z$gj@ygSK<>?1?TMCzbv2NrK!=GQ~QCXM|6JHu|!~ZA?|s# z?)pb{X1n!3kov>t1LJrV0x5~*W{kJ*F}XBj_wm&Ud8(|filjGRQ4Meb_m}M!-t*($WSWD! zLok01<9IgnZ1yUdtxqyqaO-UhameIJL$N?locjP;Y9p+IJ^_TCKJ*gRRDpJ>(CYv4 z!zbkO3O>_&1u3TJAk+|ha=4Bg#>N>p;&O@qQ(JW<9=>kcgzeAbdu4g@>waWrewc3X ze{J|##|4C&jwZMEQv~_RaF1ug3tW?UGJ~gbm89frm6kqROT$e7E7-3qH9k3CUOQiY z(}881+t4$k+sLr|nDW`Puw(ueA&bZl4%cH)(>)mh%D5?IyRs>mM}~gi`Po;`+=bA{#4GoGE_*aEVj$M|+1{qmpwOxF?%)!b1MyF~o z3Ep=K3nQD#g$cHCW)A1u6jkG~FJ<-rtc+K9QXFF4wOOjo-&cSpOLb)dXb}ARto7WT z)_tCeTD+zp=3LLw#-Rc#LjM9vQBXT615z=01>;7*XeePj(YDy%q)E3HIX*PeJJ82P zoMV^Y+_5+TEMDH)91uESFV4T?&K{%F-JuRMs@YV`7FFZryD1Qb%5eCICzDeu*uW?_ z92Z~nBHe|ITqSz{hv8r>aouh#+m5UoDLJ>x#zk*BaH4b0h0hIOZ3gcJ8S z*E|`h(D1T`-6fACKPb|2$x=wA>Muezp0Iv*OtWfn?r-8K$x-l&B3|Q`>avS{vO7~( z{f+u5t#Q=1$F)uwpoqyCn^bPJi{om#oxZTX&de%I7~qDng;P*%zf|T;zK0msb4aTw zEm9$)qV?qJ?|yjf)_%$C&j$iI6MGHb4EE*ukAq|9KCD&SSI`W98`nz!| z6;hAzX&uZuhk2$S7;BoPujUp6ZbRI?L+FoGP%Sn)^7W#HxcY^)PZn>QtoKtuZ1G4l z2Y%!zuR1TEuD>R-?arzG4c9w8DS5imJ7pHnJO{hpUEDkydvaHx;F+wf!)9h)m&4}B z#6AA9mKIc4tlZ_b;jOp35n40))~8@9tCl`D5JG>de+{bQe`D3^X>fv^#$%;r+!;bD zTwCsiRQSmmT3w{}bMS*LQBlmp-n7or!`$2pw;VRqG8AGgK9DB}GmNH_PAd&*~^578E<$=DL0 z(%}+bELe*0oOmF5HTr&XNlPSN)4>V17o1?v5V)LEV|n7=rGq1O$mO^QPHS&)?TB)A zGV0_>N~IbrD=)8}OB6pHq%~dHFfHYsE~9m??zXG**uyWhMR6@o*425;Uogzx^elu8 zCd|t3>{AI(K@|>iKD*TM#K`Oj{Wl@wn1dd1^ov)Hyx}2-owHrupTqlR5)7&}cc?2~ zOqd?Kw{4Tjj`Rq1bO}*husY4BwDp-D@!sb(pLpTkjRHyQE^N7|$N02wPRJ&~Lpx|` zI4a3ycZe*_)&?W25MAl9?OWDe{D=r-!V4VZ1>=gZ#Wr_hE%@SSBb?qavs&WLX3QJd zFxSPlJ;)M3y|5qq&~gGU@g7TqGSo}_!1UGQY2I!QHGmGU)^kP141!=KyUHBb-HTME z?22!w_$1%Tr}vVm1X=C?Q;*Z-A9>JY#+W%!Iw$mZV7^$^=5wp0rBhP8#-e0v`Ke}h z425=q+5Qy=zN2*Ohpkr4F`wR^bst9ocE$1AC+YEcc!{l|E=0E3@tH3@|EuyrC)tPd z?J^EtGDwI1#%TW3*{_ve+@$1HTMP7)hs5s#@gi>uJyfM5MjU5d*{bChWrQEdF>_FV zL!4rI9*pj9@@~GSGMV2N5Ux_+i3YLe2$Mf?EMucN+7q>7H})21Cs+&qflRV0n7mbt zk9ll&=W5(LaiI8{b94P@jVlLLR?OpRkv%aeafDI9XKbMhak$kv&d{APl_GHz+=8J{`^^;rI zzVAqH->V65Mi2Hmvk^_wR=q@@E$hr5A}U)I=h%$OLzOi>E7N>;6wV|3W2M5>O<#K^?>1Ms+|i>3P-6v$)?|E@&1JTu)k3{xQXL$KYW7%LbYb` zYln%OWEOXI+mKI@iSLIlkJjqDZLhGOZZ#qN5@uQ(d^d{LJarwf*W`&E8Mob0c<~Vp z<-*66P6v;#_cNfJ3z7lqiTpWN*C!FZr(t&x$KQFYiknxog2TOCL(fN4R=NUadI%MA#RS zJzA^P9c?O_o15^izfnfttWn!W$Suir107sb_+mw~0y?o;quf`1)}N-Vafy#G6cv1( z(%mH~)rfS#Vx`?Z#u}WeuravYr^U@Hl z+;;BJh(c_N*2x z7Bfhk00%8?OM?xohd=5s>;AEBJkZ?wHDNNjWw9|z^VNjS>gSq+!Uks_%fv;Dx@}J3 z(DiMb3H}`36`G1Vk2xA}P<9igLisEx&X03tH+>S{)WS32_{cUZOVBK)2j0mD-{I{D z9YmMX-eczGm?Fu++b1?t2o)_#eY=XVX>;HC!5vLl5^45%#Z|p#T}r*FZ*;>!c>GqR zn|_Xlw*6}L=9Lgo62bw8X`%o*goBevsJDz|K5_chnMrLkze+zdKjGtstx(KVVLbSj z_F;j#7f3&{E+y_wt=y;_ckV{NHq>+=6qoA*v`r=RGRRE>z$u!+1k31}8xQ)pPQZ|9 zMW-xx;8FaPsJfehqfFvm+SOd1(`@|RwFG0$;_FP-I;DZ0nzq6S<6}89g#`oPb2GZW z-*xZ2#gB?DcU$)IDC$>^cptrK>D0tF-wcb_>b@;7BQkDRG}f)g7bW^7yK|r~`(mm< z5#qGxg2}rI*HeDJ#4Kd)U`hma{Jv#8!)cB-v#|4FW1vF6NJe-J5)BowNe{2|fErl~ za0>Tsh{gv0u93Op^f0lO+Kg+u5mV7ykCi+)zq&a6bblp9JR;={(Wt-QBQv3Ik@Ksa z$hDJl1?4~vrqK5n^rsmYl~o7l7kRG=(FA3+)erblE463Y4w%N@#mQG%QgnY~`5f06 z-oj#RDBw`TMKk8leELkLk<7fioxbRfycDwZA-EXdu{1Z`wqkT8ZOfx#SzMD`iPZ5R z=Qv2|V8Ciot*ZdjYh1z^d(C}W+Ae4&en~LIt!6b|Bz8$-M8BoWB$7+03&ckaQLEnRui@38vXT6!)j?mEci<$twP7=c*I2~q4zzGi9Yxc{Al4-OkG>FA(8a%Lf1_RLzL2wkE z=uHL^QSTAj=YB9>f!ZwsXe_8frdRg;3Eew4Akc$U4u3!;EALr=lwvF zri2a|IbSC)(Io!GcU+V1%wslFG$5o|dmVTVLOb3CM)gxe!v#E&w^9;_d?s|zS$`>P zU?>V)(UPB0(q)3Z`ygP{`XXZtY82kRKyhB5u%G!gg_i{79{?P=*P0?8X5f47K|rVG zv*lX%C}zn%F)Qfoj3D(-fK1THv{%OS0ZkiJ%j;<{NEv$pd3^bkxA1>KgR!(>Q~@Vj zu90zs5H)||EdUA|%piE$^~$ew2-Omvw6OFoWgU#+b=$is3Oqv!N_R>cflw0(4qiWi z*&>zUxj|myAmKU|vMHv7h?WJ2_E;{#6N~Z0&g3HLg(njw>kVF#DlP(&y}Jq6s)pC` z>@q<<==(Y6@?wz^yiFnjsCsm(ZMPZl+FM^)jBSuNKlddhytS?SXEnaLZdo^QS%XJ7sPS>08N=~ntz_<^|OHG z-*eCX4SM#1AWd+5;Bp9KJD`=bkpkV3$&b6@edfXsUu!S?s9cEWI8b-V*Q9k3A)qe}FcwT=AA5P3U1G2)wn_I$-;I3T^^`172^#B!n(2 z$Jac0x4{pN(zsP>Dum}y-=Lw+;C>_n+i)t4yY8I?wW|G%?^guNeG<%G^Cw*dnEB)2 z+ywUNHUJP&DrLp|E44kni3*MKP>Ev;HNRSinYq#Hh+PcW1kwL; z6K_JqZu-8twCN++KK>##^RdC>0{Z{ooA5j_yb%^tWZp8RMoYWj=gm;)a?DS=>y?h> z1rT%C|3b_m{AJO6XC!{@*1M}0)zGiY1UwkWcW9ONoyxI#Eb$$ff&1~C=CX8|faa1k z+6S+|AMgNPP~a~c4YcQ$laK&b2nvA^gmbp<|E-@uz1|u^lT^4)&iZAXkRTqwJ!S_2 zhFcelFdh?UfBLO@yem`SNqG%0=tG|1p9pfO8Bln;f*E3;&0F* zR#oY~{sFPt5`)+qVc>Ncxy>z@nte&m-+%5E1(lk!r!rPsz6OKh;Hsbl1)dKxFf_%N z)5IZ}eF2v1D^j|3(OUz^S-M)31D2?a(C%Vl<1YM*p=reHj|Jb-dN8*UfjBjL%DFSz zcL8M+DkgUxK5Q8q01-=77g)2go7J*syj_3=n|TPnKm{TMH>kC^8IfC@#XTVdTbYXP zd-~tE!pwTBex~j;Xsfel*GHy*{Kd4QpJ>%yO=@Bk85Vw94uOyl=k+doCqXqFQ^rMn zFgM9_NH;>bYoz`|H=treBqQc`3#|m5op&({D-o5@pS7DQwDJL0ILT~l-iSX0`5Sl6 z7^_@>vTJ$79Z>oMVFh)0qM479H9OB7b)3?PRSj!wQ)?ATAPsVt*ILNi1Ta_M?&ueC9oohqOm=CZ(1` z#W&LS2j(Iu3LR&NMxDP}#Oi*Y!+s=;4dnH_cZIIveuL~HrhLE(?6sa7h?eJdwlP01 z7}!UR2!Ama=l_2}HG)>IWYVogluGT^HX_`h#yvwNl~9Wd#Jje+hZ6qE5qG|Ecwixs z^#Ks{#7@J4?B99M0g3VTX9s=~mS8URrH)bT$|$)(U!04`JwL4O{Zv5pKSV*Y7XNHG zJ4P{q{}E{KBLeMx(&~qpc1#F4MaMxrzDZ9gu2yb~3|8wVC^A{OqqJ!E6RNJxSpvy; z45(O7#7P60M-O(uuJI2k-w0gPfa?zb@@ES8khd!2y8mhigDgB2kPli4uUYjovBcV?! zE@3us?5*wz=fV#7?w)r)U&dUJ;gKNx(%1I?To&jDT*~^ET=4G^MLlHvoh=rxK`Z*X zEEPP__@wCbU$Vsa!A+|bR@mMi$hYI(dQthKy!yDR+j#+JcX6Wr-Z1_d*uaCTYnOKz%_cGGdLlO*Vh{qsvNB33IJJ}cCWOSfz{Yi%f zDR@U!%gdz<3;F_+gNEs9cRN}%Xg{?Dp_ZGKs09SX{)!L8Ry>f@S{gj_(@&#WyDBb1*k~__us?RJb-0(VcB*V>3(O4wl<%Ld$H0Ebk5dgVz#2 zpvXud9UJV)mjDa->6MT;G{RpSxO$a9-{)!GJy-}HY@`xFn2u&!O6s=jAN ztO7~e8lbEj?70Qh0si$7SY=-D#g#wLcprfAm(-1Dp&{#=z%ShCU)+BWPmpRr=Sb+U zO;cz(4<}AFh-Amkj3@gwhvh~@*fg23d9D+d>l6JhNYHumi&($JJn@_OYgd$yZ{HeK6 z^|3GIA+{6U1)%#;OAOM75YN^i>ut_qL5NGx2-K6RjzSKy!$uJ9>rlY!1nV)dbGS&- zy(jeV&jx+w#Jdlwy7g;rpDV^fU+PnEGcH`1U6~T+QhPMlccq^L@FfWc5a!&I5p2dm z0&OCz!2!UD0FiR@UI#Qov;3+R|00q^Qo4j78F`Q-CZWc(oo4s`X5jo?85gXSdU;*W z%+7pIf$&uGCtCdiu(KpT(!glkZ@_)WV6zrCYuEz2wjW zyd4QO-bb`G3mAqTBT*SygnH0D1oEGN?5GI|VI|fb%riwyPXiv-0UIfiaDgo5OFiJW zXARF({;s)vRq*Zw^JF?M#IhUPR_l+!7QeSiCO^aq#VSGEEkUj&12<*=5LzdUj~=KL zk-Sg}OYE?_{^%vtG8z^pznPf+@dFGR2;h+uc)9M3@{`AIMdTt-%5-_h)t z*-O`M9eR70m_EQLKPOQbNm)P!ggF zc2tWG)B@5L)r)-bkl=p@CM-wg75raB*hS6@ugR@B+3ApoU!lMu#N%1wfD*5+xkATq zPMT>JzZu)Ym2D3nee6dJu4b~bM-@7lr)3vwbVo(Del(U#{qgnQp|SPi$ESG$i91ko z@UO|r@6?X&>t(Q{kc)U-&HjdBz)qghDvITWZ`WQkI|KeH$S6za{`th`{{XU~1JD2f diff --git a/docs/Design/img/com-adapter.txt b/docs/Design/img/com-adapter.txt new file mode 100644 index 0000000000..d80e60eaee --- /dev/null +++ b/docs/Design/img/com-adapter.txt @@ -0,0 +1,34 @@ +Com Queue +comQueueSend +0 +Framer +comIn +0 + +Com Queue +buffQueueSend +0 +Framer +bufferIn +0 + +Framer +comStatusOut +0 +Com Queue +comStatusIn +0 + +Framer +framedOut +0 +Communication Adapter +comDataIn +0 + +Communication Adapter +comStatus +0 +Framer +comStatusIn +0 From 5832d630d7e495cdf320821c0f97375c4622490e Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 14 Nov 2022 15:16:05 -0800 Subject: [PATCH 095/169] cleans up assert level definitions, adds in relative asserts (#1765) * cleans up assert level definitions, adds in relative asserts * sp * removing absolute hash-paths for autogenerated files --- Fw/Types/Assert.hpp | 26 +++++++++++++++----------- Fw/Types/BasicTypes.hpp | 5 +++++ cmake/target/build.cmake | 2 +- cmake/utilities.cmake | 14 +++++++++----- config/FpConfig.hpp | 11 +++++------ 5 files changed, 35 insertions(+), 23 deletions(-) diff --git a/Fw/Types/Assert.hpp b/Fw/Types/Assert.hpp index bee5710995..bf1d4264ac 100644 --- a/Fw/Types/Assert.hpp +++ b/Fw/Types/Assert.hpp @@ -4,19 +4,25 @@ #include #if FW_ASSERT_LEVEL == FW_NO_ASSERT -#define FW_ASSERT(...) + #define FW_ASSERT(...) #else // ASSERT is defined + #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT -#define FILE_NAME_ARG U32 -#define FW_ASSERT(cond, ...) \ - ((void) ((cond) ? (0) : \ - (Fw::SwAssert(ASSERT_FILE_ID, __LINE__, ##__VA_ARGS__)))) + #define FILE_NAME_ARG U32 + #define FW_ASSERT(cond, ...) \ + ((void) ((cond) ? (0) : \ + (Fw::SwAssert(ASSERT_FILE_ID, __LINE__, ##__VA_ARGS__)))) +#elif FW_ASSERT_LEVEL == FW_RELATIVE_PATH_ASSERT + #define FILE_NAME_ARG const CHAR* + #define FW_ASSERT(cond, ...) \ + ((void) ((cond) ? (0) : \ + (Fw::SwAssert(ASSERT_RELATIVE_PATH, __LINE__, ##__VA_ARGS__)))) #else -#define FILE_NAME_ARG const CHAR* -#define FW_ASSERT(cond, ...) \ - ((void) ((cond) ? (0) : \ - (Fw::SwAssert(__FILE__, __LINE__, ##__VA_ARGS__)))) + #define FILE_NAME_ARG const CHAR* + #define FW_ASSERT(cond, ...) \ + ((void) ((cond) ? (0) : \ + (Fw::SwAssert(__FILE__, __LINE__, ##__VA_ARGS__)))) #endif // F' Assertion functions can technically return even though the intention is for the assertion to terminate the program. @@ -81,8 +87,6 @@ namespace Fw { // the previous assert hook AssertHook *previousHook; }; - - } #endif // if ASSERT is defined diff --git a/Fw/Types/BasicTypes.hpp b/Fw/Types/BasicTypes.hpp index c6c25323ba..a1a8cba72c 100644 --- a/Fw/Types/BasicTypes.hpp +++ b/Fw/Types/BasicTypes.hpp @@ -23,6 +23,11 @@ extern "C" { #error Unsupported compiler! #endif +#define FW_NO_ASSERT 1 //!< Asserts turned off +#define FW_FILEID_ASSERT 2 //!< File ID used - requires -DASSERT_FILE_ID=somevalue to be set on the compile command line +#define FW_FILENAME_ASSERT 3 //!< Uses the file path in the assert - image stores filenames +#define FW_RELATIVE_PATH_ASSERT 4 //!< Uses a relative file path (within fprime/fprime library) for assert. - requires -DASSERT_RELATIVE_PATH=path to be set on the compile command line + /*----------------------------------------------------------------------------*/ typedef int8_t I8; //!< 8-bit signed integer typedef uint8_t U8; //!< 8-bit unsigned integer diff --git a/cmake/target/build.cmake b/cmake/target/build.cmake index 6e9459c200..2430a2b577 100644 --- a/cmake/target/build.cmake +++ b/cmake/target/build.cmake @@ -63,7 +63,7 @@ function(build_setup_build_module MODULE SOURCES GENERATED EXCLUDED_SOURCES DEPE ) # Setup the hash file for our sources foreach(SRC_FILE IN LISTS MODULE_SOURCES) - set_hash_flag("${SRC_FILE}") + set_assert_flags("${SRC_FILE}") endforeach() endif() # Includes the source, so that the Ac files can include source headers diff --git a/cmake/utilities.cmake b/cmake/utilities.cmake index f2d590392c..e046c2cbad 100644 --- a/cmake/utilities.cmake +++ b/cmake/utilities.cmake @@ -485,19 +485,23 @@ function(get_expected_tool_version VID FILL_VARIABLE) endfunction(get_expected_tool_version) #### -# Function `set_hash_flag`: +# Function `set_assert_flags`: # # Adds a -DASSERT_FILE_ID=(First 8 digits of MD5) to each source file, and records the output in -# hashes.txt. This allows for asserts on file ID not string. +# hashes.txt. This allows for asserts on file ID not string. Also adds the -DASSERT_RELATIVE_PATH +# flag for handling relative path asserts. #### -function(set_hash_flag SRC) +function(set_assert_flags SRC) get_filename_component(FPRIME_CLOSEST_BUILD_ROOT_ABS "${FPRIME_CLOSEST_BUILD_ROOT}" ABSOLUTE) + get_filename_component(FPRIME_PROJECT_ROOT_ABS "${FPRIME_PROJECT_ROOT}" ABSOLUTE) string(REPLACE "${FPRIME_CLOSEST_BUILD_ROOT_ABS}/" "" SHORT_SRC "${SRC}") + string(REPLACE "${FPRIME_PROJECT_ROOT_ABS}/" "" SHORT_SRC "${SHORT_SRC}") + string(MD5 HASH_VAL "${SHORT_SRC}") string(SUBSTRING "${HASH_VAL}" 0 8 HASH_32) file(APPEND "${CMAKE_BINARY_DIR}/hashes.txt" "${SHORT_SRC}: 0x${HASH_32}\n") - SET_SOURCE_FILES_PROPERTIES(${SRC} PROPERTIES COMPILE_FLAGS -DASSERT_FILE_ID="0x${HASH_32}") -endfunction(set_hash_flag) + SET_SOURCE_FILES_PROPERTIES(${SRC} PROPERTIES COMPILE_FLAGS "-DASSERT_FILE_ID=0x${HASH_32} -DASSERT_RELATIVE_PATH='\"${SHORT_SRC}\"'") +endfunction(set_assert_flags) #### diff --git a/config/FpConfig.hpp b/config/FpConfig.hpp index 12b10ecb30..0924ecc618 100644 --- a/config/FpConfig.hpp +++ b/config/FpConfig.hpp @@ -189,13 +189,12 @@ struct FpLimits : BasicLimits { #endif #endif -// Turn asserts on or off - -#define FW_NO_ASSERT 1 //!< Asserts turned off -#define FW_FILEID_ASSERT 2 //!< File ID used - requires -DASSERT_FILE_ID=somevalue to be set on the compile command line -#define FW_FILENAME_ASSERT 3 //!< Uses the file name in the assert - image stores filenames +// Set assertion form. Options: +// 1. FW_NO_ASSERT: assertions are compiled out +// 2. FW_FILEID_ASSERT: asserts report a file CRC and line number +// 3. FW_FILENAME_ASSERT: asserts report a file path (__FILE__) and line number +// 4. FW_RELATIVE_PATH_ASSERT: asserts report a relative path within F´ or F´ library and line number #define FW_ASSERT_DFL_MSG_LEN 256 //!< Maximum assert message length when using the default assert handler - #ifndef FW_ASSERT_LEVEL #define FW_ASSERT_LEVEL FW_FILENAME_ASSERT //!< Defines the type of assert used #endif From 2c981a34ff961438b3c9693a93c39e7693b3bbfa Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 15 Nov 2022 10:26:55 -0800 Subject: [PATCH 096/169] lestarch: minor fixes (#1760) * lestarch: minor oversight in communication adapter description * lestarch: prevent inappropriate deallocation in Tcp driver in the event of a RETRY * lestarch: adding clang-format file * lestarch: improved MemAllocator comments and documentation * lestarch: adding communication adapter how-to guide * lestarch: sp * removing tutorial from this PR --- .clang-format | 5 +++++ .github/actions/spelling/expect.txt | 2 ++ Drv/TcpClient/TcpClientComponentImpl.cpp | 7 ++++--- Drv/TcpServer/TcpServerComponentImpl.cpp | 7 ++++--- Fw/Types/MemAllocator.hpp | 8 +++++--- docs/Design/communication-adapter-interface.md | 2 +- 6 files changed, 21 insertions(+), 10 deletions(-) create mode 100644 .clang-format diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000000..7ad9489e25 --- /dev/null +++ b/.clang-format @@ -0,0 +1,5 @@ +--- +BasedOnStyle: Chromium +IndentWidth: 4 +ColumnLimit: 120 +AccessModifierOffset: -2 \ No newline at end of file diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 03d61a73de..9a7fa3a1e2 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -211,6 +211,7 @@ COMQUEUE COMQUEUEIN COMSPLITTER COMSTUB +COMXBEE Concat config configparser @@ -1597,6 +1598,7 @@ wxgui Xabcdefx xapian xargs +XBee xcode xdf xdffe diff --git a/Drv/TcpClient/TcpClientComponentImpl.cpp b/Drv/TcpClient/TcpClientComponentImpl.cpp index 05aec9270b..7da685df0c 100644 --- a/Drv/TcpClient/TcpClientComponentImpl.cpp +++ b/Drv/TcpClient/TcpClientComponentImpl.cpp @@ -68,13 +68,14 @@ void TcpClientComponentImpl::connected() { Drv::SendStatus TcpClientComponentImpl::send_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { Drv::SocketIpStatus status = m_socket.send(fwBuffer.getData(), fwBuffer.getSize()); - // Always return the buffer - deallocate_out(0, fwBuffer); - if ((status == SOCK_DISCONNECTED) || (status == SOCK_INTERRUPTED_TRY_AGAIN)) { + // Only deallocate buffer when the caller is not asked to retry + if (status == SOCK_INTERRUPTED_TRY_AGAIN) { return SendStatus::SEND_RETRY; } else if (status != SOCK_SUCCESS) { + deallocate_out(0, fwBuffer); return SendStatus::SEND_ERROR; } + deallocate_out(0, fwBuffer); return SendStatus::SEND_OK; } diff --git a/Drv/TcpServer/TcpServerComponentImpl.cpp b/Drv/TcpServer/TcpServerComponentImpl.cpp index 86f65abd70..773abd2f1c 100644 --- a/Drv/TcpServer/TcpServerComponentImpl.cpp +++ b/Drv/TcpServer/TcpServerComponentImpl.cpp @@ -75,13 +75,14 @@ void TcpServerComponentImpl::connected() { Drv::SendStatus TcpServerComponentImpl::send_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { Drv::SocketIpStatus status = m_socket.send(fwBuffer.getData(), fwBuffer.getSize()); - // Always return the buffer - deallocate_out(0, fwBuffer); - if ((status == SOCK_DISCONNECTED) || (status == SOCK_INTERRUPTED_TRY_AGAIN)) { + // Only deallocate buffer when the caller is not asked to retry + if (status == SOCK_INTERRUPTED_TRY_AGAIN) { return SendStatus::SEND_RETRY; } else if (status != SOCK_SUCCESS) { + deallocate_out(0, fwBuffer); return SendStatus::SEND_ERROR; } + deallocate_out(0, fwBuffer); return SendStatus::SEND_OK; } diff --git a/Fw/Types/MemAllocator.hpp b/Fw/Types/MemAllocator.hpp index 521300f3a5..d352a4a073 100644 --- a/Fw/Types/MemAllocator.hpp +++ b/Fw/Types/MemAllocator.hpp @@ -27,7 +27,9 @@ * appropriate. * * The identifier can be used to look up a pre-allocated buffer by ID in an - * embedded system. + * embedded system. Identifiers may be used only in a single call to an invocation. + * Some implementations of MemAllocator discard the identifier but components using + * the MemAllocator interface should not depend on the identifier to be discarded. * * The size is the requested size of the memory. If the allocator cannot return the * requested amount, it should return the actual amount and users should check. @@ -45,7 +47,7 @@ namespace Fw { public: //! Allocate memory /*! - * \param identifier the memory segment identifier (if needed) + * \param identifier the memory segment identifier, each identifier is to be used in once single allocation * \param size the requested size - changed to actual if different * \param recoverable - flag to indicate the memory could be recoverable * \return the pointer to memory. Zero if unable to allocate @@ -56,7 +58,7 @@ namespace Fw { bool& recoverable)=0; //! Deallocate memory /*! - * \param identifier the memory segment identifier (if needed) + * \param identifier the memory segment identifier, each identifier is to be used in once single allocation * \param ptr the pointer to memory returned by allocate() */ virtual void deallocate( diff --git a/docs/Design/communication-adapter-interface.md b/docs/Design/communication-adapter-interface.md index b4cf46f2e1..d26971aa62 100644 --- a/docs/Design/communication-adapter-interface.md +++ b/docs/Design/communication-adapter-interface.md @@ -85,7 +85,7 @@ transmissions. This is done with the `comStatus` port. A communication status is | Fw::Success::SUCCESS | *Communication adapter* transmission succeeded and is ready for more data. | | Fw::Success::FAILURE | Last transmission failed; *communication adapter* is unable to receive more data. | -> * Fw::Success::SUCCESS may also indicate a connection/reconnection success when data flow must be initiated. +* Fw::Success::SUCCESS may also indicate a connection/reconnection success when data flow must be initiated. A *Communication Adapter* shall emit either Fw::Success::SUCCESS or Fw::Success::FAILURE via the `comStatus` port once for each call received on `comDataIn`. Additionally, a *Communication Adapter* shall emit Fw::Success::SUCCESS once at From e289647d89454cd1fa0e2ee1e06e2873885932b4 Mon Sep 17 00:00:00 2001 From: Thomas Boyer Chammard <49786685+thomas-bc@users.noreply.github.com> Date: Wed, 16 Nov 2022 11:22:34 -0800 Subject: [PATCH 097/169] Add sanitizer options (#1772) * Added sanitizer support in CMake * Spelling entry --- .github/actions/spelling/expect.txt | 4 ++ cmake/FPrime.cmake | 1 + cmake/options.cmake | 64 +++++++++++++++++++++++++++++ cmake/sanitizers.cmake | 46 +++++++++++++++++++++ 4 files changed, 115 insertions(+) create mode 100644 cmake/sanitizers.cmake diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 9a7fa3a1e2..22939b7f79 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -297,6 +297,7 @@ deframer deframing delchars delitem +DENABLE deployables DEPRECATEDLIST deps @@ -519,6 +520,7 @@ frontend frox frsize fsanitize +fsanitizers fscanf fstream fstrength @@ -1174,6 +1176,7 @@ rxor saddr Saikiran Sanchit +sanitizers sats savelist saveop @@ -1488,6 +1491,7 @@ typeslist typetoken tzinfo uart +UBSAN ubuntu ucf Uchenik diff --git a/cmake/FPrime.cmake b/cmake/FPrime.cmake index 20d493a1b1..5a86454c50 100644 --- a/cmake/FPrime.cmake +++ b/cmake/FPrime.cmake @@ -22,6 +22,7 @@ message(STATUS "Searching for F prime modules in: ${FPRIME_BUILD_LOCATIONS}") message(STATUS "Autocoder constants file: ${FPRIME_AC_CONSTANTS_FILE}") message(STATUS "Configuration header directory: ${FPRIME_CONFIG_DIR}") +include(sanitizers) # Enable sanitizers if they are requested include(required) include(prescan) #Must come after required if tools detection is to be inherited include(platform/platform) diff --git a/cmake/options.cmake b/cmake/options.cmake index 3c12f5b65b..e3a4cc6737 100644 --- a/cmake/options.cmake +++ b/cmake/options.cmake @@ -181,6 +181,70 @@ option(FPRIME_SKIP_TOOLS_VERSION_CHECK "Skip the version checking of tools" OFF) #### option(FPRIME_CHECK_FRAMEWORK_VERSION "(Internal) Check framework version when building." OFF) +#### +# `ENABLE_SANITIZER_ADDRESS:` +# +# Enables Google's AddressSanitizer. AddressSanitizer is a memory error detector for C/C++. +# More information: https://github.com/google/sanitizers/wiki/AddressSanitizer +# Practically, this adds the -fsanitizers=address flag to both the compiler and linker for the whole build. +# +# **Values:** +# - ON: enables AddressSanitizer. +# - OFF: (default) does not enable AddressSanitizer. +# +# e.g. `-DENABLE_SANITIZER_ADDRESS=ON` +#### +option(ENABLE_SANITIZER_ADDRESS "Enable address sanitizer" OFF) + +#### +# `ENABLE_SANITIZER_LEAK:` +# +# Enables Google's LeakSanitizer. LeakSanitizer is a memory leak detector which is integrated into AddressSanitizer. +# More information: https://github.com/google/sanitizers/wiki/AddressSanitizerLeakSanitizer +# Practically, this adds the -fsanitizers=leak flag to both the compiler and linker for the whole build. +# +# Note: LeakSanitizer is not available on macOS. Use AddressSanitizer instead. +# +# **Values:** +# - ON: enables LeakSanitizer. +# - OFF: (default) does not enable LeakSanitizer. +# +# e.g. `-DENABLE_SANITIZER_LEAK=ON` +#### +option(ENABLE_SANITIZER_LEAK "Enable leak sanitizer" OFF) + +#### +# `ENABLE_SANITIZER_UNDEFINED_BEHAVIOR:` +# +# Enables Google's UndefinedBehaviorSanitizer. UndefinedBehaviorSanitizer is an undefined behavior detector. +# More information: https://clang.llvm.org/docs/UndefinedBehaviorSanitizer.html +# Practically, this adds the -fsanitizers=undefined flag to both the compiler and linker for the whole build. +# +# **Values:** +# - ON: enables UndefinedBehaviorSanitizer. +# - OFF: (default) does not enable UndefinedBehaviorSanitizer. +# +# e.g. `-DENABLE_SANITIZER_UNDEFINED_BEHAVIOR=ON` +#### +option(ENABLE_SANITIZER_UNDEFINED_BEHAVIOR "Enable undefined behavior sanitizer" OFF) + +#### +# `ENABLE_SANITIZER_THREAD:` +# +# Enables Google's ThreadSanitizer. ThreadSanitizer is a tool that detects data races. +# More information: https://clang.llvm.org/docs/ThreadSanitizer.html +# Practically, this adds the -fsanitizers=thread flag to both the compiler and linker for the whole build. +# +# Note: ThreadSanitizer does not work with Address or Leak sanitizer enabled +# +# **Values:** +# - ON: enables ThreadSanitizer. +# - OFF: (default) does not enable ThreadSanitizer. +# +# e.g. `-DENABLE_SANITIZER_THREAD=ON` +#### +option(ENABLE_SANITIZER_THREAD "Enable thread sanitizer" OFF) + # Backwards compatibility, when build type=TESTING BUILD_TESTING is on string(TOUPPER "${CMAKE_BUILD_TYPE}" FPRIME_BUILD_TYPE) if (FPRIME_BUILD_TYPE STREQUAL "TESTING") diff --git a/cmake/sanitizers.cmake b/cmake/sanitizers.cmake new file mode 100644 index 0000000000..2bc47e8a8f --- /dev/null +++ b/cmake/sanitizers.cmake @@ -0,0 +1,46 @@ +#### +# sanitizers.cmake: +# +# Enables sanitizers in the build settings when requested by the user with -DENABLE_SANITIZER_<...>=ON. +# +# Sanitizers, by default, output their logs to stderr. To redirect the output to files instead, use the +# `log_path` option from the sanitizer _OPTION environment variable at runtime. For example, with UBSAN: +# >>> UBSAN_OPTIONS="log_path=/path/to/output_dir" fprime-util check (or a single executable file). +# If a relative path is specified, this will be relative to the test main function's file **in the build cache**. +#### + +if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES ".*Clang") + set(SANITIZERS) + + if(ENABLE_SANITIZER_ADDRESS) + list(APPEND SANITIZERS "address") + endif() + + if(ENABLE_SANITIZER_UNDEFINED_BEHAVIOR) + list(APPEND SANITIZERS "undefined") + endif() + + if(ENABLE_SANITIZER_LEAK) + if(APPLE) + message(WARNING "Leak sanitizer not supported on macOS.") + else() + list(APPEND SANITIZERS "leak") + endif() + endif() + + if(ENABLE_SANITIZER_THREAD) + if("address" IN_LIST SANITIZERS OR "leak" IN_LIST SANITIZERS) + message(WARNING "Thread sanitizer does not work with Address or Leak sanitizer enabled") + else() + list(APPEND SANITIZERS "thread") + endif() + endif() + + list(JOIN SANITIZERS "," LIST_OF_SANITIZERS) + + if(LIST_OF_SANITIZERS AND NOT "${LIST_OF_SANITIZERS}" STREQUAL "") + message(STATUS "Enabled the following sanitizers: ${LIST_OF_SANITIZERS}") + add_compile_options(-fsanitize=${LIST_OF_SANITIZERS}) + add_link_options(-fsanitize=${LIST_OF_SANITIZERS}) + endif() +endif() From 7b49c2377a775f14deba15656eabea3a61ccea33 Mon Sep 17 00:00:00 2001 From: Kevinthegreat <92656833+kevinthegreat1@users.noreply.github.com> Date: Mon, 21 Nov 2022 14:58:53 -0500 Subject: [PATCH 098/169] Fixed platform template link in cmake-platforms.md (#1777) --- docs/UsersGuide/cmake/cmake-platforms.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/UsersGuide/cmake/cmake-platforms.md b/docs/UsersGuide/cmake/cmake-platforms.md index 39622c08d5..440b596fcb 100644 --- a/docs/UsersGuide/cmake/cmake-platforms.md +++ b/docs/UsersGuide/cmake/cmake-platforms.md @@ -12,5 +12,5 @@ In order to create a new platform from scratch, the user can copy "platform.cmak out in order to generate the new platform file. It will guide the user through the setup of this piece. -To understand the platform template: [Platform Template File](../api/cmake/platform/platform-template.md) +To understand the platform template: [Platform Template File](https://github.com/nasa/fprime/blob/release/documentation/docs/UsersGuide/api/cmake/platform/platform-template.md) To use the template: [fprime Platform Template](https://github.com/nasa/fprime/blob/devel/cmake/platform/platform.cmake.template) From 005c1983b962827c19d9fa9ea0f113f3d9a02696 Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 22 Nov 2022 13:55:40 -0800 Subject: [PATCH 099/169] Update/internal to cmake settings (#1768) * internalized CMake settings * adding basic settings.ini processing to CMake * sp * formatting * fixing backwards compatibility for fprime-util * adding settings.ini that sets correct settings for cmake test builds * passing proper variables to prescan and alloing CLI overrides to settings.ini * more prescan exclusions and better comments * properly handling variable source when checking in CMake * throwing out invalid output from settings processor * fixing error output for routine data * sp and formatting * reverting setting name and fixing install dest * fixing cmake-defaulted CMAKE_INSTALL_PREFIX setting * sp per review * updating settings.ini documentation * sp * deleting unlinked and unused file * fixing internal to cmake error handling * formatting --- .github/actions/spelling/expect.txt | 11 ++ cmake/FPrime.cmake | 6 - cmake/options.cmake | 16 ++- cmake/prescan.cmake | 80 +++++++++---- cmake/settings/ini-to-stdio.py | 96 ++++++++++++++++ cmake/settings/ini.cmake | 118 ++++++++++++++++++++ cmake/test/data/TestDeployment/settings.ini | 4 + docs/UsersGuide/dev/cmake-settings.md | 1 - docs/UsersGuide/user/settings.md | 19 +++- 9 files changed, 314 insertions(+), 37 deletions(-) create mode 100644 cmake/settings/ini-to-stdio.py create mode 100644 cmake/settings/ini.cmake create mode 100644 cmake/test/data/TestDeployment/settings.ini delete mode 100644 docs/UsersGuide/dev/cmake-settings.md diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 22939b7f79..e2921d28ba 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -277,6 +277,7 @@ daringfireball Daruwala DASSERT databinding +DATAROOTDIR datastore dawbarton db @@ -457,6 +458,7 @@ fadvise FAKELOGGER fallocate fallthrough +fbuild fcheck fclose fcntl @@ -575,6 +577,7 @@ github gjslint glibc globals +gmock gmtime Gnc Gnd @@ -660,6 +663,7 @@ importables INADDR iname inbool +INCLUDEDIR inet inin initfiles @@ -758,6 +762,8 @@ lhash libc libclang libcrc +LIBDIR +LIBEXECDIR libgtest libiconv LIBLOC @@ -777,6 +783,7 @@ lld llvm loadfile localhost +LOCALSTATEDIR LOCKGUARDTESTER locs LOGASSERT @@ -947,6 +954,7 @@ odo oflag okidocki oldeol +OLDINCLUDEDIR OMG onchange onlinepubs @@ -1184,6 +1192,7 @@ saxutils sbb SBF sbin +SBINDIR sbt scanf sched @@ -1236,6 +1245,7 @@ sface sfregoso sgl SGN +SHAREDSTATEDIR SHELLCOMMAND Shenker showinitializer @@ -1348,6 +1358,7 @@ swcaegitadmin SYMLINKS synchronicity synopsys +SYSCONFDIR SYSFS sysinfo systemd diff --git a/cmake/FPrime.cmake b/cmake/FPrime.cmake index 5a86454c50..bb143ed27b 100644 --- a/cmake/FPrime.cmake +++ b/cmake/FPrime.cmake @@ -34,12 +34,6 @@ include(autocoder/autocoder) include(target/target) include(API) -# Set the install directory for the package -if (DEFINED FPRIME_INSTALL_DEST) - set(CMAKE_INSTALL_PREFIX ${FPRIME_INSTALL_DEST} CACHE PATH "Install dir" FORCE) -elseif(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT OR CMAKE_INSTALL_PREFIX STREQUAL "") - set(CMAKE_INSTALL_PREFIX ${PROJECT_SOURCE_DIR}/build-artifacts CACHE PATH "Install dir" FORCE) -endif() message(STATUS "Installation directory: ${CMAKE_INSTALL_PREFIX}") # Setup the global include directories diff --git a/cmake/options.cmake b/cmake/options.cmake index e3a4cc6737..a6c87efbd7 100644 --- a/cmake/options.cmake +++ b/cmake/options.cmake @@ -16,6 +16,13 @@ # the `-D` option there. # #### +# Remap changed settings +if (DEFINED FPRIME_INSTALL_DEST) + set(CMAKE_INSTALL_PREFIX ${FPRIME_INSTALL_DEST} CACHE PATH "Install dir" FORCE) +endif() +include("settings/ini") +ini_to_cache() + #### # `CMAKE_TOOLCHAIN_FILE:` @@ -329,13 +336,14 @@ if (DEFINED FPRIME_ENVIRONMENT_FILE) set(FPRIME_ENVIRONMENT_FILE "${FPRIME_ENVIRONMENT_FILE}" CACHE PATH "F prime environment file" FORCE) set_property(DIRECTORY APPEND PROPERTY CMAKE_CONFIGURE_DEPENDS "${FPRIME_ENVIRONMENT_FILE}") endif() -# Override the AC constants file when specified -if (NOT DEFINED FPRIME_AC_CONSTANTS_FILE) - set(FPRIME_AC_CONSTANTS_FILE "${FPRIME_FRAMEWORK_PATH}/config/AcConstants.ini" CACHE PATH "F prime AC constants.ini file" FORCE) -endif() # Settings for F config directory if (NOT DEFINED FPRIME_CONFIG_DIR) set(FPRIME_CONFIG_DIR "${FPRIME_FRAMEWORK_PATH}/config/") endif() set(FPRIME_CONFIG_DIR "${FPRIME_CONFIG_DIR}" CACHE PATH "F prime configuration header directory" FORCE) + +# Override the AC constants file when specified +if (NOT DEFINED FPRIME_AC_CONSTANTS_FILE) + set(FPRIME_AC_CONSTANTS_FILE "${FPRIME_CONFIG_DIR}/AcConstants.ini" CACHE PATH "F prime AC constants.ini file" FORCE) +endif() diff --git a/cmake/prescan.cmake b/cmake/prescan.cmake index 5f0dc51b74..505eda58da 100644 --- a/cmake/prescan.cmake +++ b/cmake/prescan.cmake @@ -12,22 +12,43 @@ # full build or the information will be wrong. #### -# NOTE: **ensure** that list properties are added by hand in the actual call. Otherwise they are expanded and break -# the call below. -set(NEEDED_PROPERTIES - FPRIME_CONFIG_DIR - FPRIME_AC_CONSTANTS_FILE - FPRIME_ENVIRONMENT_FILE - FPRIME_SETTINGS_FILE - FPRIME_PROJECT_ROOT - FPRIME_FRAMEWORK_PATH - CMAKE_TOOLCHAIN_FILE - CMAKE_BUILD_TYPE - CMAKE_DEBUG_OUTPUT - FPRIME_USE_STUBBED_DRIVERS - FPRIME_USE_BAREMETAL_SCHEDULER - FPP_TOOLS_PATH - BUILD_TESTING +set(EXCLUDED_CACHE_VARIABLES + CMAKE_EDIT_COMMAND + CMAKE_HOME_DIRECTORY + CMAKE_INSTALL_NAME_TOOL + FPRIME_PRESCAN + FPRIME_VERSION_SCRIPT + CMAKE_C_COMPILER_FORCED + CMAKE_CXX_COMPILER_FORCED + FPRIME_SKIP_TOOLS_VERSION_CHECK + CMAKE_HAVE_LIBC_PTHREAD + CMAKE_HAVE_PTHREAD_H + CMAKE_SKIP_INSTALL_ALL_DEPENDENCY + FIND_PACKAGE_MESSAGE_DETAILS_Threads + BUILD_GMOCK + CMAKE_INSTALL_BINDIR + CMAKE_INSTALL_DATAROOTDIR + CMAKE_INSTALL_INCLUDEDIR + CMAKE_INSTALL_LIBDIR + CMAKE_INSTALL_LIBEXECDIR + CMAKE_INSTALL_LOCALSTATEDIR + CMAKE_INSTALL_OLDINCLUDEDIR + CMAKE_INSTALL_SBINDIR + CMAKE_INSTALL_SHAREDSTATEDIR + CMAKE_INSTALL_SYSCONFDIR + INSTALL_GTEST + VALGRIND + gmock_build_tests + gtest_build_samples + gtest_build_tests + gtest_disable_pthreads + gtest_force_shared_crt + gtest_hide_internal_symbols +) +set(TYPES_DISALLOWED_LIST + INTERNAL + STATIC + UNINITIALIZED ) # Directory in-which to build the prescan directory set(PRESCAN_DIR "${CMAKE_BINARY_DIR}/prescan") @@ -44,11 +65,27 @@ endif() #### function(_get_call_properties) set(CALL_PROPS) - foreach (PROPERTY IN LISTS NEEDED_PROPERTIES) - if (NOT "${${PROPERTY}}" STREQUAL "") - set(CALL_PROP "-D${PROPERTY}=${${PROPERTY}}") - list(APPEND CALL_PROPS "${CALL_PROP}") + get_cmake_property(CACHE_VARS CACHE_VARIABLES) + foreach (PROPERTY IN LISTS CACHE_VARS) + get_property(CACHE_TYPE CACHE "${PROPERTY}" PROPERTY TYPE) + # Exclude listed properties and empty properties + if ("${PROPERTY}" IN_LIST EXCLUDED_CACHE_VARIABLES) + continue() + # Exclude empty values + elseif("${${PROPERTY}}" STREQUAL "") + continue() + # Exclude internal cache values + elseif("${CACHE_TYPE}" IN_LIST TYPES_DISALLOWED_LIST) + continue() + endif() + # Add escaping for list type variables + string(REPLACE ";" "\\;" PROP_VALUE "${${PROPERTY}}" ) + # Check for debugging output + if (CMAKE_DEBUG_OUTPUT) + message(STATUS "[prescan] Adding cache variable: '${PROPERTY}=${PROP_VALUE}'") endif() + set(CALL_PROP "-D${PROPERTY}=${PROP_VALUE}") + list(APPEND CALL_PROPS "${CALL_PROP}") endforeach() set(CALL_PROPS "${CALL_PROPS}" PARENT_SCOPE) endfunction(_get_call_properties) @@ -80,7 +117,6 @@ function(perform_prescan) "-DCMAKE_C_COMPILER_FORCED=TRUE" "-DCMAKE_CXX_COMPILER_FORCED=TRUE" "-DFPRIME_SKIP_TOOLS_VERSION_CHECK=ON" - "-DFPRIME_LIBRARY_LOCATIONS=${FPRIME_LIBRARY_LOCATIONS}" ${CALL_PROPS} RESULT_VARIABLE result WORKING_DIRECTORY "${PRESCAN_DIR}" @@ -94,4 +130,4 @@ function(perform_prescan) file(READ "${CMAKE_BINARY_DIR}/prescan-fpp-list" FPP_LISTING OFFSET 1) # Skips leading ";" preventing null element set_property(GLOBAL PROPERTY FP_FPP_LIST ${FPP_LISTING}) message(STATUS "Performing CMake source prescan - DONE") -endfunction() \ No newline at end of file +endfunction() diff --git a/cmake/settings/ini-to-stdio.py b/cmake/settings/ini-to-stdio.py new file mode 100644 index 0000000000..226b99e77d --- /dev/null +++ b/cmake/settings/ini-to-stdio.py @@ -0,0 +1,96 @@ +""" ini-to-stdio.py: + +Loads fprime style ini files into a format CMake can process. +""" +import argparse +import sys +from functools import partial + +from pathlib import Path +from typing import List + +from fprime.fbuild.settings import IniSettings + + +def print_setting(setting: str, value: str = "", ending: str = ";"): + """Print a setting for CMake + + Prints a setting for CMake using the format 'SETTING=VALUE;' producing a CMake list of settings. + + Args: + setting: name of setting in cmake + value: value to provide to cmake + ending: ending of the print line + """ + value = str(value).replace(";", "\\;") + print(f"{setting}={value}", end=ending) + + +def print_list_settings(items: List[str]): + """Print a list of settings of form SETTING=VALUE""" + for item in items: + splits = item.strip().split("=") + if splits[0] != "": + print_setting(*splits) + + +CMAKE_NEEDED_SETTINGS = { + "framework_path": partial(print_setting, "FPRIME_FRAMEWORK_PATH"), + "project_root": partial(print_setting, "FPRIME_PROJECT_ROOT"), + "config_directory": partial(print_setting, "FPRIME_CONFIG_DIR"), + "library_locations": lambda value: print_setting( + "FPRIME_LIBRARY_LOCATIONS", ";".join(str(item) for item in value) + ), + "default_cmake_options": lambda value: print_list_settings(value.split("\n")), + "ac_constants": partial(print_setting, "FPRIME_AC_CONSTANTS_FILE"), + # Sets two settings from install dest: fprime and cmake settings + "install_destination": partial(print_setting, "CMAKE_INSTALL_PREFIX"), +} + + +def main(): + """Do the thing.""" + parser = argparse.ArgumentParser() + parser.add_argument("settings", type=Path, help="Path to settings.ini") + parser.add_argument( + "toolchain", + nargs="?", + type=Path, + default=Path("native"), + help="Path to toolchain file", + ) + + args_ns = parser.parse_args() + loaded_settings = IniSettings.load( + args_ns.settings, str(args_ns.toolchain.stem), False + ) + loaded_settings_ut = IniSettings.load( + args_ns.settings, str(args_ns.toolchain.stem), True + ) + + for setting, handler in CMAKE_NEEDED_SETTINGS.items(): + try: + setting_value = loaded_settings[setting] + ut_setting_value = loaded_settings_ut[setting] + + assert ( + setting_value == ut_setting_value + ), f"CMake can only parse unittest independent settings" + output = loaded_settings[setting] + handler(output) + except KeyError as key_error: + print( + f"[WARNING] Failed to load settings.ini field {key_error}. Update fprime-util.", + end=";", + ) + # Print the last setting with no ending to prevent null-entry at list end + print_setting("FPRIME_SETTINGS_FILE", args_ns.settings, ending="") + return 0 + + +if __name__ == "__main__": + try: + sys.exit(main()) + except Exception as exc: + print(f"{exc}", file=sys.stderr) + sys.exit(1) diff --git a/cmake/settings/ini.cmake b/cmake/settings/ini.cmake new file mode 100644 index 0000000000..d072af9451 --- /dev/null +++ b/cmake/settings/ini.cmake @@ -0,0 +1,118 @@ +#### +# ini.cmake: +# +# This file loads settings from INI files. In cases where these settings are supplied via fprime-util, the settings are +# checked for discrepancy. This allows the cmake system to detect when it should be regenerated and has not been. In the +# case that the settings were not supplied, it sets them. +#### +include_guard() + +# Necessary global variables +set(SETTINGS_CMAKE_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}") +find_program(PYTHON NAMES python3 python) #This happens before required + +#### +# FPRIME_UTIL_CRITICAL_LIST: +# +# This is a list of critical settings that are passed in from fprime-util. If these settings change in `settings.ini` +# they need to result in a WARNING to let the user know that had fprime-util be run, it now needs to be rerun. +#### +set(FPRIME_UTIL_CRITICAL_LIST + "FPRIME_FRAMEWORK_PATH" + "FPRIME_LIBRARY_LOCATIONS" + "FPRIME_PROJECT_ROOT" + "FPRIME_ENVIRONMENT_FILE" + "FPRIME_AC_CONSTANTS_FILE" + "FPRIME_CONFIG_DIR" + "FPRIME_INSTALL_DEST" +) + +#### +# ini_to_cache: +# +# Uses a python script to load INI files. These items are set into the CMake cache. +#### +function(ini_to_cache) + set(CALCULATED_INI "${CMAKE_SOURCE_DIR}/settings.ini") + + # Check if settings.ini is defined and is not what is expected + if (DEFINED FPRIME_SETTINGS_FILE AND NOT FPRIME_SETTINGS_FILE STREQUAL "${CALCULATED_INI}") + message(FATAL_ERROR "Provided settings.ini '${FPRIME_SETTINGS_FILE}' not expected file '${CALCULATED_INI}'") + endif() + # Execute the process + execute_process(COMMAND ${PYTHON} + "${SETTINGS_CMAKE_DIRECTORY}/ini-to-stdio.py" + "${CALCULATED_INI}" + ${CMAKE_TOOLCHAIN_FILE} + OUTPUT_VARIABLE INI_OUTPUT + OUTPUT_STRIP_TRAILING_WHITESPACE + RESULT_VARIABLE RESULT_CODE + ) + # Check result code + if (NOT RESULT_CODE EQUAL 0) + message(FATAL_ERROR "Failed to process settings.ini file: ${CALCULATED_INI}") + endif() + + # Unset the CMAKE_INSTALL_PREFIX as we override it + if(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT OR CMAKE_INSTALL_PREFIX STREQUAL "") + unset(CMAKE_INSTALL_PREFIX CACHE) + endif() + # Process line-by-line + foreach(LINE IN LISTS INI_OUTPUT) + # Skip malformed lines + if (NOT LINE MATCHES "^[A-Za-z0-9_]+=") + message(STATUS "${LINE}") + continue() + endif() + STRING(REPLACE ";" "\\;" LINE "${LINE}") + STRING(REPLACE "=" ";" LINE "${LINE}") + list(GET LINE 0 SETTING) + list(LENGTH LINE ELEMENTS) + if (ELEMENTS GREATER 1) + list(GET LINE 1 VALUE) + else() + set(VALUE "") + endif() + + # Here we set several cache variables: + # - _INI_: original setting, but was loaded from settings.ini + # - _CLI_: original setting, but was passed in via CLI + # These are used to detect changes and alert the user. + # If the setting is undefined, then we must load it from the INI file and set the proper value. + if (NOT DEFINED "${SETTING}") + # Print source of setting when debugging + if (CMAKE_DEBUG_OUTPUT) + message(STATUS "${SETTING} read from settings.ini as '${VALUE}'") + endif() + set("${SETTING}_INI_" "${VALUE}" CACHE INTERNAL "Original value of ${SETTING} from settings.ini") + set("${SETTING}" "${VALUE}" CACHE INTERNAL "") + # If setting was originally loaded, here, from settings.ini. We should check that it is correctly re-set. + elseif(DEFINED "${SETTING}_INI_") + # Changed INI files are hard-failure as it is difficult to know how/when to regenerate + if(NOT "${VALUE}" STREQUAL "${${SETTING}_INI_}") + # Print some extra output to help debug + if (CMAKE_DEBUG_OUTPUT) + message(WARNING "${SETTING} changed from '${${SETTING}_INI_}' to '${VALUE}'") + endif() + message(FATAL_ERROR "settings.ini field changed. Please regenerate.") + endif() + # If setting was passed in on CLI + elseif(DEFINED "${SETTING}_CLI_") + # Changed INI files are hard-failure as it is difficult to know how/when to regenerate + if(NOT "${VALUE}" STREQUAL "${${SETTING}_CLI_}" AND SETTING IN_LIST FPRIME_UTIL_CRITICAL_LIST) + # Print some extra output to help debug + if (CMAKE_DEBUG_OUTPUT) + message(WARNING "${SETTING} changed from '${${SETTING}_CLI_}' to '${VALUE}'") + endif() + message(WARNING "settings.ini field changed. This likely means fprime-util generate should be run.") + endif() + # Setting defined, but none of the check-values are set. This it is the first run, with items from CLI. + else() + # Print source of setting when debugging + if (CMAKE_DEBUG_OUTPUT) + message(STATUS "${SETTING} read from CLI as '${${SETTING}}'") + endif() + set("${SETTING}_CLI_" "${${SETTING}}" CACHE INTERNAL "Original value of ${SETTING} from CLI") + endif() + endforeach() +endfunction(ini_to_cache) diff --git a/cmake/test/data/TestDeployment/settings.ini b/cmake/test/data/TestDeployment/settings.ini new file mode 100644 index 0000000000..2a275d7277 --- /dev/null +++ b/cmake/test/data/TestDeployment/settings.ini @@ -0,0 +1,4 @@ +[fprime] +framework_path: ../../../.. +library_locations: ../test-fprime-library:../test-fprime-library2 +project_root: .. diff --git a/docs/UsersGuide/dev/cmake-settings.md b/docs/UsersGuide/dev/cmake-settings.md deleted file mode 100644 index dfc88bdc00..0000000000 --- a/docs/UsersGuide/dev/cmake-settings.md +++ /dev/null @@ -1 +0,0 @@ -# TODO: document the settings in CMake diff --git a/docs/UsersGuide/user/settings.md b/docs/UsersGuide/user/settings.md index ce130c523a..cc174afc91 100644 --- a/docs/UsersGuide/user/settings.md +++ b/docs/UsersGuide/user/settings.md @@ -4,10 +4,6 @@ In many circumstances it is useful to set default values for the build as well a locations for F´ to use external code. The `settings.ini` file allows users to set various settings to control the build. -**Note:** settings.ini only adjusts the build when running through `fprime-util`. These settings can -be supplied directly to CMake using -D flags as described here: [CMake -Settings](../dev/cmake-settings.md), but it is not recommended to use CMake directly. - In this document: - [`settings.ini` Settings](#settingsini-settings) - [`fprime` Section](#fprime-section) @@ -51,6 +47,18 @@ These settings include: - `ac_constants`: Path to autocode constants ini file. - `config_directory`: Path to configuration header directory. +### Platform Sections + +Some settings may be overridden for specific platforms using specific platform sections. These sections +have the same name as the platform and may set the following settings: + +1. `config_directory` +2. `ac_constants` +3. `install_destination` +4. `environment_file` + +These settings only apply when building for the specified platform. + ### Example `settings.ini` This `settings.ini` file comes from the [fprime-sphinx](https://github.com/fprime-community/fprime-sphinx) @@ -66,6 +74,9 @@ default_toolchain: gr712-vxworks6 environment_file: ../fprime-vxworks/cmake/env/VxWorks-GR712.ini ac_constants: ./Cfg/AcConstants.ini config_directory: Cfg + +[gr712-vxworks6] +config_directory: Cfg_gr712 ``` ### Example Environment Ini File From 9409139668c218c10187cc0ce504005363df3f55 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Mon, 28 Nov 2022 14:20:08 -0800 Subject: [PATCH 100/169] Fix printf and scanf format strings (#1784) --- STest/STest/Random/Random.cpp | 9 +++++---- STest/STest/Random/bsd_random.c | 2 +- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/STest/STest/Random/Random.cpp b/STest/STest/Random/Random.cpp index 25af352bc7..7d993f863e 100644 --- a/STest/STest/Random/Random.cpp +++ b/STest/STest/Random/Random.cpp @@ -10,6 +10,7 @@ // ====================================================================== #include +#include #include #include "STest/Random/Random.hpp" @@ -37,7 +38,7 @@ namespace STest { bool result = true; FILE *fp = fopen(fileName, "r"); if (fp != nullptr) { - result = (fscanf(fp, "%u", &value) == 1); + result = (fscanf(fp, "%" PRIu32, &value) == 1); (void) fclose(fp); } else { @@ -59,7 +60,7 @@ namespace STest { if (fp != nullptr) { int status = fprintf( fp, - "%u\n", + "%" PRIu32 "\n", seedValue ); result = (status > 0); @@ -78,11 +79,11 @@ namespace STest { const bool seedValueOK = SeedValue::getFromFile("seed", seedValue); if (seedValueOK) { - printf("[STest::Random] Read seed %u from file\n", seedValue); + printf("[STest::Random] Read seed %" PRIu32 " from file\n", seedValue); } else { seedValue = SeedValue::getFromTime(); - printf("[STest::Random] Generated seed %u from system time\n", seedValue); + printf("[STest::Random] Generated seed %" PRIu32 " from system time\n", seedValue); } (void) SeedValue::appendToFile("seed-history", seedValue); SeedValue::set(seedValue); diff --git a/STest/STest/Random/bsd_random.c b/STest/STest/Random/bsd_random.c index affa2b785e..36add5f392 100644 --- a/STest/STest/Random/bsd_random.c +++ b/STest/STest/Random/bsd_random.c @@ -284,7 +284,7 @@ bsd_initstate(seed, arg_state, n) state[-1] = MAX_TYPES * (rptr - state) + rand_type; if (n < BREAK_0) { (void)fprintf(stderr, - "random: not enough state (%ld bytes); ignored.\n", n); + "random: not enough state (%zd bytes); ignored.\n", n); return(0); } if (n < BREAK_1) { From b7a25920a37fdabf14b54cf3652abed56e7eafc7 Mon Sep 17 00:00:00 2001 From: Timothy Canham Date: Tue, 29 Nov 2022 14:00:20 -0800 Subject: [PATCH 101/169] Add packetized telemetry option (#1776) * manual packet gen * Added tlmPkt to deployment * Packet files * Fixes to packet gen script * format python, updated packet files * spelling fixes * integrating packet autocoder * final updates for telemetry packetization * formatting telemetry packetizer cpde * moving tlm packetizer configuration file * resetting stock telemetry channelizer * missed packetizer setup call * fixing autocoding miss-match with Svc::TlmChan Co-authored-by: M Starch --- .gitignore | 2 + Autocoders/Python/bin/tlm_packet_gen.py | 58 +- Autocoders/Python/bin/tlm_packet_gen.sh | 14 + .../fprime_ac/parsers/XmlSerializeParser.py | 2 +- .../Python/src/fprime_ac/utils/buildroot.py | 1 + Ref/Top/CMakeLists.txt | 3 +- Ref/Top/{RefPacketsAi.xml => RefPackets.xml} | 55 +- Ref/Top/RefTopology.cpp | 6 +- Ref/Top/RefTopologyDefs.hpp | 2 +- Ref/Top/instances.fpp | 11 +- Ref/Top/topology.fpp | 8 +- Svc/TlmPacketizer/TlmPacketizer.cpp | 715 +++--- Svc/TlmPacketizer/TlmPacketizer.hpp | 257 ++- .../TlmPacketizerComponentImplCfg.hpp | 42 - Svc/TlmPacketizer/TlmPacketizerTypes.hpp | 37 +- Svc/TlmPacketizer/test/ut/Tester.cpp | 1913 ++++++++--------- Svc/TlmPacketizer/test/ut/Tester.hpp | 246 +-- Svc/TlmPacketizer/test/ut/main.cpp | 54 +- cmake/FPrime.cmake | 1 + cmake/autocoder/packets.cmake | 63 + cmake/utilities.cmake | 16 + config/TlmPacketizerCfg.hpp | 43 + requirements.txt | 4 +- 23 files changed, 1749 insertions(+), 1804 deletions(-) create mode 100755 Autocoders/Python/bin/tlm_packet_gen.sh rename Ref/Top/{RefPacketsAi.xml => RefPackets.xml} (65%) delete mode 100644 Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp create mode 100644 cmake/autocoder/packets.cmake create mode 100644 config/TlmPacketizerCfg.hpp diff --git a/.gitignore b/.gitignore index d17c56549e..1e422e991c 100644 --- a/.gitignore +++ b/.gitignore @@ -82,3 +82,5 @@ depend /.idea/ /venv/ + +Packet-Views diff --git a/Autocoders/Python/bin/tlm_packet_gen.py b/Autocoders/Python/bin/tlm_packet_gen.py index b1c82b0e07..8e7a45d694 100755 --- a/Autocoders/Python/bin/tlm_packet_gen.py +++ b/Autocoders/Python/bin/tlm_packet_gen.py @@ -114,6 +114,8 @@ PRINT = logging.getLogger("output") DEBUG = logging.getLogger("debug") +PACKET_VIEW_DIR = "./Packet-Views" + class TlmPacketParseValueError(ValueError): pass @@ -136,8 +138,8 @@ def add_type_size(self, type, size): def get_type_size(self, type_name, size): # switch based on type - if type == "string": - return size + if type_name == "string": + return int(size) + 2 # plus 2 to store the string length elif type_name == "I8": return 1 elif type_name == "I16": @@ -163,28 +165,6 @@ def get_type_size(self, type_name, size): else: return None - # def search_for_file(self,file_type, file_path): - # ''' - # Searches for a given included port or serializable by looking in three places: - # - The specified BUILD_ROOT - # - The F Prime core - # - The exact specified path - # @param file_type: type of file searched for - # @param file_path: path to look for based on offset - # @return: full path of file - # ''' - # core = os.environ.get("FPRIME_CORE_DIR", BUILD_ROOT) - # for possible in [BUILD_ROOT, core, None]: - # if not possible is None: - # checker = os.path.join(possible, file_path) - # else: - # checker = file_path - # if os.path.exists(checker): - # DEBUG.debug("%s xml type description file: %s" % (file_type,file_path)) - # return checker - # else: - # return None - def generate_channel_size_dict(self, the_parsed_topology_xml, xml_filename): """ Generates GDS XML dictionary from parsed topology XML @@ -224,7 +204,7 @@ def generate_channel_size_dict(self, the_parsed_topology_xml, xml_filename): for comp in the_parsed_topology_xml.get_instances(): comp_name = comp.get_name() - comp_id = int(comp.get_base_id()) + comp_id = int(comp.get_base_id(), 0) comp_type = comp.get_type() if self.verbose: PRINT.debug("Processing %s" % comp_name) @@ -246,6 +226,9 @@ def generate_channel_size_dict(self, the_parsed_topology_xml, xml_filename): # if channel is enum if type(chan_type) == type(tuple()): chan_size = 4 + # if channel type is string + # elif chan_type == "string": + # chan_size = int(chan.get_size()) + 2 # FIXME: buffer size storage size magic number - needs to be turned into a constant # if channel is serializable elif chan_type in self.size_dict: chan_size = self.size_dict[chan_type] @@ -266,7 +249,7 @@ def generate_channel_size_dict(self, the_parsed_topology_xml, xml_filename): def gen_packet_file(self, xml_filename): - view_path = "./Views" + view_path = PACKET_VIEW_DIR if not os.path.exists(view_path): os.mkdir(view_path) @@ -275,11 +258,6 @@ def gen_packet_file(self, xml_filename): if not os.path.isfile(xml_filename): raise TlmPacketParseIOError("File %s does not exist!" % xml_filename) - if not "PacketsAi" in xml_filename: - raise IOError( - "ERROR: Missing PacketsAi at end of file name %s" % xml_filename - ) - fd = open(xml_filename, "r") xml_parser = etree.XMLParser(remove_comments=True) element_tree = etree.parse(fd, parser=xml_parser) @@ -315,12 +293,12 @@ def gen_packet_file(self, xml_filename): ht.num_packets = 0 total_packet_size = 0 levels = [] - view_path = "./Views" + view_path = PACKET_VIEW_DIR # find the topology import for entry in element_tree.getroot(): # read in topology file if entry.tag == "import_topology": - top_file = search_for_file("Packet", entry.text) + top_file = search_for_file("Topology", entry.text) if top_file is None: raise TlmPacketParseIOError( "import file %s not found" % entry.text @@ -424,12 +402,9 @@ def gen_packet_file(self, xml_filename): "Invalid xml type %s" % element_tree.getroot().tag ) - output_file_base = os.path.splitext(os.path.basename(xml_filename))[0].replace( - "Ai", "" - ) - file_dir = os.path.dirname(xml_filename).replace( - get_nearest_build_root(xml_filename) + os.sep, "" - ) + output_file_base = os.path.splitext(os.path.basename(xml_filename))[0] + nearest_build_root = get_nearest_build_root(xml_filename) + file_dir = os.path.relpath(os.path.dirname(xml_filename), nearest_build_root) missing_channels = False @@ -499,6 +474,7 @@ def process_serializable_files(self, serializable_file_list): for ( member_name, member_type, + member_array_size, member_size, member_format_specifier, member_comment, @@ -520,6 +496,8 @@ def process_serializable_files(self, serializable_file_list): ) sys.exit(-1) serializable_size += type_size + if member_array_size != None: + serializable_size *= member_array_size self.add_type_size(serializable_type, serializable_size) if self.verbose: print( @@ -616,7 +594,7 @@ def main(): print(f"Usage: {sys.argv[0]} [options] xml_filename") return elif len(args) == 1: - xml_filename = args[0] + xml_filename = os.path.abspath(args[0]) else: print("ERROR: Too many filenames, should only have one") return diff --git a/Autocoders/Python/bin/tlm_packet_gen.sh b/Autocoders/Python/bin/tlm_packet_gen.sh new file mode 100755 index 0000000000..f2d2743588 --- /dev/null +++ b/Autocoders/Python/bin/tlm_packet_gen.sh @@ -0,0 +1,14 @@ +#!/usr/bin/bash + +script_dir=$(dirname $0) + +# $0 = this script +# $1 = packet file +# $2 = deployment build cache (ex. Ref/build-fprime-automatic-native) + +export PYTHONPATH=$script_dir/../src +export BUILD_ROOT=$script_dir/../../../:$2:$2/F-Prime +echo "BUILD_ROOT=$BUILD_ROOT" + +# get python from the path +python3 $script_dir/tlm_packet_gen.py $1 \ No newline at end of file diff --git a/Autocoders/Python/src/fprime_ac/parsers/XmlSerializeParser.py b/Autocoders/Python/src/fprime_ac/parsers/XmlSerializeParser.py index 2b78c4a919..a8132f4e3c 100644 --- a/Autocoders/Python/src/fprime_ac/parsers/XmlSerializeParser.py +++ b/Autocoders/Python/src/fprime_ac/parsers/XmlSerializeParser.py @@ -320,6 +320,6 @@ def get_comment(self): def get_members(self): """ - Returns a list of member (name, type, optional size, optional format, optional comment) needed. + Returns a list of member (name, type, optional array size, optional size, optional format, optional comment) needed. """ return self.__members diff --git a/Autocoders/Python/src/fprime_ac/utils/buildroot.py b/Autocoders/Python/src/fprime_ac/utils/buildroot.py index 571f9156fe..f26ab569b9 100644 --- a/Autocoders/Python/src/fprime_ac/utils/buildroot.py +++ b/Autocoders/Python/src/fprime_ac/utils/buildroot.py @@ -41,6 +41,7 @@ def get_nearest_build_root(path): :param path: path to find nearest build root to :return: nearest build root """ + path = os.path.abspath(path) parents = filter( lambda build: os.path.commonpath([build, path]) == build, get_build_roots() ) diff --git a/Ref/Top/CMakeLists.txt b/Ref/Top/CMakeLists.txt index 1399d95ebd..9de37fec1a 100644 --- a/Ref/Top/CMakeLists.txt +++ b/Ref/Top/CMakeLists.txt @@ -7,6 +7,7 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/instances.fpp" + "${CMAKE_CURRENT_LIST_DIR}/RefPackets.xml" "${CMAKE_CURRENT_LIST_DIR}/topology.fpp" "${CMAKE_CURRENT_LIST_DIR}/RefTopology.cpp" ) @@ -18,4 +19,4 @@ set(MOD_DEPS Drv/TcpClient ) -register_fprime_module() \ No newline at end of file +register_fprime_module() diff --git a/Ref/Top/RefPacketsAi.xml b/Ref/Top/RefPackets.xml similarity index 65% rename from Ref/Top/RefPacketsAi.xml rename to Ref/Top/RefPackets.xml index 3a9e2bc86e..8ad799a436 100644 --- a/Ref/Top/RefPacketsAi.xml +++ b/Ref/Top/RefPackets.xml @@ -18,8 +18,9 @@ - + + @@ -64,51 +65,83 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - + - + - + - + - + - + - + - + diff --git a/Ref/Top/RefTopology.cpp b/Ref/Top/RefTopology.cpp index 22a3a2370c..4266f97111 100644 --- a/Ref/Top/RefTopology.cpp +++ b/Ref/Top/RefTopology.cpp @@ -10,6 +10,7 @@ // ====================================================================== // Provides access to autocoded functions #include +#include // Necessary project-specified types #include @@ -60,7 +61,7 @@ enum TopologyConstants { // Ping entries are autocoded, however; this code is not properly exported. Thus, it is copied here. Svc::Health::PingEntry pingEntries[] = { {PingEntries::blockDrv::WARN, PingEntries::blockDrv::FATAL, "blockDrv"}, - {PingEntries::chanTlm::WARN, PingEntries::chanTlm::FATAL, "chanTlm"}, + {PingEntries::tlmSend::WARN, PingEntries::tlmSend::FATAL, "chanTlm"}, {PingEntries::cmdDisp::WARN, PingEntries::cmdDisp::FATAL, "cmdDisp"}, {PingEntries::cmdSeq::WARN, PingEntries::cmdSeq::FATAL, "cmdSeq"}, {PingEntries::eventLogger::WARN, PingEntries::eventLogger::FATAL, "eventLogger"}, @@ -114,6 +115,9 @@ void configureTopology() { // Framer and Deframer components need to be passed a protocol handler downlink.setup(framing); uplink.setup(deframing); + + // Note: Uncomment when using Svc:TlmPacketizer + //tlmSend.setPacketList(RefPacketsPkts, RefPacketsIgnore, 1); } // Public functions for use in main program are namespaced with deployment name Ref diff --git a/Ref/Top/RefTopologyDefs.hpp b/Ref/Top/RefTopologyDefs.hpp index 93e50bbfbe..6c5b3de729 100644 --- a/Ref/Top/RefTopologyDefs.hpp +++ b/Ref/Top/RefTopologyDefs.hpp @@ -56,7 +56,7 @@ namespace PingEntries { namespace blockDrv { enum { WARN = 3, FATAL = 5 }; } -namespace chanTlm { +namespace tlmSend { enum { WARN = 3, FATAL = 5 }; } namespace cmdDisp { diff --git a/Ref/Top/instances.fpp b/Ref/Top/instances.fpp index efde81b0bb..86d2490e81 100644 --- a/Ref/Top/instances.fpp +++ b/Ref/Top/instances.fpp @@ -68,11 +68,20 @@ module Ref { stack size Default.STACK_SIZE \ priority 98 - instance chanTlm: Svc.TlmChan base id 0x0C00 \ + # comment in Svc.TlmChan or Svc.TlmPacketizer + # depending on which form of telemetry downlink + # you wish to use + + instance tlmSend: Svc.TlmChan base id 0x0C00 \ queue size Default.QUEUE_SIZE \ stack size Default.STACK_SIZE \ priority 97 + #instance tlmSend: Svc.TlmPacketizer base id 0x0C00 \ + # queue size Default.QUEUE_SIZE \ + # stack size Default.STACK_SIZE \ + # priority 97 + instance prmDb: Svc.PrmDb base id 0x0D00 \ queue size Default.QUEUE_SIZE \ stack size Default.STACK_SIZE \ diff --git a/Ref/Top/topology.fpp b/Ref/Top/topology.fpp index bff1a2af1a..66b226b5db 100644 --- a/Ref/Top/topology.fpp +++ b/Ref/Top/topology.fpp @@ -28,7 +28,7 @@ module Ref { instance SG4 instance SG5 instance blockDrv - instance chanTlm + instance tlmSend instance cmdDisp instance cmdSeq instance comm @@ -64,7 +64,7 @@ module Ref { param connections instance prmDb - telemetry connections instance chanTlm + telemetry connections instance tlmSend text event connections instance textLogger @@ -78,7 +78,7 @@ module Ref { connections Downlink { - chanTlm.PktSend -> downlink.comIn + tlmSend.PktSend -> downlink.comIn eventLogger.PktSend -> downlink.comIn fileDownlink.bufferSendOut -> downlink.bufferIn @@ -103,7 +103,7 @@ module Ref { rateGroupDriverComp.CycleOut[Ports_RateGroups.rateGroup1] -> rateGroup1Comp.CycleIn rateGroup1Comp.RateGroupMemberOut[0] -> SG1.schedIn rateGroup1Comp.RateGroupMemberOut[1] -> SG2.schedIn - rateGroup1Comp.RateGroupMemberOut[2] -> chanTlm.Run + rateGroup1Comp.RateGroupMemberOut[2] -> tlmSend.Run rateGroup1Comp.RateGroupMemberOut[3] -> fileDownlink.Run rateGroup1Comp.RateGroupMemberOut[4] -> systemResources.run diff --git a/Svc/TlmPacketizer/TlmPacketizer.cpp b/Svc/TlmPacketizer/TlmPacketizer.cpp index 9235394af8..e35990b9ea 100644 --- a/Svc/TlmPacketizer/TlmPacketizer.cpp +++ b/Svc/TlmPacketizer/TlmPacketizer.cpp @@ -8,391 +8,342 @@ // ALL RIGHTS RESERVED. United States Government Sponsorship // acknowledged. -#include #include #include +#include namespace Svc { - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - TlmPacketizer :: - TlmPacketizer( - const char *const compName - ) : - TlmPacketizerComponentBase(compName) - ,m_numPackets(0) - ,m_configured(false) - ,m_startLevel(0) - ,m_maxLevel(0) - { - // clear slot pointers - for (NATIVE_UINT_TYPE entry = 0; entry < TLMPACKETIZER_NUM_TLM_HASH_SLOTS; entry++) { - this->m_tlmEntries.slots[entry] = nullptr; - } - // clear buckets - for (NATIVE_UINT_TYPE entry = 0; entry < TLMPACKETIZER_HASH_BUCKETS; entry++) { - this->m_tlmEntries.buckets[entry].used = false; - this->m_tlmEntries.buckets[entry].bucketNo = entry; - this->m_tlmEntries.buckets[entry].next = nullptr; - this->m_tlmEntries.buckets[entry].id = 0; - } - // clear free index - this->m_tlmEntries.free = 0; - // clear missing tlm channel check - for (NATIVE_UINT_TYPE entry = 0; entry < TLMPACKETIZER_MAX_MISSING_TLM_CHECK; entry++) { - this->m_missTlmCheck[entry].checked = false; - this->m_missTlmCheck[entry].id = 0; - } - - // clear packet buffers - for (NATIVE_UINT_TYPE buffer = 0; buffer < MAX_PACKETIZER_PACKETS; buffer++) { - this->m_fillBuffers[buffer].updated = false; - this->m_fillBuffers[buffer].requested = false; - this->m_sendBuffers[buffer].updated = false; - } - } - - void TlmPacketizer :: - init( - const NATIVE_INT_TYPE queueDepth, - const NATIVE_INT_TYPE instance - ) - { +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +TlmPacketizer ::TlmPacketizer(const char* const compName) + : TlmPacketizerComponentBase(compName), m_numPackets(0), m_configured(false), m_startLevel(0), m_maxLevel(0) { + // clear slot pointers + for (NATIVE_UINT_TYPE entry = 0; entry < TLMPACKETIZER_NUM_TLM_HASH_SLOTS; entry++) { + this->m_tlmEntries.slots[entry] = nullptr; + } + // clear buckets + for (NATIVE_UINT_TYPE entry = 0; entry < TLMPACKETIZER_HASH_BUCKETS; entry++) { + this->m_tlmEntries.buckets[entry].used = false; + this->m_tlmEntries.buckets[entry].bucketNo = entry; + this->m_tlmEntries.buckets[entry].next = nullptr; + this->m_tlmEntries.buckets[entry].id = 0; + } + // clear free index + this->m_tlmEntries.free = 0; + // clear missing tlm channel check + for (NATIVE_UINT_TYPE entry = 0; entry < TLMPACKETIZER_MAX_MISSING_TLM_CHECK; entry++) { + this->m_missTlmCheck[entry].checked = false; + this->m_missTlmCheck[entry].id = 0; + } + + // clear packet buffers + for (NATIVE_UINT_TYPE buffer = 0; buffer < MAX_PACKETIZER_PACKETS; buffer++) { + this->m_fillBuffers[buffer].updated = false; + this->m_fillBuffers[buffer].requested = false; + this->m_sendBuffers[buffer].updated = false; + } +} + +void TlmPacketizer ::init(const NATIVE_INT_TYPE queueDepth, const NATIVE_INT_TYPE instance) { TlmPacketizerComponentBase::init(queueDepth, instance); - } - - TlmPacketizer :: - ~TlmPacketizer() - { - - } - - void TlmPacketizer::setPacketList( - const TlmPacketizerPacketList& packetList, - const Svc::TlmPacketizerPacket& ignoreList, - const NATIVE_UINT_TYPE startLevel) { - - FW_ASSERT(packetList.list); - FW_ASSERT(ignoreList.list); - FW_ASSERT(packetList.numEntries <= MAX_PACKETIZER_PACKETS,packetList.numEntries); - // validate packet sizes against maximum com buffer size and populate hash - // table - for (NATIVE_UINT_TYPE pktEntry = 0; pktEntry < packetList.numEntries; pktEntry++) { - // Initial size is packetized telemetry descriptor + size of time tag + sizeof packet ID - NATIVE_UINT_TYPE packetLen = sizeof(FwPacketDescriptorType) + Fw::Time::SERIALIZED_SIZE + sizeof(FwTlmPacketizeIdType); - FW_ASSERT(packetList.list[pktEntry]->list,pktEntry); - // add up entries for each defined packet - for (NATIVE_UINT_TYPE tlmEntry = 0; tlmEntry < packetList.list[pktEntry]->numEntries; tlmEntry++) { - // get hash value for id - FwChanIdType id = packetList.list[pktEntry]->list[tlmEntry].id; - TlmEntry *entryToUse = this->findBucket(id); - // copy into entry - FW_ASSERT(entryToUse); - entryToUse->used = true; - // not ignored channel - entryToUse->ignored = false; - entryToUse->id = id; - // the offset into the buffer will be the current packet length - entryToUse->packetOffset[pktEntry] = packetLen; - - packetLen += packetList.list[pktEntry]->list[tlmEntry].size; - - } // end channel in packet - FW_ASSERT(packetLen <= FW_COM_BUFFER_MAX_SIZE,packetLen,pktEntry); - // clear contents - memset(this->m_fillBuffers[pktEntry].buffer.getBuffAddr(),0,packetLen); - // serialize packet descriptor and packet ID now since it will always be the same - Fw::SerializeStatus stat = this->m_fillBuffers[pktEntry].buffer.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM)); - FW_ASSERT(Fw::FW_SERIALIZE_OK == stat,stat); - stat = this->m_fillBuffers[pktEntry].buffer.serialize(packetList.list[pktEntry]->id); - FW_ASSERT(Fw::FW_SERIALIZE_OK == stat,stat); - // set packet buffer length - stat = this->m_fillBuffers[pktEntry].buffer.setBuffLen(packetLen); - FW_ASSERT(Fw::FW_SERIALIZE_OK == stat,stat); - // save ID - this->m_fillBuffers[pktEntry].id = packetList.list[pktEntry]->id; - // save level - this->m_fillBuffers[pktEntry].level = packetList.list[pktEntry]->level; - // store max level - if (packetList.list[pktEntry]->level > this->m_maxLevel) { - this->m_maxLevel = packetList.list[pktEntry]->level; - } - // save start level - this->m_startLevel = startLevel; - - } // end packet list - - // populate hash table with ignore list - for (NATIVE_UINT_TYPE channelEntry = 0; channelEntry < ignoreList.numEntries; channelEntry++) { - // get hash value for id - FwChanIdType id = ignoreList.list[channelEntry].id; - - TlmEntry *entryToUse = this->findBucket(id); - - // copy into entry - FW_ASSERT(entryToUse); - entryToUse->used = true; - // is ignored channel - entryToUse->ignored = true; - entryToUse->id = id; - } // end ignore list - - // store number of packets - this->m_numPackets = packetList.numEntries; - - // indicate configured - this->m_configured = true; - } - - TlmPacketizer::TlmEntry* TlmPacketizer::findBucket(FwChanIdType id) { - NATIVE_UINT_TYPE index = this->doHash(id); - FW_ASSERT(index < TLMPACKETIZER_HASH_BUCKETS); - TlmEntry* entryToUse = nullptr; - TlmEntry* prevEntry = nullptr; - - // Search to see if channel has already been stored or a bucket needs to be added - if (this->m_tlmEntries.slots[index]) { - entryToUse = this->m_tlmEntries.slots[index]; - for (NATIVE_UINT_TYPE bucket = 0; bucket < TLMPACKETIZER_HASH_BUCKETS; bucket++) { - if (entryToUse) { - if (entryToUse->id == id) { // found the matching entry - break; - } else { // try next entry - prevEntry = entryToUse; - entryToUse = entryToUse->next; - } - } else { - // Make sure that we haven't run out of buckets - FW_ASSERT(this->m_tlmEntries.free < TLMPACKETIZER_HASH_BUCKETS,this->m_tlmEntries.free); - // add new bucket from free list - entryToUse = &this->m_tlmEntries.buckets[this->m_tlmEntries.free++]; - // Coverity warning about null dereference - see if it happens - FW_ASSERT(prevEntry); - prevEntry->next = entryToUse; - // clear next pointer - entryToUse->next = nullptr; - // set all packet offsets to -1 for new entry - for (NATIVE_UINT_TYPE pktOffsetEntry = 0; pktOffsetEntry < MAX_PACKETIZER_PACKETS; pktOffsetEntry++) { - entryToUse->packetOffset[pktOffsetEntry] = -1; - } - break; - } - } - } else { - // Make sure that we haven't run out of buckets - FW_ASSERT(this->m_tlmEntries.free < TLMPACKETIZER_HASH_BUCKETS,this->m_tlmEntries.free); - // create new entry at slot head - this->m_tlmEntries.slots[index] = &this->m_tlmEntries.buckets[this->m_tlmEntries.free++]; - entryToUse = this->m_tlmEntries.slots[index]; - entryToUse->next = nullptr; - // set all packet offsets to -1 for new entry - for (NATIVE_UINT_TYPE pktOffsetEntry = 0; pktOffsetEntry < MAX_PACKETIZER_PACKETS; pktOffsetEntry++) { - entryToUse->packetOffset[pktOffsetEntry] = -1; - } - - } - - return entryToUse; - } - - - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - void TlmPacketizer :: - TlmRecv_handler( - const NATIVE_INT_TYPE portNum, - FwChanIdType id, - Fw::Time &timeTag, - Fw::TlmBuffer &val - ) - { - FW_ASSERT(this->m_configured); - // get hash value for id - NATIVE_UINT_TYPE index = this->doHash(id); - TlmEntry* entryToUse = nullptr; - - // Search to see if the channel is being sent - entryToUse = this->m_tlmEntries.slots[index]; - - // if no entries at hash, channel not part of a packet or is not ignored - if (not entryToUse) { - this->missingChannel(id); - return; - } - - for (NATIVE_UINT_TYPE bucket = 0; bucket < TLMPACKETIZER_HASH_BUCKETS; bucket++) { - if (entryToUse) { - if (entryToUse->id == id) { // found the matching entry - // check to see if the channel is ignored. If so, just return. - if (entryToUse->ignored) { - return; - } - break; - } else { // try next entry - entryToUse = entryToUse->next; - } - } else { - // telemetry channel not in any packets - this->missingChannel(id); - return; - } - } - - // copy telemetry value into active buffers - for (NATIVE_UINT_TYPE pkt = 0; pkt < MAX_PACKETIZER_PACKETS; pkt++) { - // check if current packet has this channel - if (entryToUse->packetOffset[pkt] != -1) { - // get destination address - // printf("PK %d CH: %d\n",this->m_fillBuffers[pkt].id,id); - this->m_lock.lock(); - this->m_fillBuffers[pkt].updated = true; - this->m_fillBuffers[pkt].latestTime = timeTag; - U8* ptr = &this->m_fillBuffers[pkt].buffer.getBuffAddr()[entryToUse->packetOffset[pkt]]; - memcpy(ptr,val.getBuffAddr(),val.getBuffLength()); - this->m_lock.unLock(); - } - } - - } - - void TlmPacketizer :: - Run_handler( - const NATIVE_INT_TYPE portNum, - NATIVE_UINT_TYPE context - ) - { - FW_ASSERT(this->m_configured); - - // Only write packets if connected - if (not this->isConnected_PktSend_OutputPort(0)) { - return; - } - - // lock mutex long enough to modify active telemetry buffer - // so the data can be read without worrying about updates - this->m_lock.lock(); - // copy buffers from fill side to send side - for (NATIVE_UINT_TYPE pkt = 0; pkt < this->m_numPackets; pkt++) { - if ((this->m_fillBuffers[pkt].updated) and - ((this->m_fillBuffers[pkt].level <= this->m_startLevel) or - (this->m_fillBuffers[pkt].requested))) { - - this->m_sendBuffers[pkt] = this->m_fillBuffers[pkt]; - if (PACKET_UPDATE_ON_CHANGE == PACKET_UPDATE_MODE) { - this->m_fillBuffers[pkt].updated = false; - } - this->m_fillBuffers[pkt].requested = false; - // PACKET_UPDATE_AFTER_FIRST_CHANGE will be this case - updated flag will not be cleared - } else if ((PACKET_UPDATE_ALWAYS == PACKET_UPDATE_MODE) and (this->m_fillBuffers[pkt].level <= this->m_startLevel)) { - this->m_sendBuffers[pkt] = this->m_fillBuffers[pkt]; - this->m_sendBuffers[pkt].updated = true; - } else { - this->m_sendBuffers[pkt].updated = false; - } - } - this->m_lock.unLock(); - - // push all updated packet buffers - for (NATIVE_UINT_TYPE pkt = 0; pkt < this->m_numPackets; pkt++) { - if (this->m_sendBuffers[pkt].updated) { - // serialize time into time offset in packet - Fw::ExternalSerializeBuffer buff(&this->m_sendBuffers[pkt].buffer.getBuffAddr() - [sizeof(FwPacketDescriptorType)+ sizeof(FwTlmPacketizeIdType)],Fw::Time::SERIALIZED_SIZE); - Fw::SerializeStatus stat = buff.serialize(this->m_sendBuffers[pkt].latestTime); - FW_ASSERT(Fw::FW_SERIALIZE_OK == stat, stat); - this->PktSend_out(0,this->m_sendBuffers[pkt].buffer,0); - } - } - } - - void TlmPacketizer :: - pingIn_handler( - const NATIVE_INT_TYPE portNum, - U32 key - ) - { - // return key - this->pingOut_out(0,key); - } - - // ---------------------------------------------------------------------- - // Command handler implementations - // ---------------------------------------------------------------------- - - void TlmPacketizer :: - SET_LEVEL_cmdHandler( - const FwOpcodeType opCode, - const U32 cmdSeq, - U32 level - ) - { - this->m_startLevel = level; - if (level > this->m_maxLevel) { - this->log_WARNING_LO_MaxLevelExceed(level,this->m_maxLevel); - } - this->tlmWrite_SendLevel(level); - this->log_ACTIVITY_HI_LevelSet(level); - this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); - } - - void TlmPacketizer :: - SEND_PKT_cmdHandler( - const FwOpcodeType opCode, - const U32 cmdSeq, - U32 id - ) - { - NATIVE_UINT_TYPE pkt = 0; - for (pkt = 0; pkt < this->m_numPackets; pkt++) { - if (this->m_fillBuffers[pkt].id == id) { - - this->m_lock.lock(); - this->m_fillBuffers[pkt].updated = true; - this->m_fillBuffers[pkt].latestTime = this->getTime(); - this->m_fillBuffers[pkt].requested = true; - this->m_lock.unLock(); - - this->log_ACTIVITY_LO_PacketSent(id); - break; - } - } - - // couldn't find it - if (pkt == this->m_numPackets) { - log_WARNING_LO_PacketNotFound(id); - this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::VALIDATION_ERROR); - return; - } - - this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); - } - - - NATIVE_UINT_TYPE TlmPacketizer::doHash(FwChanIdType id) { - return (id % TLMPACKETIZER_HASH_MOD_VALUE)%TLMPACKETIZER_NUM_TLM_HASH_SLOTS; - } - - void TlmPacketizer::missingChannel(FwChanIdType id) { - // search to see if missing channel has already been sent - for (NATIVE_UINT_TYPE slot = 0; slot < TLMPACKETIZER_MAX_MISSING_TLM_CHECK; slot++) { - // if it's been checked, return - if (this->m_missTlmCheck[slot].checked and (this->m_missTlmCheck[slot].id == id)) { - return; - } else if (not this->m_missTlmCheck[slot].checked) { - this->m_missTlmCheck[slot].checked = true; - this->m_missTlmCheck[slot].id = id; - this->log_WARNING_LO_NoChan(id); - return; - } - } - - } - - -} // end namespace Svc +} + +TlmPacketizer ::~TlmPacketizer() {} + +void TlmPacketizer::setPacketList(const TlmPacketizerPacketList& packetList, + const Svc::TlmPacketizerPacket& ignoreList, + const NATIVE_UINT_TYPE startLevel) { + FW_ASSERT(packetList.list); + FW_ASSERT(ignoreList.list); + FW_ASSERT(packetList.numEntries <= MAX_PACKETIZER_PACKETS, packetList.numEntries); + // validate packet sizes against maximum com buffer size and populate hash + // table + for (NATIVE_UINT_TYPE pktEntry = 0; pktEntry < packetList.numEntries; pktEntry++) { + // Initial size is packetized telemetry descriptor + size of time tag + sizeof packet ID + NATIVE_UINT_TYPE packetLen = + sizeof(FwPacketDescriptorType) + Fw::Time::SERIALIZED_SIZE + sizeof(FwTlmPacketizeIdType); + FW_ASSERT(packetList.list[pktEntry]->list, pktEntry); + // add up entries for each defined packet + for (NATIVE_UINT_TYPE tlmEntry = 0; tlmEntry < packetList.list[pktEntry]->numEntries; tlmEntry++) { + // get hash value for id + FwChanIdType id = packetList.list[pktEntry]->list[tlmEntry].id; + TlmEntry* entryToUse = this->findBucket(id); + // copy into entry + FW_ASSERT(entryToUse); + entryToUse->used = true; + // not ignored channel + entryToUse->ignored = false; + entryToUse->id = id; + // the offset into the buffer will be the current packet length + entryToUse->packetOffset[pktEntry] = packetLen; + + packetLen += packetList.list[pktEntry]->list[tlmEntry].size; + + } // end channel in packet + FW_ASSERT(packetLen <= FW_COM_BUFFER_MAX_SIZE, packetLen, pktEntry); + // clear contents + memset(this->m_fillBuffers[pktEntry].buffer.getBuffAddr(), 0, packetLen); + // serialize packet descriptor and packet ID now since it will always be the same + Fw::SerializeStatus stat = this->m_fillBuffers[pktEntry].buffer.serialize( + static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM)); + FW_ASSERT(Fw::FW_SERIALIZE_OK == stat, stat); + stat = this->m_fillBuffers[pktEntry].buffer.serialize(packetList.list[pktEntry]->id); + FW_ASSERT(Fw::FW_SERIALIZE_OK == stat, stat); + // set packet buffer length + stat = this->m_fillBuffers[pktEntry].buffer.setBuffLen(packetLen); + FW_ASSERT(Fw::FW_SERIALIZE_OK == stat, stat); + // save ID + this->m_fillBuffers[pktEntry].id = packetList.list[pktEntry]->id; + // save level + this->m_fillBuffers[pktEntry].level = packetList.list[pktEntry]->level; + // store max level + if (packetList.list[pktEntry]->level > this->m_maxLevel) { + this->m_maxLevel = packetList.list[pktEntry]->level; + } + // save start level + this->m_startLevel = startLevel; + + } // end packet list + + // populate hash table with ignore list + for (NATIVE_UINT_TYPE channelEntry = 0; channelEntry < ignoreList.numEntries; channelEntry++) { + // get hash value for id + FwChanIdType id = ignoreList.list[channelEntry].id; + + TlmEntry* entryToUse = this->findBucket(id); + + // copy into entry + FW_ASSERT(entryToUse); + entryToUse->used = true; + // is ignored channel + entryToUse->ignored = true; + entryToUse->id = id; + } // end ignore list + + // store number of packets + this->m_numPackets = packetList.numEntries; + + // indicate configured + this->m_configured = true; +} + +TlmPacketizer::TlmEntry* TlmPacketizer::findBucket(FwChanIdType id) { + NATIVE_UINT_TYPE index = this->doHash(id); + FW_ASSERT(index < TLMPACKETIZER_HASH_BUCKETS); + TlmEntry* entryToUse = nullptr; + TlmEntry* prevEntry = nullptr; + + // Search to see if channel has already been stored or a bucket needs to be added + if (this->m_tlmEntries.slots[index]) { + entryToUse = this->m_tlmEntries.slots[index]; + for (NATIVE_UINT_TYPE bucket = 0; bucket < TLMPACKETIZER_HASH_BUCKETS; bucket++) { + if (entryToUse) { + if (entryToUse->id == id) { // found the matching entry + break; + } else { // try next entry + prevEntry = entryToUse; + entryToUse = entryToUse->next; + } + } else { + // Make sure that we haven't run out of buckets + FW_ASSERT(this->m_tlmEntries.free < TLMPACKETIZER_HASH_BUCKETS, this->m_tlmEntries.free); + // add new bucket from free list + entryToUse = &this->m_tlmEntries.buckets[this->m_tlmEntries.free++]; + // Coverity warning about null dereference - see if it happens + FW_ASSERT(prevEntry); + prevEntry->next = entryToUse; + // clear next pointer + entryToUse->next = nullptr; + // set all packet offsets to -1 for new entry + for (NATIVE_UINT_TYPE pktOffsetEntry = 0; pktOffsetEntry < MAX_PACKETIZER_PACKETS; pktOffsetEntry++) { + entryToUse->packetOffset[pktOffsetEntry] = -1; + } + break; + } + } + } else { + // Make sure that we haven't run out of buckets + FW_ASSERT(this->m_tlmEntries.free < TLMPACKETIZER_HASH_BUCKETS, this->m_tlmEntries.free); + // create new entry at slot head + this->m_tlmEntries.slots[index] = &this->m_tlmEntries.buckets[this->m_tlmEntries.free++]; + entryToUse = this->m_tlmEntries.slots[index]; + entryToUse->next = nullptr; + // set all packet offsets to -1 for new entry + for (NATIVE_UINT_TYPE pktOffsetEntry = 0; pktOffsetEntry < MAX_PACKETIZER_PACKETS; pktOffsetEntry++) { + entryToUse->packetOffset[pktOffsetEntry] = -1; + } + } + + return entryToUse; +} + +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- + +void TlmPacketizer ::TlmRecv_handler(const NATIVE_INT_TYPE portNum, + FwChanIdType id, + Fw::Time& timeTag, + Fw::TlmBuffer& val) { + FW_ASSERT(this->m_configured); + // get hash value for id + NATIVE_UINT_TYPE index = this->doHash(id); + TlmEntry* entryToUse = nullptr; + + // Search to see if the channel is being sent + entryToUse = this->m_tlmEntries.slots[index]; + + // if no entries at hash, channel not part of a packet or is not ignored + if (not entryToUse) { + this->missingChannel(id); + return; + } + + for (NATIVE_UINT_TYPE bucket = 0; bucket < TLMPACKETIZER_HASH_BUCKETS; bucket++) { + if (entryToUse) { + if (entryToUse->id == id) { // found the matching entry + // check to see if the channel is ignored. If so, just return. + if (entryToUse->ignored) { + return; + } + break; + } else { // try next entry + entryToUse = entryToUse->next; + } + } else { + // telemetry channel not in any packets + this->missingChannel(id); + return; + } + } + + // copy telemetry value into active buffers + for (NATIVE_UINT_TYPE pkt = 0; pkt < MAX_PACKETIZER_PACKETS; pkt++) { + // check if current packet has this channel + if (entryToUse->packetOffset[pkt] != -1) { + // get destination address + // printf("PK %d CH: %d\n",this->m_fillBuffers[pkt].id,id); + this->m_lock.lock(); + this->m_fillBuffers[pkt].updated = true; + this->m_fillBuffers[pkt].latestTime = timeTag; + U8* ptr = &this->m_fillBuffers[pkt].buffer.getBuffAddr()[entryToUse->packetOffset[pkt]]; + memcpy(ptr, val.getBuffAddr(), val.getBuffLength()); + this->m_lock.unLock(); + } + } +} + +void TlmPacketizer ::Run_handler(const NATIVE_INT_TYPE portNum, NATIVE_UINT_TYPE context) { + FW_ASSERT(this->m_configured); + + // Only write packets if connected + if (not this->isConnected_PktSend_OutputPort(0)) { + return; + } + + // lock mutex long enough to modify active telemetry buffer + // so the data can be read without worrying about updates + this->m_lock.lock(); + // copy buffers from fill side to send side + for (NATIVE_UINT_TYPE pkt = 0; pkt < this->m_numPackets; pkt++) { + if ((this->m_fillBuffers[pkt].updated) and + ((this->m_fillBuffers[pkt].level <= this->m_startLevel) or (this->m_fillBuffers[pkt].requested))) { + this->m_sendBuffers[pkt] = this->m_fillBuffers[pkt]; + if (PACKET_UPDATE_ON_CHANGE == PACKET_UPDATE_MODE) { + this->m_fillBuffers[pkt].updated = false; + } + this->m_fillBuffers[pkt].requested = false; + // PACKET_UPDATE_AFTER_FIRST_CHANGE will be this case - updated flag will not be cleared + } else if ((PACKET_UPDATE_ALWAYS == PACKET_UPDATE_MODE) and + (this->m_fillBuffers[pkt].level <= this->m_startLevel)) { + this->m_sendBuffers[pkt] = this->m_fillBuffers[pkt]; + this->m_sendBuffers[pkt].updated = true; + } else { + this->m_sendBuffers[pkt].updated = false; + } + } + this->m_lock.unLock(); + + // push all updated packet buffers + for (NATIVE_UINT_TYPE pkt = 0; pkt < this->m_numPackets; pkt++) { + if (this->m_sendBuffers[pkt].updated) { + // serialize time into time offset in packet + Fw::ExternalSerializeBuffer buff( + &this->m_sendBuffers[pkt] + .buffer.getBuffAddr()[sizeof(FwPacketDescriptorType) + sizeof(FwTlmPacketizeIdType)], + Fw::Time::SERIALIZED_SIZE); + Fw::SerializeStatus stat = buff.serialize(this->m_sendBuffers[pkt].latestTime); + FW_ASSERT(Fw::FW_SERIALIZE_OK == stat, stat); + + this->PktSend_out(0, this->m_sendBuffers[pkt].buffer, 0); + } + } +} + +void TlmPacketizer ::pingIn_handler(const NATIVE_INT_TYPE portNum, U32 key) { + // return key + this->pingOut_out(0, key); +} + +// ---------------------------------------------------------------------- +// Command handler implementations +// ---------------------------------------------------------------------- + +void TlmPacketizer ::SET_LEVEL_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, U32 level) { + this->m_startLevel = level; + if (level > this->m_maxLevel) { + this->log_WARNING_LO_MaxLevelExceed(level, this->m_maxLevel); + } + this->tlmWrite_SendLevel(level); + this->log_ACTIVITY_HI_LevelSet(level); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TlmPacketizer ::SEND_PKT_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, U32 id) { + NATIVE_UINT_TYPE pkt = 0; + for (pkt = 0; pkt < this->m_numPackets; pkt++) { + if (this->m_fillBuffers[pkt].id == id) { + this->m_lock.lock(); + this->m_fillBuffers[pkt].updated = true; + this->m_fillBuffers[pkt].latestTime = this->getTime(); + this->m_fillBuffers[pkt].requested = true; + this->m_lock.unLock(); + + this->log_ACTIVITY_LO_PacketSent(id); + break; + } + } + + // couldn't find it + if (pkt == this->m_numPackets) { + log_WARNING_LO_PacketNotFound(id); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::VALIDATION_ERROR); + return; + } + + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +NATIVE_UINT_TYPE TlmPacketizer::doHash(FwChanIdType id) { + return (id % TLMPACKETIZER_HASH_MOD_VALUE) % TLMPACKETIZER_NUM_TLM_HASH_SLOTS; +} + +void TlmPacketizer::missingChannel(FwChanIdType id) { + // search to see if missing channel has already been sent + for (NATIVE_UINT_TYPE slot = 0; slot < TLMPACKETIZER_MAX_MISSING_TLM_CHECK; slot++) { + // if it's been checked, return + if (this->m_missTlmCheck[slot].checked and (this->m_missTlmCheck[slot].id == id)) { + return; + } else if (not this->m_missTlmCheck[slot].checked) { + this->m_missTlmCheck[slot].checked = true; + this->m_missTlmCheck[slot].id = id; + this->log_WARNING_LO_NoChan(id); + return; + } + } +} + +} // end namespace Svc diff --git a/Svc/TlmPacketizer/TlmPacketizer.hpp b/Svc/TlmPacketizer/TlmPacketizer.hpp index d8492946be..4957bb3cd9 100644 --- a/Svc/TlmPacketizer/TlmPacketizer.hpp +++ b/Svc/TlmPacketizer/TlmPacketizer.hpp @@ -1,4 +1,4 @@ -// ====================================================================== +// ====================================================================== // \title TlmPacketizerImpl.hpp // \author tcanham // \brief hpp file for TlmPacketizer component implementation class @@ -11,147 +11,134 @@ #ifndef TlmPacketizer_HPP #define TlmPacketizer_HPP +#include "Os/Mutex.hpp" #include "Svc/TlmPacketizer/TlmPacketizerComponentAc.hpp" #include "Svc/TlmPacketizer/TlmPacketizerTypes.hpp" -#include "Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp" -#include "Os/Mutex.hpp" +#include "TlmPacketizerCfg.hpp" namespace Svc { - class TlmPacketizer : - public TlmPacketizerComponentBase - { - - public: - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object TlmPacketizer - //! - TlmPacketizer( - const char *const compName /*!< The component name*/ - ); - - //! Initialize object TlmPacketizer - //! - void init( - const NATIVE_INT_TYPE queueDepth, /*!< The queue depth*/ - const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ - ); - - void setPacketList( - const TlmPacketizerPacketList& packetList, // channels to packetize - const Svc::TlmPacketizerPacket& ignoreList, // channels to ignore (i.e. no warning event if not packetized) - const NATIVE_UINT_TYPE startLevel); // starting level of packets to send - - //! Destroy object TlmPacketizer - //! - ~TlmPacketizer(void); - - PRIVATE: - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for TlmRecv - //! - void TlmRecv_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - FwChanIdType id, /*!< Telemetry Channel ID*/ - Fw::Time &timeTag, /*!< Time Tag*/ - Fw::TlmBuffer &val /*!< Buffer containing serialized telemetry value*/ - ); - - //! Handler implementation for Run - //! - void Run_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - NATIVE_UINT_TYPE context /*!< The call order*/ - ); - - //! Handler implementation for pingIn - //! - void pingIn_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U32 key /*!< Value to return to pinger*/ - ); - - //! Implementation for SET_LEVEL command handler - //! Set telemetry send leve - void SET_LEVEL_cmdHandler( - const FwOpcodeType opCode, /*!< The opcode*/ - const U32 cmdSeq, /*!< The command sequence number*/ - U32 level /*!< The I32 command argument*/ - ); - - //! Implementation for SEND_PKT command handler - //! Force a packet to be sent - void SEND_PKT_cmdHandler( - const FwOpcodeType opCode, /*!< The opcode*/ - const U32 cmdSeq, /*!< The command sequence number*/ - U32 id /*!< The packet ID*/ - ); - - // number of packets to fill - NATIVE_UINT_TYPE m_numPackets; - // Array of packet buffers to send - // Double-buffered to fill one while sending one - - struct BufferEntry { - Fw::ComBuffer buffer; //!< buffer for packetized channels - Fw::Time latestTime; //!< latest update time - NATIVE_UINT_TYPE id; //!< channel id - NATIVE_UINT_TYPE level; //!< channel level - bool updated; //!< if packet had any updates during last cycle - bool requested; //!< if the packet was requested with SEND_PKT in the last cycle - }; - - // buffers for filling with telemetry - BufferEntry m_fillBuffers[MAX_PACKETIZER_PACKETS]; - // buffers for sending - will be copied from fill buffers - BufferEntry m_sendBuffers[MAX_PACKETIZER_PACKETS]; - - struct TlmEntry { - FwChanIdType id; //!< telemetry id stored in slot - // Offsets into packet buffers. - // -1 means that channel is not in that packet - NATIVE_INT_TYPE packetOffset[MAX_PACKETIZER_PACKETS]; - TlmEntry* next; //!< pointer to next bucket in table - bool used; //!< if entry has been used - bool ignored; //!< ignored packet id - NATIVE_UINT_TYPE bucketNo; //!< for testing - }; - - struct TlmSet { - TlmEntry* slots[TLMPACKETIZER_NUM_TLM_HASH_SLOTS]; //!< set of hash slots in hash table - TlmEntry buckets[TLMPACKETIZER_HASH_BUCKETS]; //!< set of buckets used in hash table - NATIVE_UINT_TYPE free; //!< next free bucket - } m_tlmEntries; - - // hash function for looking up telemetry channel - NATIVE_UINT_TYPE doHash(FwChanIdType id); - - Os::Mutex m_lock; //!< used to lock access to packet buffers - - bool m_configured; //!< indicates a table has been passed and packets configured - - struct MissingTlmChan { - FwChanIdType id; - bool checked; - } m_missTlmCheck[TLMPACKETIZER_MAX_MISSING_TLM_CHECK]; - - void missingChannel(FwChanIdType id); //!< Helper to check to see if missing channel warning was sent - - TlmEntry* findBucket(FwChanIdType id); - - NATIVE_UINT_TYPE m_startLevel; //!< initial level for sending packets - NATIVE_UINT_TYPE m_maxLevel; //!< maximum level in all packets +class TlmPacketizer : public TlmPacketizerComponentBase { + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object TlmPacketizer + //! + TlmPacketizer(const char* const compName /*!< The component name*/ + ); + + //! Initialize object TlmPacketizer + //! + void init(const NATIVE_INT_TYPE queueDepth, /*!< The queue depth*/ + const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ + ); + + void setPacketList( + const TlmPacketizerPacketList& packetList, // channels to packetize + const Svc::TlmPacketizerPacket& ignoreList, // channels to ignore (i.e. no warning event if not packetized) + const NATIVE_UINT_TYPE startLevel); // starting level of packets to send + + //! Destroy object TlmPacketizer + //! + ~TlmPacketizer(void); + + PRIVATE: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for TlmRecv + //! + void TlmRecv_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + FwChanIdType id, /*!< Telemetry Channel ID*/ + Fw::Time& timeTag, /*!< Time Tag*/ + Fw::TlmBuffer& val /*!< Buffer containing serialized telemetry value*/ + ); + + //! Handler implementation for Run + //! + void Run_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + NATIVE_UINT_TYPE context /*!< The call order*/ + ); + + //! Handler implementation for pingIn + //! + void pingIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + U32 key /*!< Value to return to pinger*/ + ); + + //! Implementation for SET_LEVEL command handler + //! Set telemetry send leve + void SET_LEVEL_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + U32 level /*!< The I32 command argument*/ + ); + + //! Implementation for SEND_PKT command handler + //! Force a packet to be sent + void SEND_PKT_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + U32 id /*!< The packet ID*/ + ); + + // number of packets to fill + NATIVE_UINT_TYPE m_numPackets; + // Array of packet buffers to send + // Double-buffered to fill one while sending one + + struct BufferEntry { + Fw::ComBuffer buffer; //!< buffer for packetized channels + Fw::Time latestTime; //!< latest update time + NATIVE_UINT_TYPE id; //!< channel id + NATIVE_UINT_TYPE level; //!< channel level + bool updated; //!< if packet had any updates during last cycle + bool requested; //!< if the packet was requested with SEND_PKT in the last cycle + }; + // buffers for filling with telemetry + BufferEntry m_fillBuffers[MAX_PACKETIZER_PACKETS]; + // buffers for sending - will be copied from fill buffers + BufferEntry m_sendBuffers[MAX_PACKETIZER_PACKETS]; + + struct TlmEntry { + FwChanIdType id; //!< telemetry id stored in slot + // Offsets into packet buffers. + // -1 means that channel is not in that packet + NATIVE_INT_TYPE packetOffset[MAX_PACKETIZER_PACKETS]; + TlmEntry* next; //!< pointer to next bucket in table + bool used; //!< if entry has been used + bool ignored; //!< ignored packet id + NATIVE_UINT_TYPE bucketNo; //!< for testing }; -} // end namespace Svc + struct TlmSet { + TlmEntry* slots[TLMPACKETIZER_NUM_TLM_HASH_SLOTS]; //!< set of hash slots in hash table + TlmEntry buckets[TLMPACKETIZER_HASH_BUCKETS]; //!< set of buckets used in hash table + NATIVE_UINT_TYPE free; //!< next free bucket + } m_tlmEntries; + + // hash function for looking up telemetry channel + NATIVE_UINT_TYPE doHash(FwChanIdType id); + + Os::Mutex m_lock; //!< used to lock access to packet buffers + + bool m_configured; //!< indicates a table has been passed and packets configured + + struct MissingTlmChan { + FwChanIdType id; + bool checked; + } m_missTlmCheck[TLMPACKETIZER_MAX_MISSING_TLM_CHECK]; + + void missingChannel(FwChanIdType id); //!< Helper to check to see if missing channel warning was sent + + TlmEntry* findBucket(FwChanIdType id); + + NATIVE_UINT_TYPE m_startLevel; //!< initial level for sending packets + NATIVE_UINT_TYPE m_maxLevel; //!< maximum level in all packets +}; + +} // end namespace Svc #endif diff --git a/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp b/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp deleted file mode 100644 index bae4d1e91e..0000000000 --- a/Svc/TlmPacketizer/TlmPacketizerComponentImplCfg.hpp +++ /dev/null @@ -1,42 +0,0 @@ -/* - * TlmPacketizerComponentImplCfg.hpp - * - * Created on: Dec 10, 2017 - * Author: tim - */ - -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. - - -#ifndef SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ -#define SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ - -#include - -namespace Svc { - static const NATIVE_UINT_TYPE MAX_PACKETIZER_PACKETS = 200; - static const NATIVE_UINT_TYPE TLMPACKETIZER_NUM_TLM_HASH_SLOTS = 15; // !< Number of slots in the hash table. - // Works best when set to about twice the number of components producing telemetry - static const NATIVE_UINT_TYPE TLMPACKETIZER_HASH_MOD_VALUE = 99; // !< The modulo value of the hashing function. - // Should be set to a little below the ID gaps to spread the entries around - - static const NATIVE_UINT_TYPE TLMPACKETIZER_HASH_BUCKETS = 1000; // !< Buckets assignable to a hash slot. - // Buckets must be >= number of telemetry channels in system - static const NATIVE_UINT_TYPE TLMPACKETIZER_MAX_MISSING_TLM_CHECK = 25; // !< Maximum number of missing telemetry channel checks - - // packet update mode - enum PacketUpdateMode { - PACKET_UPDATE_ALWAYS, // Always send packets, even if no changes to channel data - PACKET_UPDATE_ON_CHANGE, // Only send packets if any of the channels updates - PACKET_UPDATE_AFTER_FIRST_CHANGE, // Always send packets, but only after first channel has been updated - }; - - static const PacketUpdateMode PACKET_UPDATE_MODE = PACKET_UPDATE_ON_CHANGE; -} - - - -#endif /* SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ */ diff --git a/Svc/TlmPacketizer/TlmPacketizerTypes.hpp b/Svc/TlmPacketizer/TlmPacketizerTypes.hpp index 1a0e9efd38..0ef7c38a62 100644 --- a/Svc/TlmPacketizer/TlmPacketizerTypes.hpp +++ b/Svc/TlmPacketizer/TlmPacketizerTypes.hpp @@ -10,31 +10,30 @@ // ALL RIGHTS RESERVED. United States Government Sponsorship // acknowledged. - #ifndef SVC_TLMPACKETIZER_TLMPACKETIZERTYPES_HPP_ #define SVC_TLMPACKETIZER_TLMPACKETIZERTYPES_HPP_ #include -#include +#include namespace Svc { - struct TlmPacketizerChannelEntry { - FwChanIdType id; //!< Id of channel - NATIVE_UINT_TYPE size; //!< serialized size of channel in bytes - }; - - struct TlmPacketizerPacket { - const TlmPacketizerChannelEntry* list; //!< pointer to a channel entry - FwTlmPacketizeIdType id; //!< packet ID - NATIVE_UINT_TYPE level; //!< packet level - used to select set of packets to send - NATIVE_UINT_TYPE numEntries; //!< number of channels in packet - }; - - struct TlmPacketizerPacketList { - const TlmPacketizerPacket* list[MAX_PACKETIZER_PACKETS]; //!< - NATIVE_UINT_TYPE numEntries; - }; -} +struct TlmPacketizerChannelEntry { + FwChanIdType id; //!< Id of channel + NATIVE_UINT_TYPE size; //!< serialized size of channel in bytes +}; + +struct TlmPacketizerPacket { + const TlmPacketizerChannelEntry* list; //!< pointer to a channel entry + FwTlmPacketizeIdType id; //!< packet ID + NATIVE_UINT_TYPE level; //!< packet level - used to select set of packets to send + NATIVE_UINT_TYPE numEntries; //!< number of channels in packet +}; + +struct TlmPacketizerPacketList { + const TlmPacketizerPacket* list[MAX_PACKETIZER_PACKETS]; //!< + NATIVE_UINT_TYPE numEntries; +}; +} // namespace Svc #endif /* SVC_TLMPACKETIZER_TLMPACKETIZERTYPES_HPP_ */ diff --git a/Svc/TlmPacketizer/test/ut/Tester.cpp b/Svc/TlmPacketizer/test/ut/Tester.cpp index ff3be6a8de..f72ef3feab 100644 --- a/Svc/TlmPacketizer/test/ut/Tester.cpp +++ b/Svc/TlmPacketizer/test/ut/Tester.cpp @@ -18,1051 +18,960 @@ namespace Svc { - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - Tester :: - Tester() : - TlmPacketizerGTestBase("Tester", MAX_HISTORY_SIZE), - component("TlmPacketizer") - ,m_timeSent(false) - { +// ---------------------------------------------------------------------- +// Construction and destruction +// ---------------------------------------------------------------------- + +Tester ::Tester() : TlmPacketizerGTestBase("Tester", MAX_HISTORY_SIZE), component("TlmPacketizer"), m_timeSent(false) { this->initComponents(); this->connectPorts(); - } +} + +Tester ::~Tester() {} + +// ---------------------------------------------------------------------- +// Tests +// ---------------------------------------------------------------------- + +// Some Test tables + +TlmPacketizerChannelEntry packet1List[] = {{10, 4}, {100, 2}, {333, 1}}; + +TlmPacketizerChannelEntry packet2List[] = {{10, 4}, {13, 8}, {250, 2}, {22, 1}}; + +TlmPacketizerPacket packet1 = {packet1List, 4, 1, FW_NUM_ARRAY_ELEMENTS(packet1List)}; + +TlmPacketizerPacket packet2 = {packet2List, 8, 2, FW_NUM_ARRAY_ELEMENTS(packet2List)}; + +TlmPacketizerPacketList packetList = {{&packet1, &packet2}, 2}; - Tester :: - ~Tester() - { +TlmPacketizerChannelEntry ignoreList[] = {{25, 0}, {50, 0}}; - } +TlmPacketizerPacket ignore = {ignoreList, 0, 0, FW_NUM_ARRAY_ELEMENTS(ignoreList)}; - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- +void Tester ::initTest() { + this->component.setPacketList(packetList, ignore, 2); +} - // Some Test tables +void Tester ::pushTlmTest() { + this->component.setPacketList(packetList, ignore, 2); + Fw::Time ts; + Fw::TlmBuffer buff; - TlmPacketizerChannelEntry packet1List[] = { - {10, 4}, - {100, 2}, - {333, 1} - }; + // first channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); - TlmPacketizerChannelEntry packet2List[] = { - {10, 4}, - {13, 8}, - {250, 2}, - {22,1} - }; + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); - TlmPacketizerPacket packet1 = {packet1List, 4, 1, FW_NUM_ARRAY_ELEMENTS(packet1List)}; + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); - TlmPacketizerPacket packet2 = {packet2List, 8, 2, FW_NUM_ARRAY_ELEMENTS(packet2List)}; + // second channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(50))); + this->invoke_to_TlmRecv(0, 10, ts, buff); - TlmPacketizerPacketList packetList = { - {&packet1, &packet2}, - 2 - }; + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); - TlmPacketizerChannelEntry ignoreList[] = { - {25, 0}, - {50, 0} - }; - - TlmPacketizerPacket ignore = {ignoreList, 0, 0, FW_NUM_ARRAY_ELEMENTS(ignoreList)}; + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); - void Tester :: - initTest() - { - this->component.setPacketList(packetList,ignore,2); - - } - - void Tester :: - pushTlmTest() - { - this->component.setPacketList(packetList,ignore,2); - Fw::Time ts; - Fw::TlmBuffer buff; + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); +} - // first channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - // second channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(50))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - } - - - void Tester :: - sendPacketsTest() - { - this->component.setPacketList(packetList,ignore,2); - Fw::Time ts; - Fw::TlmBuffer buff; - - // first channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - // second channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - // third channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - // fifth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - // sixth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - // seventh channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->setTestTime(this->m_testTime); - // run scheduler port to send packets - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - ASSERT_FROM_PORT_HISTORY_SIZE(2); - ASSERT_from_PktSend_SIZE(2); - - // construct the packet buffers and make sure they are correct - - Fw::ComBuffer comBuff; - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(1,comBuff,static_cast(0)); - - } - - void Tester :: - sendPacketLevelsTest() - { - this->component.setPacketList(packetList,ignore,1); - Fw::Time ts; - Fw::TlmBuffer buff; - - // first channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - // second channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - // third channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - // fifth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - // sixth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - // seventh channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->setTestTime(this->m_testTime); - // run scheduler port to send packets - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - ASSERT_FROM_PORT_HISTORY_SIZE(2); - ASSERT_from_PktSend_SIZE(2); - - // construct the packet buffers and make sure they are correct - - Fw::ComBuffer comBuff; - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(1,comBuff,static_cast(0)); - - } - - void Tester :: - updatePacketsTest() - { - this->component.setPacketList(packetList,ignore,2); - Fw::Time ts; - Fw::TlmBuffer buff; - - Fw::ComBuffer comBuff; - - // Initially no packets should be pushed - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - // Should be no packets pushed - ASSERT_from_PktSend_SIZE(0); - - // first channel - ts.set(100,1000); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - this->m_testTime.add(1,0); - this->setTestTime(this->m_testTime); - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(2); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(1,comBuff,static_cast(0)); - - // second channel - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - this->m_testTime.add(1,0); - this->setTestTime(this->m_testTime); - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - // only one should be pushed - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - // only one should be pushed - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - //** Update all the packets again with new values - - // first channel - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1000))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(2); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(1,comBuff,static_cast(0)); - - // second channel - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(550))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(550))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(211))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(550))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(211))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(34441))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(34441))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(8649))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(34441))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8649))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(65))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(34441))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8649))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(65))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - } - - void Tester :: - ignoreTest() - { - this->component.setPacketList(packetList,ignore,2); - Fw::Time ts; - Fw::TlmBuffer buff; - - Fw::ComBuffer comBuff; - - // Initially no packets should be pushed - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - // Should be no packets pushed - ASSERT_from_PktSend_SIZE(0); - - // first channel - ts.set(100,1000); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - this->m_testTime.add(1,0); - this->setTestTime(this->m_testTime); - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(2); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(ts)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(0))); - - ASSERT_from_PktSend(1,comBuff,static_cast(0)); - - // ignored channel - - buff.resetSer(); - ts.add(1,0); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,25,ts,buff); - - this->m_testTime.add(1,0); - this->setTestTime(this->m_testTime); - this->clearFromPortHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - // no packets should be pushed - ASSERT_from_PktSend_SIZE(0); - - } - - void Tester :: - sendManualPacketTest() - { - this->component.setPacketList(packetList,ignore,2); - Fw::Time ts; - Fw::TlmBuffer buff; - - // first channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - // second channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - // third channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - // fifth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - // sixth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - // seventh channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->setTestTime(this->m_testTime); - // run scheduler port to send packets - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - ASSERT_FROM_PORT_HISTORY_SIZE(2); - ASSERT_from_PktSend_SIZE(2); - - // construct the packet buffers and make sure they are correct - - Fw::ComBuffer comBuff1; - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff1,static_cast(0)); - - Fw::ComBuffer comBuff2; - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff2.serialize(static_cast(15))); - - ASSERT_from_PktSend(1,comBuff2,static_cast(0)); - - // should not be any new packets - this->clearHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - ASSERT_FROM_PORT_HISTORY_SIZE(0); - ASSERT_from_PktSend_SIZE(0); - - // send command to manually send a packet - this->sendCmd_SEND_PKT(0,12,4); - this->component.doDispatch(); - ASSERT_EVENTS_SIZE(1); - ASSERT_EVENTS_PacketSent(0,4); - ASSERT_CMD_RESPONSE_SIZE(1); - ASSERT_CMD_RESPONSE(0,TlmPacketizerComponentBase::OPCODE_SEND_PKT,12,Fw::CmdResponse::OK); - // dispatch run call to send packet - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - ASSERT_from_PktSend(0,comBuff1,static_cast(0)); - - // another packet - this->clearHistory(); - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - ASSERT_FROM_PORT_HISTORY_SIZE(0); - ASSERT_from_PktSend_SIZE(0); - - // send command to manually send a packet - this->clearHistory(); - this->sendCmd_SEND_PKT(0,12,8); - this->component.doDispatch(); - ASSERT_EVENTS_SIZE(1); - ASSERT_EVENTS_PacketSent(0,8); - ASSERT_CMD_RESPONSE_SIZE(1); - ASSERT_CMD_RESPONSE(0,TlmPacketizerComponentBase::OPCODE_SEND_PKT,12,Fw::CmdResponse::OK); - // dispatch run call to send packet - this->invoke_to_Run(0,0); - this->component.doDispatch(); - ASSERT_from_PktSend_SIZE(1); - ASSERT_from_PktSend(0,comBuff2,static_cast(0)); - - // Try to send invalid packet - // send command to manually send a packet - this->clearHistory(); - this->sendCmd_SEND_PKT(0,12,20); - this->component.doDispatch(); - ASSERT_EVENTS_SIZE(1); - ASSERT_EVENTS_PacketNotFound(0,20); - ASSERT_CMD_RESPONSE_SIZE(1); - ASSERT_CMD_RESPONSE(0,TlmPacketizerComponentBase::OPCODE_SEND_PKT,12,Fw::CmdResponse::VALIDATION_ERROR); - - } - - void Tester :: - setPacketLevelTest() - { - this->component.setPacketList(packetList,ignore,0); - Fw::Time ts; - Fw::TlmBuffer buff; - - // first channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - // second channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - // third channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - // fifth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - // sixth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - // seventh channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->setTestTime(this->m_testTime); - // run scheduler port to send packets - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - // should be no packets sent since packet level is 0 - ASSERT_FROM_PORT_HISTORY_SIZE(0); - ASSERT_from_PktSend_SIZE(0); - - // send the command to select packet level 1 - this->clearHistory(); - this->sendCmd_SET_LEVEL(0,13,1); - this->component.doDispatch(); - ASSERT_EVENTS_SIZE(1); - ASSERT_EVENTS_LevelSet_SIZE(1); - ASSERT_EVENTS_LevelSet(0,1); - ASSERT_TLM_SIZE(1); - ASSERT_TLM_SendLevel_SIZE(1); - ASSERT_TLM_SendLevel(0,1); - - // send the packets - // first channel - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x20))); - this->invoke_to_TlmRecv(0,10,ts,buff); - - // second channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x15))); - this->invoke_to_TlmRecv(0,100,ts,buff); - - // third channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x14))); - this->invoke_to_TlmRecv(0,333,ts,buff); - - // fifth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x1000000))); - this->invoke_to_TlmRecv(0,13,ts,buff); - - // sixth channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x1010))); - this->invoke_to_TlmRecv(0,250,ts,buff); - - // seventh channel - buff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,buff.serialize(static_cast(0x15))); - this->invoke_to_TlmRecv(0,22,ts,buff); - - this->setTestTime(this->m_testTime); - // run scheduler port to send packets - this->invoke_to_Run(0,0); - this->component.doDispatch(); - - // should be one packet sent since packet level is 1 - ASSERT_FROM_PORT_HISTORY_SIZE(1); - ASSERT_from_PktSend_SIZE(1); - - // Should be packet 4 - - Fw::ComBuffer comBuff1; - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(0x20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(0x15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff1.serialize(static_cast(0x14))); - - ASSERT_from_PktSend(0,comBuff1,static_cast(0)); - -return; - - ASSERT_FROM_PORT_HISTORY_SIZE(2); - ASSERT_from_PktSend_SIZE(2); - - // construct the packet buffers and make sure they are correct - - Fw::ComBuffer comBuff; - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(4))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(14))); - - ASSERT_from_PktSend(0,comBuff,static_cast(0)); - - comBuff.resetSer(); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(8))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(this->m_testTime)); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(20))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1000000))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(1010))); - ASSERT_EQ(Fw::FW_SERIALIZE_OK,comBuff.serialize(static_cast(15))); - - ASSERT_from_PktSend(1,comBuff,static_cast(0)); - - } - - void Tester :: - nonPacketizedChannelTest() { - - this->component.setPacketList(packetList,ignore,2); - Fw::Time ts; - Fw::TlmBuffer buff; - - // start at non-used channel - for (NATIVE_UINT_TYPE channel = 1000; channel < 1000 + TLMPACKETIZER_MAX_MISSING_TLM_CHECK; channel++) { - this->clearEvents(); - this->invoke_to_TlmRecv(0,channel,ts,buff); - ASSERT_EVENTS_SIZE(1); - ASSERT_EVENTS_NoChan_SIZE(1); - ASSERT_EVENTS_NoChan(0,channel); - } - - // One more channel should not emit event - this->clearEvents(); - this->invoke_to_TlmRecv(0,1000+TLMPACKETIZER_MAX_MISSING_TLM_CHECK,ts,buff); - ASSERT_EVENTS_SIZE(0); - ASSERT_EVENTS_NoChan_SIZE(0); - - // sending the missing channels again should emit no events - - for (NATIVE_UINT_TYPE channel = 1000; channel < 1000 + TLMPACKETIZER_MAX_MISSING_TLM_CHECK; channel++) { - this->clearEvents(); - this->invoke_to_TlmRecv(0,channel,ts,buff); - ASSERT_EVENTS_SIZE(0); - ASSERT_EVENTS_NoChan_SIZE(0); - } - - } - - void Tester :: - pingTest() { - - this->component.setPacketList(packetList,ignore,2); - // ping component - this->clearFromPortHistory(); - this->invoke_to_pingIn(0,static_cast(0x1234)); - this->component.doDispatch(); - ASSERT_from_pingOut_SIZE(1); - ASSERT_from_pingOut(0,static_cast(0x1234)); - - } - - // ---------------------------------------------------------------------- - // Handlers for typed from ports - // ---------------------------------------------------------------------- - - void Tester :: - from_Time_handler( - const NATIVE_INT_TYPE portNum, - Fw::Time &time - ) - { - time = this->m_testTime; - this->m_timeSent = true; - } - - void Tester :: - from_PktSend_handler( - const NATIVE_INT_TYPE portNum, - Fw::ComBuffer &data, - U32 context - ) - { +void Tester ::sendPacketsTest() { + this->component.setPacketList(packetList, ignore, 2); + Fw::Time ts; + Fw::TlmBuffer buff; + + // first channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + // second channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + // third channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + // fifth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + // sixth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + // seventh channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->setTestTime(this->m_testTime); + // run scheduler port to send packets + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + ASSERT_FROM_PORT_HISTORY_SIZE(2); + ASSERT_from_PktSend_SIZE(2); + + // construct the packet buffers and make sure they are correct + + Fw::ComBuffer comBuff; + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(1, comBuff, static_cast(0)); +} + +void Tester ::sendPacketLevelsTest() { + this->component.setPacketList(packetList, ignore, 1); + Fw::Time ts; + Fw::TlmBuffer buff; + + // first channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + // second channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + // third channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + // fifth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + // sixth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + // seventh channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->setTestTime(this->m_testTime); + // run scheduler port to send packets + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + ASSERT_FROM_PORT_HISTORY_SIZE(2); + ASSERT_from_PktSend_SIZE(2); + + // construct the packet buffers and make sure they are correct + + Fw::ComBuffer comBuff; + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(1, comBuff, static_cast(0)); +} + +void Tester ::updatePacketsTest() { + this->component.setPacketList(packetList, ignore, 2); + Fw::Time ts; + Fw::TlmBuffer buff; + + Fw::ComBuffer comBuff; + + // Initially no packets should be pushed + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + // Should be no packets pushed + ASSERT_from_PktSend_SIZE(0); + + // first channel + ts.set(100, 1000); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + this->m_testTime.add(1, 0); + this->setTestTime(this->m_testTime); + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(2); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(1, comBuff, static_cast(0)); + + // second channel + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + this->m_testTime.add(1, 0); + this->setTestTime(this->m_testTime); + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + // only one should be pushed + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + // only one should be pushed + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + //** Update all the packets again with new values + + // first channel + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1000))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(2); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(1, comBuff, static_cast(0)); + + // second channel + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(550))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(550))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(211))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(550))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(211))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(34441))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(34441))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(8649))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(34441))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8649))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(65))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(34441))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8649))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(65))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); +} + +void Tester ::ignoreTest() { + this->component.setPacketList(packetList, ignore, 2); + Fw::Time ts; + Fw::TlmBuffer buff; + + Fw::ComBuffer comBuff; + + // Initially no packets should be pushed + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + // Should be no packets pushed + ASSERT_from_PktSend_SIZE(0); + + // first channel + ts.set(100, 1000); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + this->m_testTime.add(1, 0); + this->setTestTime(this->m_testTime); + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(2); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(ts)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(0))); + + ASSERT_from_PktSend(1, comBuff, static_cast(0)); + + // ignored channel + + buff.resetSer(); + ts.add(1, 0); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 25, ts, buff); + + this->m_testTime.add(1, 0); + this->setTestTime(this->m_testTime); + this->clearFromPortHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + // no packets should be pushed + ASSERT_from_PktSend_SIZE(0); +} + +void Tester ::sendManualPacketTest() { + this->component.setPacketList(packetList, ignore, 2); + Fw::Time ts; + Fw::TlmBuffer buff; + + // first channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + // second channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + // third channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + // fifth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + // sixth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + // seventh channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->setTestTime(this->m_testTime); + // run scheduler port to send packets + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + ASSERT_FROM_PORT_HISTORY_SIZE(2); + ASSERT_from_PktSend_SIZE(2); + + // construct the packet buffers and make sure they are correct + + Fw::ComBuffer comBuff1; + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff1.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff1, static_cast(0)); + + Fw::ComBuffer comBuff2; + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff2.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff2.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff2.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff2.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff2.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff2.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff2.serialize(static_cast(15))); + + ASSERT_from_PktSend(1, comBuff2, static_cast(0)); + + // should not be any new packets + this->clearHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + ASSERT_FROM_PORT_HISTORY_SIZE(0); + ASSERT_from_PktSend_SIZE(0); + + // send command to manually send a packet + this->sendCmd_SEND_PKT(0, 12, 4); + this->component.doDispatch(); + ASSERT_EVENTS_SIZE(1); + ASSERT_EVENTS_PacketSent(0, 4); + ASSERT_CMD_RESPONSE_SIZE(1); + ASSERT_CMD_RESPONSE(0, TlmPacketizerComponentBase::OPCODE_SEND_PKT, 12, Fw::CmdResponse::OK); + // dispatch run call to send packet + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + ASSERT_from_PktSend(0, comBuff1, static_cast(0)); + + // another packet + this->clearHistory(); + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + ASSERT_FROM_PORT_HISTORY_SIZE(0); + ASSERT_from_PktSend_SIZE(0); + + // send command to manually send a packet + this->clearHistory(); + this->sendCmd_SEND_PKT(0, 12, 8); + this->component.doDispatch(); + ASSERT_EVENTS_SIZE(1); + ASSERT_EVENTS_PacketSent(0, 8); + ASSERT_CMD_RESPONSE_SIZE(1); + ASSERT_CMD_RESPONSE(0, TlmPacketizerComponentBase::OPCODE_SEND_PKT, 12, Fw::CmdResponse::OK); + // dispatch run call to send packet + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + ASSERT_from_PktSend_SIZE(1); + ASSERT_from_PktSend(0, comBuff2, static_cast(0)); + + // Try to send invalid packet + // send command to manually send a packet + this->clearHistory(); + this->sendCmd_SEND_PKT(0, 12, 20); + this->component.doDispatch(); + ASSERT_EVENTS_SIZE(1); + ASSERT_EVENTS_PacketNotFound(0, 20); + ASSERT_CMD_RESPONSE_SIZE(1); + ASSERT_CMD_RESPONSE(0, TlmPacketizerComponentBase::OPCODE_SEND_PKT, 12, Fw::CmdResponse::VALIDATION_ERROR); +} + +void Tester ::setPacketLevelTest() { + this->component.setPacketList(packetList, ignore, 0); + Fw::Time ts; + Fw::TlmBuffer buff; + + // first channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + // second channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + // third channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + // fifth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + // sixth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + // seventh channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->setTestTime(this->m_testTime); + // run scheduler port to send packets + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + // should be no packets sent since packet level is 0 + ASSERT_FROM_PORT_HISTORY_SIZE(0); + ASSERT_from_PktSend_SIZE(0); + + // send the command to select packet level 1 + this->clearHistory(); + this->sendCmd_SET_LEVEL(0, 13, 1); + this->component.doDispatch(); + ASSERT_EVENTS_SIZE(1); + ASSERT_EVENTS_LevelSet_SIZE(1); + ASSERT_EVENTS_LevelSet(0, 1); + ASSERT_TLM_SIZE(1); + ASSERT_TLM_SendLevel_SIZE(1); + ASSERT_TLM_SendLevel(0, 1); + + // send the packets + // first channel + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x20))); + this->invoke_to_TlmRecv(0, 10, ts, buff); + + // second channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x15))); + this->invoke_to_TlmRecv(0, 100, ts, buff); + + // third channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x14))); + this->invoke_to_TlmRecv(0, 333, ts, buff); + + // fifth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x1000000))); + this->invoke_to_TlmRecv(0, 13, ts, buff); + + // sixth channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x1010))); + this->invoke_to_TlmRecv(0, 250, ts, buff); + + // seventh channel + buff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, buff.serialize(static_cast(0x15))); + this->invoke_to_TlmRecv(0, 22, ts, buff); + + this->setTestTime(this->m_testTime); + // run scheduler port to send packets + this->invoke_to_Run(0, 0); + this->component.doDispatch(); + + // should be one packet sent since packet level is 1 + ASSERT_FROM_PORT_HISTORY_SIZE(1); + ASSERT_from_PktSend_SIZE(1); + + // Should be packet 4 + + Fw::ComBuffer comBuff1; + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff1.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(0x20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(0x15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff1.serialize(static_cast(0x14))); + + ASSERT_from_PktSend(0, comBuff1, static_cast(0)); + + return; + + ASSERT_FROM_PORT_HISTORY_SIZE(2); + ASSERT_from_PktSend_SIZE(2); + + // construct the packet buffers and make sure they are correct + + Fw::ComBuffer comBuff; + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(4))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(14))); + + ASSERT_from_PktSend(0, comBuff, static_cast(0)); + + comBuff.resetSer(); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, + comBuff.serialize(static_cast(Fw::ComPacket::FW_PACKET_PACKETIZED_TLM))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(8))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(this->m_testTime)); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(20))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1000000))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(1010))); + ASSERT_EQ(Fw::FW_SERIALIZE_OK, comBuff.serialize(static_cast(15))); + + ASSERT_from_PktSend(1, comBuff, static_cast(0)); +} + +void Tester ::nonPacketizedChannelTest() { + this->component.setPacketList(packetList, ignore, 2); + Fw::Time ts; + Fw::TlmBuffer buff; + + // start at non-used channel + for (NATIVE_UINT_TYPE channel = 1000; channel < 1000 + TLMPACKETIZER_MAX_MISSING_TLM_CHECK; channel++) { + this->clearEvents(); + this->invoke_to_TlmRecv(0, channel, ts, buff); + ASSERT_EVENTS_SIZE(1); + ASSERT_EVENTS_NoChan_SIZE(1); + ASSERT_EVENTS_NoChan(0, channel); + } + + // One more channel should not emit event + this->clearEvents(); + this->invoke_to_TlmRecv(0, 1000 + TLMPACKETIZER_MAX_MISSING_TLM_CHECK, ts, buff); + ASSERT_EVENTS_SIZE(0); + ASSERT_EVENTS_NoChan_SIZE(0); + + // sending the missing channels again should emit no events + + for (NATIVE_UINT_TYPE channel = 1000; channel < 1000 + TLMPACKETIZER_MAX_MISSING_TLM_CHECK; channel++) { + this->clearEvents(); + this->invoke_to_TlmRecv(0, channel, ts, buff); + ASSERT_EVENTS_SIZE(0); + ASSERT_EVENTS_NoChan_SIZE(0); + } +} + +void Tester ::pingTest() { + this->component.setPacketList(packetList, ignore, 2); + // ping component + this->clearFromPortHistory(); + this->invoke_to_pingIn(0, static_cast(0x1234)); + this->component.doDispatch(); + ASSERT_from_pingOut_SIZE(1); + ASSERT_from_pingOut(0, static_cast(0x1234)); +} + +// ---------------------------------------------------------------------- +// Handlers for typed from ports +// ---------------------------------------------------------------------- + +void Tester ::from_Time_handler(const NATIVE_INT_TYPE portNum, Fw::Time& time) { + time = this->m_testTime; + this->m_timeSent = true; +} + +void Tester ::from_PktSend_handler(const NATIVE_INT_TYPE portNum, Fw::ComBuffer& data, U32 context) { this->pushFromPortEntry_PktSend(data, context); - } - - void Tester :: - from_pingOut_handler( - const NATIVE_INT_TYPE portNum, - U32 key - ) - { - this->pushFromPortEntry_pingOut(key); - } +} - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- +void Tester ::from_pingOut_handler(const NATIVE_INT_TYPE portNum, U32 key) { + this->pushFromPortEntry_pingOut(key); +} - void Tester :: - connectPorts() - { +// ---------------------------------------------------------------------- +// Helper methods +// ---------------------------------------------------------------------- +void Tester ::connectPorts() { // PktSend - this->component.set_PktSend_OutputPort( - 0, - this->get_from_PktSend(0) - ); + this->component.set_PktSend_OutputPort(0, this->get_from_PktSend(0)); // Run - this->connect_to_Run( - 0, - this->component.get_Run_InputPort(0) - ); + this->connect_to_Run(0, this->component.get_Run_InputPort(0)); // TlmRecv - this->connect_to_TlmRecv( - 0, - this->component.get_TlmRecv_InputPort(0) - ); + this->connect_to_TlmRecv(0, this->component.get_TlmRecv_InputPort(0)); // cmdIn - this->connect_to_cmdIn( - 0, - this->component.get_cmdIn_InputPort(0) - ); + this->connect_to_cmdIn(0, this->component.get_cmdIn_InputPort(0)); // cmdRegOut - this->component.set_cmdRegOut_OutputPort( - 0, - this->get_from_cmdRegOut(0) - ); + this->component.set_cmdRegOut_OutputPort(0, this->get_from_cmdRegOut(0)); // cmdResponseOut - this->component.set_cmdResponseOut_OutputPort( - 0, - this->get_from_cmdResponseOut(0) - ); + this->component.set_cmdResponseOut_OutputPort(0, this->get_from_cmdResponseOut(0)); // eventOut - this->component.set_eventOut_OutputPort( - 0, - this->get_from_eventOut(0) - ); + this->component.set_eventOut_OutputPort(0, this->get_from_eventOut(0)); // pingIn - this->connect_to_pingIn( - 0, - this->component.get_pingIn_InputPort(0) - ); + this->connect_to_pingIn(0, this->component.get_pingIn_InputPort(0)); // pingOut - this->component.set_pingOut_OutputPort( - 0, - this->get_from_pingOut(0) - ); + this->component.set_pingOut_OutputPort(0, this->get_from_pingOut(0)); // textEventOut - this->component.set_textEventOut_OutputPort( - 0, - this->get_from_textEventOut(0) - ); + this->component.set_textEventOut_OutputPort(0, this->get_from_textEventOut(0)); // timeGetOut - this->component.set_timeGetOut_OutputPort( - 0, - this->get_from_timeGetOut(0) - ); + this->component.set_timeGetOut_OutputPort(0, this->get_from_timeGetOut(0)); // tlmOut - this->component.set_tlmOut_OutputPort( - 0, - this->get_from_tlmOut(0) - ); - - } - - void Tester::textLogIn(const FwEventIdType id, //!< The event ID - Fw::Time& timeTag, //!< The time - const Fw::LogSeverity severity, //!< The severity - const Fw::TextLogString& text //!< The event string - ) { - TextLogEntry e = { id, timeTag, severity, text }; + this->component.set_tlmOut_OutputPort(0, this->get_from_tlmOut(0)); +} - printTextLogHistoryEntry(e, stdout); - } +void Tester::textLogIn(const FwEventIdType id, //!< The event ID + Fw::Time& timeTag, //!< The time + const Fw::LogSeverity severity, //!< The severity + const Fw::TextLogString& text //!< The event string +) { + TextLogEntry e = {id, timeTag, severity, text}; + printTextLogHistoryEntry(e, stdout); +} - void Tester :: - initComponents() - { +void Tester ::initComponents() { this->init(); - this->component.init( - QUEUE_DEPTH, INSTANCE - ); - } + this->component.init(QUEUE_DEPTH, INSTANCE); +} -} // end namespace Svc +} // end namespace Svc diff --git a/Svc/TlmPacketizer/test/ut/Tester.hpp b/Svc/TlmPacketizer/test/ut/Tester.hpp index 99652415c2..3f7d45b187 100644 --- a/Svc/TlmPacketizer/test/ut/Tester.hpp +++ b/Svc/TlmPacketizer/test/ut/Tester.hpp @@ -16,135 +16,121 @@ namespace Svc { - class Tester : - public TlmPacketizerGTestBase - { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - public: - - //! Construct object Tester - //! - Tester(void); - - //! Destroy object Tester - //! - ~Tester(void); - - public: - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - //! Initialization test - //! - void initTest(void); - - //! push telemetry test - //! - void pushTlmTest(void); - - //! send packets test - //! - void sendPacketsTest(void); - - //! send packets with levels test - //! - void sendPacketLevelsTest(void); - - //! update packets test - //! - void updatePacketsTest(void); - - //! non-packetized channel test - //! - void nonPacketizedChannelTest(void); - - //! ping test - //! - void pingTest(void); - - //! ignore test - //! - void ignoreTest(void); - - //! manually send packet test - //! - void sendManualPacketTest(void); - - //! set packet level test - //! - void setPacketLevelTest(void); - - private: - - // ---------------------------------------------------------------------- - // Handlers for typed from ports - // ---------------------------------------------------------------------- - - //! Handler for from_Time - //! - void from_Time_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Time &time /*!< The U32 cmd argument*/ - ); - - //! Handler for from_PktSend - //! - void from_PktSend_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::ComBuffer &data, /*!< Buffer containing packet data*/ - U32 context /*!< Call context value; meaning chosen by user*/ - ); - - //! Handler for from_pingOut - //! - void from_pingOut_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U32 key /*!< Value to return to pinger*/ - ); - - virtual void textLogIn( - const FwEventIdType id, /*!< The event ID*/ - Fw::Time& timeTag, /*!< The time*/ - const Fw::LogSeverity severity, /*!< The severity*/ - const Fw::TextLogString& text /*!< The event string*/ - ); - - - private: - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - //! Connect ports - //! - void connectPorts(void); - - //! Initialize components - //! - void initComponents(void); - - private: - - // ---------------------------------------------------------------------- - // Variables - // ---------------------------------------------------------------------- - - //! The component under test - //! - TlmPacketizer component; - - Fw::Time m_testTime; //!< store test time for packets - bool m_timeSent; //!< flag when time was sent - - }; - -} // end namespace Svc +class Tester : public TlmPacketizerGTestBase { + // ---------------------------------------------------------------------- + // Construction and destruction + // ---------------------------------------------------------------------- + + public: + //! Construct object Tester + //! + Tester(void); + + //! Destroy object Tester + //! + ~Tester(void); + + public: + // ---------------------------------------------------------------------- + // Tests + // ---------------------------------------------------------------------- + + //! Initialization test + //! + void initTest(void); + + //! push telemetry test + //! + void pushTlmTest(void); + + //! send packets test + //! + void sendPacketsTest(void); + + //! send packets with levels test + //! + void sendPacketLevelsTest(void); + + //! update packets test + //! + void updatePacketsTest(void); + + //! non-packetized channel test + //! + void nonPacketizedChannelTest(void); + + //! ping test + //! + void pingTest(void); + + //! ignore test + //! + void ignoreTest(void); + + //! manually send packet test + //! + void sendManualPacketTest(void); + + //! set packet level test + //! + void setPacketLevelTest(void); + + private: + // ---------------------------------------------------------------------- + // Handlers for typed from ports + // ---------------------------------------------------------------------- + + //! Handler for from_Time + //! + void from_Time_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Time& time /*!< The U32 cmd argument*/ + ); + + //! Handler for from_PktSend + //! + void from_PktSend_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::ComBuffer& data, /*!< Buffer containing packet data*/ + U32 context /*!< Call context value; meaning chosen by user*/ + ); + + //! Handler for from_pingOut + //! + void from_pingOut_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + U32 key /*!< Value to return to pinger*/ + ); + + virtual void textLogIn(const FwEventIdType id, /*!< The event ID*/ + Fw::Time& timeTag, /*!< The time*/ + const Fw::LogSeverity severity, /*!< The severity*/ + const Fw::TextLogString& text /*!< The event string*/ + ); + + private: + // ---------------------------------------------------------------------- + // Helper methods + // ---------------------------------------------------------------------- + + //! Connect ports + //! + void connectPorts(void); + + //! Initialize components + //! + void initComponents(void); + + private: + // ---------------------------------------------------------------------- + // Variables + // ---------------------------------------------------------------------- + + //! The component under test + //! + TlmPacketizer component; + + Fw::Time m_testTime; //!< store test time for packets + bool m_timeSent; //!< flag when time was sent +}; + +} // end namespace Svc #endif diff --git a/Svc/TlmPacketizer/test/ut/main.cpp b/Svc/TlmPacketizer/test/ut/main.cpp index 3cd590702d..678a586ee0 100644 --- a/Svc/TlmPacketizer/test/ut/main.cpp +++ b/Svc/TlmPacketizer/test/ut/main.cpp @@ -3,64 +3,55 @@ // ALL RIGHTS RESERVED. United States Government Sponsorship // acknowledged. - -#include "Tester.hpp" #include #include +#include "Tester.hpp" -TEST(TestNominal,Initialization) { - - TEST_CASE(100.1.1,"Initialization"); +TEST(TestNominal, Initialization) { + TEST_CASE(100.1.1, "Initialization"); Svc::Tester tester; tester.initTest(); } - -TEST(TestNominal,PushTlm) { - - TEST_CASE(100.1.2,"Push Telemetry"); +TEST(TestNominal, PushTlm) { + TEST_CASE(100.1.2, "Push Telemetry"); Svc::Tester tester; tester.pushTlmTest(); } -TEST(TestNominal,SendPackets) { - - TEST_CASE(100.1.2,"Send Packets"); +TEST(TestNominal, SendPackets) { + TEST_CASE(100.1.2, "Send Packets"); Svc::Tester tester; tester.sendPacketsTest(); } -//TEST(TestNominal,SendPacketLevels) { +// TEST(TestNominal,SendPacketLevels) { // -// TEST_CASE(100.1.3,"Send Packets with levels"); -// Svc::Tester tester; -// tester.sendPacketLevelsTest(); -//} - -TEST(TestNominal,UpdatePacketsTest) { +// TEST_CASE(100.1.3,"Send Packets with levels"); +// Svc::Tester tester; +// tester.sendPacketLevelsTest(); +// } - TEST_CASE(100.1.4,"Update Packets"); +TEST(TestNominal, UpdatePacketsTest) { + TEST_CASE(100.1.4, "Update Packets"); Svc::Tester tester; tester.updatePacketsTest(); } -TEST(TestNominal,PingTest) { - - TEST_CASE(100.1.5,"Ping"); +TEST(TestNominal, PingTest) { + TEST_CASE(100.1.5, "Ping"); Svc::Tester tester; tester.pingTest(); } -TEST(TestNominal,IgnoredChannelTest) { - - TEST_CASE(100.1.6,"Ignored Channels"); +TEST(TestNominal, IgnoredChannelTest) { + TEST_CASE(100.1.6, "Ignored Channels"); Svc::Tester tester; tester.ignoreTest(); } -TEST(TestNominal,SendPacketTest) { - - TEST_CASE(100.1.7,"Manually sent packets"); +TEST(TestNominal, SendPacketTest) { + TEST_CASE(100.1.7, "Manually sent packets"); Svc::Tester tester; tester.sendManualPacketTest(); } @@ -72,9 +63,8 @@ TEST(TestNominal,SetPacketLevelTest) { tester.setPacketLevelTest(); } #endif -TEST(TestOffNominal,NonPacketizedChannelTest) { - - TEST_CASE(100.2.1,"Non-packetized Channels"); +TEST(TestOffNominal, NonPacketizedChannelTest) { + TEST_CASE(100.2.1, "Non-packetized Channels"); Svc::Tester tester; tester.nonPacketizedChannelTest(); } diff --git a/cmake/FPrime.cmake b/cmake/FPrime.cmake index bb143ed27b..78fce76782 100644 --- a/cmake/FPrime.cmake +++ b/cmake/FPrime.cmake @@ -69,6 +69,7 @@ register_fprime_target(target/fpp_locs) register_fprime_target(target/build) register_fprime_build_autocoder(autocoder/fpp) register_fprime_build_autocoder(autocoder/ai_xml) +register_fprime_build_autocoder(autocoder/packets) register_fprime_target(target/noop) register_fprime_target(target/version) register_fprime_target(target/dict) diff --git a/cmake/autocoder/packets.cmake b/cmake/autocoder/packets.cmake new file mode 100644 index 0000000000..f2d5157b86 --- /dev/null +++ b/cmake/autocoder/packets.cmake @@ -0,0 +1,63 @@ +#### +# autocoder/packets.cmake +# +# Packets autocoder. +##### +include(utilities) +include(autocoder/helpers) +include(autocoder/ai-shared) + +set(PACKETS_AUTOCODER_SCRIPT "${FPRIME_FRAMEWORK_PATH}/Autocoders/Python/bin/tlm_packet_gen.py") + +autocoder_setup_for_individual_sources() +#### +# `packets_is_supported`: +# +# Required function, processes Ai.xml files. +# `AC_INPUT_FILE` potential input to the autocoder +# ...: any number of arguments representing a list of previously generated files +#### +function(packets_is_supported AC_INPUT_FILE) + autocoder_support_by_suffix("Packets.xml" "${AC_INPUT_FILE}" TRUE) +endfunction (packets_is_supported) + +#### +# `determine_topology_files`: +# +# Get topology determined from packet file. +#### +function(determine_topology_files AC_INPUT_FILE) + file(READ "${AC_INPUT_FILE}" FILE_CONTENTS) + string(REGEX REPLACE ".*([^>]*).*" "\\1" TOPOLOGY_FILE "${FILE_CONTENTS}") + # This will work as long as the topology ai file is not part of the fprime core "library" code + set(FULL_TOPOLOGY_FILE "${CMAKE_BINARY_DIR}/${TOPOLOGY_FILE}" PARENT_SCOPE) +endfunction(determine_topology_files) + +#### +# `packets_setup_autocode`: +# +# Required function, sets up a custom command to produce Ac.hpp and Ac.cpp files. +#### +function(packets_setup_autocode AC_INPUT_FILE) + determine_topology_files("${AC_INPUT_FILE}") + get_filename_component(AC_INPUT_FILE_NO_PATH "${AC_INPUT_FILE}" NAME) + + string(REPLACE ";" ":" FPRIME_BUILD_LOCATIONS_SEP "${FPRIME_BUILD_LOCATIONS}") + string(REPLACE "Packets.xml" "PacketsAc.cpp" CPP_FILE "${AC_INPUT_FILE_NO_PATH}") + string(REPLACE "Packets.xml" "PacketsAc.hpp" HPP_FILE "${AC_INPUT_FILE_NO_PATH}") + + set(GENERATED_FILES + "${CMAKE_CURRENT_BINARY_DIR}/${CPP_FILE}" + "${CMAKE_CURRENT_BINARY_DIR}/${HPP_FILE}" + ) + add_custom_command( + OUTPUT ${GENERATED_FILES} + COMMAND + PYTHONPATH=${PYTHON_AUTOCODER_DIR}/src:${PYTHON_AUTOCODER_DIR}/utils + BUILD_ROOT=${FPRIME_BUILD_LOCATIONS_SEP}:${CMAKE_BINARY_DIR}:${CMAKE_BINARY_DIR}/F-Prime + "${PYTHON}" "${PACKETS_AUTOCODER_SCRIPT}" "${AC_INPUT_FILE}" + DEPENDS "${AC_INPUT_FILE}" "${FULL_TOPOLOGY_FILE}" + ) + set(AUTOCODER_GENERATED "${GENERATED_FILES}" PARENT_SCOPE) + set(AUTOCODER_DEPENDENCIES "" PARENT_SCOPE) +endfunction(packets_setup_autocode) diff --git a/cmake/utilities.cmake b/cmake/utilities.cmake index e046c2cbad..5dcff4e9f3 100644 --- a/cmake/utilities.cmake +++ b/cmake/utilities.cmake @@ -385,6 +385,22 @@ function (read_from_lines CONTENT) endforeach() endfunction() +#### +# Function `full_path_from_build_relative_path`: +# +# Creates a full path from the shortened build-relative path. +# -**SHORT_PATH:** build relative path +# Return: full path from relative path +#### +function(full_path_from_build_relative_path SHORT_PATH OUTPUT_VARIABLE) + foreach(FPRIME_LOCATION IN LISTS FPRIME_BUILD_LOCATIONS) + if (EXISTS "${FPRIME_LOCATION}/${SHORT_PATH}") + set("${OUTPUT_VARIABLE}" "${FPRIME_LOCATION}/${SHORT_PATH}" PARENT_SCOPE) + return() + endif() + endforeach() + set("${OUTPUT_VARIABLE}" "" PARENT_SCOPE) +endfunction(full_path_from_build_relative_path) #### # Function `get_nearest_build_root`: diff --git a/config/TlmPacketizerCfg.hpp b/config/TlmPacketizerCfg.hpp new file mode 100644 index 0000000000..2b514374a9 --- /dev/null +++ b/config/TlmPacketizerCfg.hpp @@ -0,0 +1,43 @@ +/* + * TlmPacketizerComponentImplCfg.hpp + * + * Created on: Dec 10, 2017 + * Author: tim + */ + +// \copyright +// Copyright 2009-2015, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. + +#ifndef SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ +#define SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ + +#include + +namespace Svc { +static const NATIVE_UINT_TYPE MAX_PACKETIZER_PACKETS = 200; +static const NATIVE_UINT_TYPE TLMPACKETIZER_NUM_TLM_HASH_SLOTS = + 15; // !< Number of slots in the hash table. + // Works best when set to about twice the number of components producing telemetry +static const NATIVE_UINT_TYPE TLMPACKETIZER_HASH_MOD_VALUE = + 99; // !< The modulo value of the hashing function. + // Should be set to a little below the ID gaps to spread the entries around + +static const NATIVE_UINT_TYPE TLMPACKETIZER_HASH_BUCKETS = + 1000; // !< Buckets assignable to a hash slot. + // Buckets must be >= number of telemetry channels in system +static const NATIVE_UINT_TYPE TLMPACKETIZER_MAX_MISSING_TLM_CHECK = + 25; // !< Maximum number of missing telemetry channel checks + +// packet update mode +enum PacketUpdateMode { + PACKET_UPDATE_ALWAYS, // Always send packets, even if no changes to channel data + PACKET_UPDATE_ON_CHANGE, // Only send packets if any of the channels updates + PACKET_UPDATE_AFTER_FIRST_CHANGE, // Always send packets, but only after first channel has been updated +}; + +static const PacketUpdateMode PACKET_UPDATE_MODE = PACKET_UPDATE_ON_CHANGE; +} // namespace Svc + +#endif /* SVC_TLMPACKETIZER_TLMPACKETIZERCOMPONENTIMPLCFG_HPP_ */ diff --git a/requirements.txt b/requirements.txt index f9c8a745de..3fbd80fd7c 100644 --- a/requirements.txt +++ b/requirements.txt @@ -14,8 +14,8 @@ Flask==1.1.4 Flask-Compress==1.12 Flask-RESTful==0.3.9 fprime-fpp==1.1.0 -fprime-gds==3.1.4 -fprime-tools==3.1.1 +fprime-gds==3.1.5a1 +fprime-tools==3.1.2a1 gcovr==5.1 idna==3.3 importlib-metadata==4.11.4 From 9b7c08bc7a887f4a26f86681f8d5217a96fbf1ee Mon Sep 17 00:00:00 2001 From: Thomas Boyer Chammard <49786685+thomas-bc@users.noreply.github.com> Date: Tue, 29 Nov 2022 15:13:31 -0800 Subject: [PATCH 102/169] Update sanitizer.cmake logging mode (#1781) * Update logging mode * sanitizers doc update * spelling --- cmake/sanitizers.cmake | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/cmake/sanitizers.cmake b/cmake/sanitizers.cmake index 2bc47e8a8f..4f826fedd6 100644 --- a/cmake/sanitizers.cmake +++ b/cmake/sanitizers.cmake @@ -4,9 +4,14 @@ # Enables sanitizers in the build settings when requested by the user with -DENABLE_SANITIZER_<...>=ON. # # Sanitizers, by default, output their logs to stderr. To redirect the output to files instead, use the -# `log_path` option from the sanitizer _OPTION environment variable at runtime. For example, with UBSAN: -# >>> UBSAN_OPTIONS="log_path=/path/to/output_dir" fprime-util check (or a single executable file). -# If a relative path is specified, this will be relative to the test main function's file **in the build cache**. +# `log_path` option from the sanitizer _OPTIONS environment variable at runtime. For example, with UBSAN: +# >>> UBSAN_OPTIONS="log_path=/path/to/output_dir/file_prefix" fprime-util check +# or +# >>> UBSAN_OPTIONS="log_path=/path/to/output_dir/file_prefix" ./path/to/executable +# +# Note: is a prefix to which the sanitizer will add a unique ID to generate a unique filename. +# If a relative path is specified, this will be relative to the component's folder **in the build cache** +# if using fprime-util check, OR relative to the current directory if running a single executable. #### if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES ".*Clang") @@ -22,7 +27,7 @@ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES ".*Clan if(ENABLE_SANITIZER_LEAK) if(APPLE) - message(WARNING "Leak sanitizer not supported on macOS.") + message(STATUS "[WARNING] Leak sanitizer is not supported on macOS") else() list(APPEND SANITIZERS "leak") endif() @@ -30,7 +35,7 @@ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES ".*Clan if(ENABLE_SANITIZER_THREAD) if("address" IN_LIST SANITIZERS OR "leak" IN_LIST SANITIZERS) - message(WARNING "Thread sanitizer does not work with Address or Leak sanitizer enabled") + message(STATUS "[WARNING] Thread sanitizer does not work with Address or Leak sanitizer enabled") else() list(APPEND SANITIZERS "thread") endif() From 547197194acff1f99d86e6e441fa9b5b5bd2d60b Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 1 Dec 2022 13:24:49 -0800 Subject: [PATCH 103/169] Corrects namespace of Tester in TestMain.cpp. Fixes #1725 (#1787) --- .../src/fprime_ac/generators/templates/test/test_main.tmpl | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test/test_main.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test/test_main.tmpl index 2a31e9affe..00cfb25a6a 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test/test_main.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test/test_main.tmpl @@ -6,7 +6,11 @@ #for $test_name, $method_name in $test_cases TEST(Nominal, ${test_name}) { - Ref::Tester tester; + #if $namespace_list != None + #echo "::".join($namespace_list)#::Tester tester; + #else + Tester tester; + #end if tester.${method_name}(); } #end for From 14091f63b9ff9d71ccc94eae65788b381a253b03 Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 5 Dec 2022 09:33:48 -0800 Subject: [PATCH 104/169] fixing cppcheck detected issues (#1788) * fixing cppcheck detected issues * fixing spi casts to use the header type --- Drv/Ip/SocketReadTask.cpp | 2 +- Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp | 10 +++++----- Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp | 4 ++-- Os/Posix/TaskId.cpp | 3 +-- Svc/ComLogger/ComLogger.cpp | 2 +- Svc/Health/HealthComponentImpl.cpp | 2 +- Svc/Health/HealthComponentImpl.hpp | 2 +- Svc/SystemResources/SystemResources.cpp | 8 ++++---- 8 files changed, 16 insertions(+), 17 deletions(-) diff --git a/Drv/Ip/SocketReadTask.cpp b/Drv/Ip/SocketReadTask.cpp index 2124ccd92a..6c82289350 100644 --- a/Drv/Ip/SocketReadTask.cpp +++ b/Drv/Ip/SocketReadTask.cpp @@ -19,7 +19,7 @@ namespace Drv { -SocketReadTask::SocketReadTask() : m_stop(false) {} +SocketReadTask::SocketReadTask() : m_reconnect(false), m_stop(false) {} SocketReadTask::~SocketReadTask() {} diff --git a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp index 4c3d62beed..8f1dbab133 100644 --- a/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp +++ b/Drv/LinuxGpioDriver/LinuxGpioDriverComponentImpl.cpp @@ -49,7 +49,7 @@ namespace Drv { } // TODO check value of len - len = snprintf(buf, sizeof(buf), "%d", gpio); + len = snprintf(buf, sizeof(buf), "%u", gpio); if(write(fd, buf, len) != len) { (void) close(fd); DEBUG_PRINT("gpio/export error!\n"); @@ -80,7 +80,7 @@ namespace Drv { } // TODO check value of len - len = snprintf(buf, sizeof(buf), "%d", gpio); + len = snprintf(buf, sizeof(buf), "%u", gpio); if(write(fd, buf, len) != len) { (void) close(fd); DEBUG_PRINT("gpio/unexport error!\n"); @@ -104,7 +104,7 @@ namespace Drv { int fd, len; char buf[MAX_BUF]; - len = snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%d/direction", gpio); + len = snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%u/direction", gpio); FW_ASSERT(len > 0, len); fd = open(buf, O_WRONLY); @@ -190,7 +190,7 @@ namespace Drv { FW_ASSERT(edge != nullptr); // TODO check that edge has correct values of "none", "rising", or "falling" - len = snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%d/edge", gpio); + len = snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%u/edge", gpio); FW_ASSERT(len > 0, len); fd = open(buf, O_WRONLY); @@ -219,7 +219,7 @@ namespace Drv { int fd, len; char buf[MAX_BUF]; - len = snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%d/value", gpio); + len = snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%u/value", gpio); FW_ASSERT(len > 0, len); fd = open(buf, O_RDWR | O_NONBLOCK ); diff --git a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp index 0090095d5e..dd92ae76be 100644 --- a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp +++ b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp @@ -46,8 +46,8 @@ namespace Drv { spi_ioc_transfer tr; // Zero for unused fields: memset(&tr, 0, sizeof(tr)); - tr.tx_buf = reinterpret_cast(writeBuffer.getData()); - tr.rx_buf = reinterpret_cast(readBuffer.getData()); + tr.tx_buf = reinterpret_cast<__u64>(writeBuffer.getData()); + tr.rx_buf = reinterpret_cast<__u64>(readBuffer.getData()); tr.len = writeBuffer.getSize(); /* .speed_hz = 0, diff --git a/Os/Posix/TaskId.cpp b/Os/Posix/TaskId.cpp index 33274dfaf5..ad007c224e 100644 --- a/Os/Posix/TaskId.cpp +++ b/Os/Posix/TaskId.cpp @@ -13,9 +13,8 @@ extern "C" { namespace Os { - TaskId::TaskId() + TaskId::TaskId() : id(pthread_self()) { - id = pthread_self(); } TaskId::~TaskId() { diff --git a/Svc/ComLogger/ComLogger.cpp b/Svc/ComLogger/ComLogger.cpp index 2d10362a0d..af1d27f621 100644 --- a/Svc/ComLogger/ComLogger.cpp +++ b/Svc/ComLogger/ComLogger.cpp @@ -31,7 +31,7 @@ namespace Svc { FW_ASSERT(maxFileSize > sizeof(U16), maxFileSize); // must be a positive integer greater than buffer length size } else { - FW_ASSERT(maxFileSize > sizeof(0), maxFileSize); // must be a positive integer + FW_ASSERT(maxFileSize > 0, maxFileSize); // must be a positive integer } FW_ASSERT(Fw::StringUtils::string_length(incomingFilePrefix, sizeof(this->filePrefix)) < sizeof(this->filePrefix), Fw::StringUtils::string_length(incomingFilePrefix, sizeof(this->filePrefix)), sizeof(this->filePrefix)); // ensure that file prefix is not too big diff --git a/Svc/Health/HealthComponentImpl.cpp b/Svc/Health/HealthComponentImpl.cpp index d60338a598..adc9934f0a 100644 --- a/Svc/Health/HealthComponentImpl.cpp +++ b/Svc/Health/HealthComponentImpl.cpp @@ -200,7 +200,7 @@ namespace Svc { this->cmdResponse_out(opCode,cmdSeq,Fw::CmdResponse::OK); } - NATIVE_INT_TYPE HealthImpl::findEntry(Fw::CmdStringArg entry) { + NATIVE_INT_TYPE HealthImpl::findEntry(const Fw::CmdStringArg& entry) { // walk through entries for (NATIVE_UINT_TYPE tableEntry = 0; tableEntry < NUM_PINGSEND_OUTPUT_PORTS; tableEntry++) { diff --git a/Svc/Health/HealthComponentImpl.hpp b/Svc/Health/HealthComponentImpl.hpp index f8f94c7ae7..7ecbd20f01 100644 --- a/Svc/Health/HealthComponentImpl.hpp +++ b/Svc/Health/HealthComponentImpl.hpp @@ -142,7 +142,7 @@ namespace Svc { Fw::Enabled::t enabled; //!< if current ping result is checked } m_pingTrackerEntries[NUM_PINGSEND_OUTPUT_PORTS]; - NATIVE_INT_TYPE findEntry(Fw::CmdStringArg entry); + NATIVE_INT_TYPE findEntry(const Fw::CmdStringArg& entry); //! Private member data U32 m_numPingEntries; //!< stores number of entries passed to constructor diff --git a/Svc/SystemResources/SystemResources.cpp b/Svc/SystemResources/SystemResources.cpp index c187348a10..7f476b1dc1 100644 --- a/Svc/SystemResources/SystemResources.cpp +++ b/Svc/SystemResources/SystemResources.cpp @@ -39,10 +39,6 @@ SystemResources ::SystemResources(const char* const compName) } m_cpu_count = (m_cpu_count >= CPU_COUNT) ? CPU_COUNT : m_cpu_count; -} - -void SystemResources ::init(const NATIVE_INT_TYPE instance) { - SystemResourcesComponentBase::init(instance); m_cpu_tlm_functions[0] = &Svc::SystemResources::tlmWrite_CPU_00; m_cpu_tlm_functions[1] = &Svc::SystemResources::tlmWrite_CPU_01; @@ -62,6 +58,10 @@ void SystemResources ::init(const NATIVE_INT_TYPE instance) { m_cpu_tlm_functions[15] = &Svc::SystemResources::tlmWrite_CPU_15; } +void SystemResources ::init(const NATIVE_INT_TYPE instance) { + SystemResourcesComponentBase::init(instance); +} + SystemResources ::~SystemResources() {} // ---------------------------------------------------------------------- From fbfc9ad56354ce7185a0e813392f76fe7a45d42f Mon Sep 17 00:00:00 2001 From: Josh Soref <2119212+jsoref@users.noreply.github.com> Date: Tue, 6 Dec 2022 13:19:16 -0500 Subject: [PATCH 105/169] Update check-spelling to v0.0.21 (#1790) * spelling: async Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: basic Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: file for Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: files Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: generic Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: github.com/nasa/fprime Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: header Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: into Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: multiline Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: sync Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * spelling: workaround Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> * Update check-spelling to v0.0.21 Signed-off-by: Josh Soref <2119212+jsoref@users.noreply.github.com> Co-authored-by: M Starch --- .github/actions/spelling/README.md | 1 + .github/actions/spelling/advice.md | 2 +- .github/actions/spelling/allow.txt | 6 + .github/actions/spelling/candidate.patterns | 527 ++++++++++++++++++ .github/actions/spelling/excludes.txt | 34 +- .github/actions/spelling/expect.txt | 21 +- .../actions/spelling/line_forbidden.patterns | 27 +- .github/actions/spelling/patterns.txt | 65 ++- .github/workflows/spelling.yml | 54 +- .../schema/default/interface_schema.rng | 2 +- .../default/internal_interface_schema.rng | 2 +- Autocoders/Python/src/fprime_ac/models/Arg.py | 2 +- .../fprime_ac/parsers/XmlComponentParser.py | 4 +- .../src/fprime_ac/parsers/XmlPortsParser.py | 2 +- Autocoders/Python/templates/CMakeLists.txt | 2 +- CFDP/Checksum/CMakeLists.txt | 2 +- CFDP/Checksum/GTest/CMakeLists.txt | 2 +- Drv/BlockDriver/CMakeLists.txt | 2 +- Drv/ByteStreamDriverModel/CMakeLists.txt | 2 +- Drv/DataTypes/CMakeLists.txt | 2 +- Drv/GpioDriverPorts/CMakeLists.txt | 2 +- Drv/I2cDriverPorts/CMakeLists.txt | 2 +- Drv/Ip/CMakeLists.txt | 2 +- Drv/LinuxGpioDriver/CMakeLists.txt | 2 +- Drv/LinuxI2cDriver/CMakeLists.txt | 2 +- Drv/LinuxSpiDriver/CMakeLists.txt | 2 +- Drv/LinuxUartDriver/CMakeLists.txt | 2 +- Drv/SpiDriverPorts/CMakeLists.txt | 2 +- Drv/TcpClient/CMakeLists.txt | 2 +- Drv/TcpServer/CMakeLists.txt | 2 +- Drv/Udp/CMakeLists.txt | 2 +- Fw/Buffer/CMakeLists.txt | 2 +- Fw/Cfg/CMakeLists.txt | 2 +- Fw/Cmd/CMakeLists.txt | 2 +- Fw/Com/CMakeLists.txt | 2 +- Fw/Comp/CMakeLists.txt | 2 +- Fw/FilePacket/CMakeLists.txt | 2 +- Fw/FilePacket/GTest/CMakeLists.txt | 2 +- Fw/Log/CMakeLists.txt | 2 +- Fw/Logger/CMakeLists.txt | 2 +- Fw/Logger/test/ut/Main.cpp | 6 +- Fw/Obj/CMakeLists.txt | 2 +- Fw/Port/CMakeLists.txt | 2 +- Fw/Prm/CMakeLists.txt | 2 +- Fw/SerializableFile/CMakeLists.txt | 2 +- .../test/TestSerializable/CMakeLists.txt | 2 +- Fw/Test/CMakeLists.txt | 2 +- Fw/Time/CMakeLists.txt | 2 +- Fw/Tlm/CMakeLists.txt | 2 +- Fw/Types/CMakeLists.txt | 2 +- Fw/Types/GTest/CMakeLists.txt | 2 +- Os/Baremetal/TaskRunner/BareTaskHandle.hpp | 2 +- Os/Baremetal/TaskRunner/CMakeLists.txt | 2 +- Os/CMakeLists.txt | 2 +- Os/Stubs/CMakeLists.txt | 2 +- RPI/RpiDemo/CMakeLists.txt | 2 +- RPI/Top/CMakeLists.txt | 2 +- Ref/PingReceiver/CMakeLists.txt | 2 +- Ref/RecvBuffApp/CMakeLists.txt | 2 +- Ref/SendBuffApp/CMakeLists.txt | 2 +- Ref/SignalGen/CMakeLists.txt | 2 +- Ref/Top/CMakeLists.txt | 2 +- Svc/ActiveLogger/CMakeLists.txt | 2 +- Svc/ActiveRateGroup/CMakeLists.txt | 2 +- Svc/ActiveTextLogger/CMakeLists.txt | 2 +- Svc/AssertFatalAdapter/CMakeLists.txt | 2 +- Svc/BufferLogger/CMakeLists.txt | 2 +- Svc/BufferManager/CMakeLists.txt | 2 +- Svc/CmdDispatcher/CMakeLists.txt | 2 +- Svc/CmdSequencer/CMakeLists.txt | 2 +- Svc/CmdSequencer/docs/sdd.md | 2 +- .../test/ut/SequenceFiles/File.hpp | 2 +- Svc/ComLogger/CMakeLists.txt | 2 +- Svc/ComSplitter/CMakeLists.txt | 2 +- Svc/Cycle/CMakeLists.txt | 2 +- Svc/Deframer/CMakeLists.txt | 2 +- Svc/Fatal/CMakeLists.txt | 2 +- Svc/FatalHandler/CMakeLists.txt | 2 +- Svc/FileDownlink/CMakeLists.txt | 2 +- Svc/FileDownlinkPorts/CMakeLists.txt | 2 +- Svc/FileManager/CMakeLists.txt | 2 +- Svc/FileUplink/CMakeLists.txt | 2 +- Svc/Framer/CMakeLists.txt | 2 +- Svc/FramingProtocol/CMakeLists.txt | 2 +- Svc/GenericHub/CMakeLists.txt | 2 +- ...leAppAi.xml => GenericHubExampleAppAi.xml} | 0 ...aterAppAi.xml => GenericRepeaterAppAi.xml} | 0 Svc/GroundInterface/CMakeLists.txt | 2 +- Svc/Health/CMakeLists.txt | 2 +- Svc/LinuxTime/CMakeLists.txt | 2 +- Svc/LinuxTimer/CMakeLists.txt | 2 +- Svc/PassiveConsoleTextLogger/CMakeLists.txt | 2 +- Svc/Ping/CMakeLists.txt | 2 +- Svc/PolyDb/CMakeLists.txt | 2 +- Svc/PolyIf/CMakeLists.txt | 2 +- Svc/PrmDb/CMakeLists.txt | 2 +- Svc/RateGroupDriver/CMakeLists.txt | 2 +- Svc/Sched/CMakeLists.txt | 2 +- Svc/Seq/CMakeLists.txt | 2 +- Svc/StaticMemory/CMakeLists.txt | 2 +- Svc/SystemResources/CMakeLists.txt | 2 +- Svc/Time/CMakeLists.txt | 2 +- Svc/TlmChan/CMakeLists.txt | 2 +- Svc/TlmPacketizer/CMakeLists.txt | 2 +- Svc/WatchDog/CMakeLists.txt | 2 +- Utils/Hash/CMakeLists.txt | 2 +- Utils/Types/CMakeLists.txt | 2 +- docs/UsersGuide/dev/testAPI/user_guide.md | 30 +- 108 files changed, 830 insertions(+), 135 deletions(-) create mode 100644 .github/actions/spelling/candidate.patterns rename Svc/GenericHub/docs/{GenricHubExampleAppAi.xml => GenericHubExampleAppAi.xml} (100%) rename Svc/GenericRepeater/docs/{GenricRepeaterAppAi.xml => GenericRepeaterAppAi.xml} (100%) diff --git a/.github/actions/spelling/README.md b/.github/actions/spelling/README.md index ca5ca67d08..8dd5e9f88d 100644 --- a/.github/actions/spelling/README.md +++ b/.github/actions/spelling/README.md @@ -7,6 +7,7 @@ File | Purpose | Format | Info [excludes.txt](excludes.txt) | Files to ignore entirely | perl regular expression | [excludes](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-excludes) [only.txt](only.txt) | Only check matching files (applied after excludes) | perl regular expression | [only](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-only) [patterns.txt](patterns.txt) | Patterns to ignore from checked lines | perl regular expression (order matters, first match wins) | [patterns](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-patterns) +[candidate.patterns](candidate.patterns) | Patterns that might be worth adding to [patterns.txt](patterns.txt) | perl regular expression with optional comment block introductions (all matches will be suggested) | [candidates](https://github.com/check-spelling/check-spelling/wiki/Feature:-Suggest-patterns) [line_forbidden.patterns](line_forbidden.patterns) | Patterns to flag in checked lines | perl regular expression (order matters, first match wins) | [patterns](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-patterns) [expect.txt](expect.txt) | Expected words that aren't in the dictionary | one word per line (sorted, alphabetically) | [expect](https://github.com/check-spelling/check-spelling/wiki/Configuration#expect) [advice.md](advice.md) | Supplement for GitHub comment when unrecognized words are found | GitHub Markdown | [advice](https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples%3A-advice) diff --git a/.github/actions/spelling/advice.md b/.github/actions/spelling/advice.md index 54f0c9b5e5..1004eeaa60 100644 --- a/.github/actions/spelling/advice.md +++ b/.github/actions/spelling/advice.md @@ -1,5 +1,5 @@ -

    If the flagged items are false positives +
    If the flagged items are :exploding_head: false positives If items relate to a ... * binary file (or some other file you wouldn't want to check at all). diff --git a/.github/actions/spelling/allow.txt b/.github/actions/spelling/allow.txt index e69de29bb2..f008fff9df 100644 --- a/.github/actions/spelling/allow.txt +++ b/.github/actions/spelling/allow.txt @@ -0,0 +1,6 @@ +github +https +ssh +ubuntu +workaround +workarounds diff --git a/.github/actions/spelling/candidate.patterns b/.github/actions/spelling/candidate.patterns new file mode 100644 index 0000000000..91d1e8a8f1 --- /dev/null +++ b/.github/actions/spelling/candidate.patterns @@ -0,0 +1,527 @@ +# marker to ignore all code on line +^.*/\* #no-spell-check-line \*/.*$ +# marker to ignore all code on line +^.*\bno-spell-check(?:-line|)(?:\s.*|)$ + +# https://cspell.org/configuration/document-settings/ +# cspell inline +^.*\b[Cc][Ss][Pp][Ee][Ll]{2}:\s*[Dd][Ii][Ss][Aa][Bb][Ll][Ee]-[Ll][Ii][Nn][Ee]\b + +# patch hunk comments +^\@\@ -\d+(?:,\d+|) \+\d+(?:,\d+|) \@\@ .* +# git index header +index [0-9a-z]{7,40}\.\.[0-9a-z]{7,40} + +# cid urls +(['"])cid:.*?\g{-1} + +# data url in parens +\(data:[^)]*?(?:[A-Z]{3,}|[A-Z][a-z]{2,}|[a-z]{3,})[^)]*\) +# data url in quotes +([`'"])data:.*?(?:[A-Z]{3,}|[A-Z][a-z]{2,}|[a-z]{3,}).*\g{-1} +# data url +data:[-a-zA-Z=;:/0-9+]*,\S* + +# https/http/file urls +#(?:\b(?:https?|ftp|file)://)[-A-Za-z0-9+&@#/%?=~_|!:,.;]+[-A-Za-z0-9+&@#/%=~_|] + +# mailto urls +mailto:[-a-zA-Z=;:/?%&0-9+@.]{3,} + +# magnet urls +magnet:[?=:\w]+ + +# magnet urls +"magnet:[^"]+" + +# obs: +"obs:[^"]*" + +# The `\b` here means a break, it's the fancy way to handle urls, but it makes things harder to read +# In this examples content, I'm using a number of different ways to match things to show various approaches +# asciinema +\basciinema\.org/a/[0-9a-zA-Z]+ + +# apple +\bdeveloper\.apple\.com/[-\w?=/]+ +# Apple music +\bembed\.music\.apple\.com/fr/playlist/usr-share/[-\w.]+ + +# appveyor api +\bci\.appveyor\.com/api/projects/status/[0-9a-z]+ +# appveyor project +\bci\.appveyor\.com/project/(?:[^/\s"]*/){2}builds?/\d+/job/[0-9a-z]+ + +# Amazon + +# Amazon +\bamazon\.com/[-\w]+/(?:dp/[0-9A-Z]+|) +# AWS S3 +\b\w*\.s3[^.]*\.amazonaws\.com/[-\w/&#%_?:=]* +# AWS execute-api +\b[0-9a-z]{10}\.execute-api\.[-0-9a-z]+\.amazonaws\.com\b +# AWS ELB +\b\w+\.[-0-9a-z]+\.elb\.amazonaws\.com\b +# AWS SNS +\bsns\.[-0-9a-z]+.amazonaws\.com/[-\w/&#%_?:=]* +# AWS VPC +vpc-\w+ + +# While you could try to match `http://` and `https://` by using `s?` in `https?://`, sometimes there +# YouTube url +\b(?:(?:www\.|)youtube\.com|youtu.be)/(?:channel/|embed/|user/|playlist\?list=|watch\?v=|v/|)[-a-zA-Z0-9?&=_%]* +# YouTube music +\bmusic\.youtube\.com/youtubei/v1/browse(?:[?&]\w+=[-a-zA-Z0-9?&=_]*) +# YouTube tag +<\s*youtube\s+id=['"][-a-zA-Z0-9?_]*['"] +# YouTube image +\bimg\.youtube\.com/vi/[-a-zA-Z0-9?&=_]* +# Google Accounts +\baccounts.google.com/[-_/?=.:;+%&0-9a-zA-Z]* +# Google Analytics +\bgoogle-analytics\.com/collect.[-0-9a-zA-Z?%=&_.~]* +# Google APIs +\bgoogleapis\.(?:com|dev)/[a-z]+/(?:v\d+/|)[a-z]+/[-@:./?=\w+|&]+ +# Google Storage +\b[-a-zA-Z0-9.]*\bstorage\d*\.googleapis\.com(?:/\S*|) +# Google Calendar +\bcalendar\.google\.com/calendar(?:/u/\d+|)/embed\?src=[@./?=\w&%]+ +\w+\@group\.calendar\.google\.com\b +# Google DataStudio +\bdatastudio\.google\.com/(?:(?:c/|)u/\d+/|)(?:embed/|)(?:open|reporting|datasources|s)/[-0-9a-zA-Z]+(?:/page/[-0-9a-zA-Z]+|) +# The leading `/` here is as opposed to the `\b` above +# ... a short way to match `https://` or `http://` since most urls have one of those prefixes +# Google Docs +/docs\.google\.com/[a-z]+/(?:ccc\?key=\w+|(?:u/\d+|d/(?:e/|)[0-9a-zA-Z_-]+/)?(?:edit\?[-\w=#.]*|/\?[\w=&]*|)) +# Google Drive +\bdrive\.google\.com/(?:file/d/|open)[-0-9a-zA-Z_?=]* +# Google Groups +\bgroups\.google\.com/(?:(?:forum/#!|d/)(?:msg|topics?|searchin)|a)/[^/\s"]+/[-a-zA-Z0-9$]+(?:/[-a-zA-Z0-9]+)* +# Google Maps +\bmaps\.google\.com/maps\?[\w&;=]* +# Google themes +themes\.googleusercontent\.com/static/fonts/[^/\s"]+/v\d+/[^.]+. +# Google CDN +\bclients2\.google(?:usercontent|)\.com[-0-9a-zA-Z/.]* +# Goo.gl +/goo\.gl/[a-zA-Z0-9]+ +# Google Chrome Store +\bchrome\.google\.com/webstore/detail/[-\w]*(?:/\w*|) +# Google Books +\bgoogle\.(?:\w{2,4})/books(?:/\w+)*\?[-\w\d=&#.]* +# Google Fonts +\bfonts\.(?:googleapis|gstatic)\.com/[-/?=:;+&0-9a-zA-Z]* +# Google Forms +\bforms\.gle/\w+ +# Google Scholar +\bscholar\.google\.com/citations\?user=[A-Za-z0-9_]+ +# Google Colab Research Drive +\bcolab\.research\.google\.com/drive/[-0-9a-zA-Z_?=]* + +# GitHub SHAs (api) +\bapi.github\.com/repos(?:/[^/\s"]+){3}/[0-9a-f]+\b +# GitHub SHAs (markdown) +(?:\[`?[0-9a-f]+`?\]\(https:/|)/(?:www\.|)github\.com(?:/[^/\s"]+){2,}(?:/[^/\s")]+)(?:[0-9a-f]+(?:[-0-9a-zA-Z/#.]*|)\b|) +# GitHub SHAs +\bgithub\.com(?:/[^/\s"]+){2}[@#][0-9a-f]+\b +# GitHub wiki +\bgithub\.com/(?:[^/]+/){2}wiki/(?:(?:[^/]+/|)_history|[^/]+(?:/_compare|)/[0-9a-f.]{40,})\b +# githubusercontent +/[-a-z0-9]+\.githubusercontent\.com/[-a-zA-Z0-9?&=_\/.]* +# githubassets +\bgithubassets.com/[0-9a-f]+(?:[-/\w.]+) +# gist github +\bgist\.github\.com/[^/\s"]+/[0-9a-f]+ +# git.io +\bgit\.io/[0-9a-zA-Z]+ +# GitHub JSON +"node_id": "[-a-zA-Z=;:/0-9+]*" +# Contributor +\[[^\]]+\]\(https://github\.com/[^/\s"]+\) +# GHSA +GHSA(?:-[0-9a-z]{4}){3} + +# GitLab commit +\bgitlab\.[^/\s"]*/\S+/\S+/commit/[0-9a-f]{7,16}#[0-9a-f]{40}\b +# GitLab merge requests +\bgitlab\.[^/\s"]*/\S+/\S+/-/merge_requests/\d+/diffs#[0-9a-f]{40}\b +# GitLab uploads +\bgitlab\.[^/\s"]*/uploads/[-a-zA-Z=;:/0-9+]* +# GitLab commits +\bgitlab\.[^/\s"]*/(?:[^/\s"]+/){2}commits?/[0-9a-f]+\b + +# binanace +accounts.binance.com/[a-z/]*oauth/authorize\?[-0-9a-zA-Z&%]* + +# bitbucket diff +\bapi\.bitbucket\.org/\d+\.\d+/repositories/(?:[^/\s"]+/){2}diff(?:stat|)(?:/[^/\s"]+){2}:[0-9a-f]+ +# bitbucket repositories commits +\bapi\.bitbucket\.org/\d+\.\d+/repositories/(?:[^/\s"]+/){2}commits?/[0-9a-f]+ +# bitbucket commits +\bbitbucket\.org/(?:[^/\s"]+/){2}commits?/[0-9a-f]+ + +# bit.ly +\bbit\.ly/\w+ + +# bitrise +\bapp\.bitrise\.io/app/[0-9a-f]*/[\w.?=&]* + +# bootstrapcdn.com +\bbootstrapcdn\.com/[-./\w]+ + +# cdn.cloudflare.com +\bcdnjs\.cloudflare\.com/[./\w]+ + +# circleci +\bcircleci\.com/gh(?:/[^/\s"]+){1,5}.[a-z]+\?[-0-9a-zA-Z=&]+ + +# gitter +\bgitter\.im(?:/[^/\s"]+){2}\?at=[0-9a-f]+ + +# gravatar +\bgravatar\.com/avatar/[0-9a-f]+ + +# ibm +[a-z.]*ibm\.com/[-_#=:%!?~.\\/\d\w]* + +# imgur +\bimgur\.com/[^.]+ + +# Internet Archive +\barchive\.org/web/\d+/(?:[-\w.?,'/\\+&%$#_:]*) + +# discord +/discord(?:app\.com|\.gg)/(?:invite/)?[a-zA-Z0-9]{7,} + +# Disqus +\bdisqus\.com/[-\w/%.()!?&=_]* + +# medium link +\blink\.medium\.com/[a-zA-Z0-9]+ +# medium +\bmedium\.com/\@?[^/\s"]+/[-\w]+ + +# microsoft +\b(?:https?://|)(?:(?:download\.visualstudio|docs|msdn2?|research)\.microsoft|blogs\.msdn)\.com/[-_a-zA-Z0-9()=./%]* +# powerbi +\bapp\.powerbi\.com/reportEmbed/[^"' ]* +# vs devops +\bvisualstudio.com(?::443|)/[-\w/?=%&.]* +# microsoft store +\bmicrosoft\.com/store/apps/\w+ + +# mvnrepository.com +\bmvnrepository\.com/[-0-9a-z./]+ + +# now.sh +/[0-9a-z-.]+\.now\.sh\b + +# oracle +\bdocs\.oracle\.com/[-0-9a-zA-Z./_?#&=]* + +# chromatic.com +/\S+.chromatic.com\S*[")] + +# codacy +\bapi\.codacy\.com/project/badge/Grade/[0-9a-f]+ + +# compai +\bcompai\.pub/v1/png/[0-9a-f]+ + +# mailgun api +\.api\.mailgun\.net/v3/domains/[0-9a-z]+\.mailgun.org/messages/[0-9a-zA-Z=@]* +# mailgun +\b[0-9a-z]+.mailgun.org + +# /message-id/ +/message-id/[-\w@./%]+ + +# Reddit +\breddit\.com/r/[/\w_]* + +# requestb.in +\brequestb\.in/[0-9a-z]+ + +# sched +\b[a-z0-9]+\.sched\.com\b + +# Slack url +slack://[a-zA-Z0-9?&=]+ +# Slack +\bslack\.com/[-0-9a-zA-Z/_~?&=.]* +# Slack edge +\bslack-edge\.com/[-a-zA-Z0-9?&=%./]+ +# Slack images +\bslack-imgs\.com/[-a-zA-Z0-9?&=%.]+ + +# shields.io +\bshields\.io/[-\w/%?=&.:+;,]* + +# stackexchange -- https://stackexchange.com/feeds/sites +\b(?:askubuntu|serverfault|stack(?:exchange|overflow)|superuser).com/(?:questions/\w+/[-\w]+|a/) + +# Sentry +[0-9a-f]{32}\@o\d+\.ingest\.sentry\.io\b + +# Twitter markdown +\[\@[^[/\]:]*?\]\(https://twitter.com/[^/\s"')]*(?:/status/\d+(?:\?[-_0-9a-zA-Z&=]*|)|)\) +# Twitter hashtag +\btwitter\.com/hashtag/[\w?_=&]* +# Twitter status +\btwitter\.com/[^/\s"')]*(?:/status/\d+(?:\?[-_0-9a-zA-Z&=]*|)|) +# Twitter profile images +\btwimg\.com/profile_images/[_\w./]* +# Twitter media +\btwimg\.com/media/[-_\w./?=]* +# Twitter link shortened +\bt\.co/\w+ + +# facebook +\bfburl\.com/[0-9a-z_]+ +# facebook CDN +\bfbcdn\.net/[\w/.,]* +# facebook watch +\bfb\.watch/[0-9A-Za-z]+ + +# dropbox +\bdropbox\.com/sh?/[^/\s"]+/[-0-9A-Za-z_.%?=&;]+ + +# ipfs protocol +ipfs://[0-9a-z]* +# ipfs url +/ipfs/[0-9a-z]* + +# w3 +\bw3\.org/[-0-9a-zA-Z/#.]+ + +# loom +\bloom\.com/embed/[0-9a-f]+ + +# regex101 +\bregex101\.com/r/[^/\s"]+/\d+ + +# figma +\bfigma\.com/file(?:/[0-9a-zA-Z]+/)+ + +# freecodecamp.org +\bfreecodecamp\.org/[-\w/.]+ + +# image.tmdb.org +\bimage\.tmdb\.org/[/\w.]+ + +# mermaid +\bmermaid\.ink/img/[-\w]+|\bmermaid-js\.github\.io/mermaid-live-editor/#/edit/[-\w]+ + +# Wikipedia +\ben\.wikipedia\.org/wiki/[-\w%.#]+ + +# gitweb +[^"\s]+/gitweb/\S+;h=[0-9a-f]+ + +# HyperKitty lists +/archives/list/[^@/]+\@[^/\s"]*/message/[^/\s"]*/ + +# lists +/thread\.html/[^"\s]+ + +# list-management +\blist-manage\.com/subscribe(?:[?&](?:u|id)=[0-9a-f]+)+ + +# kubectl.kubernetes.io/last-applied-configuration +"kubectl.kubernetes.io/last-applied-configuration": ".*" + +# pgp +\bgnupg\.net/pks/lookup[?&=0-9a-zA-Z]* + +# Spotify +\bopen\.spotify\.com/embed/playlist/\w+ + +# Mastodon +\bmastodon\.[-a-z.]*/(?:media/|\@)[?&=0-9a-zA-Z_]* + +# scastie +\bscastie\.scala-lang\.org/[^/]+/\w+ + +# images.unsplash.com +\bimages\.unsplash\.com/(?:(?:flagged|reserve)/|)[-\w./%?=%&.;]+ + +# pastebin +\bpastebin\.com/[\w/]+ + +# heroku +\b\w+\.heroku\.com/source/archive/\w+ + +# quip +\b\w+\.quip\.com/\w+(?:(?:#|/issues/)\w+)? + +# badgen.net +\bbadgen\.net/badge/[^")\]'\s]+ + +# statuspage.io +\w+\.statuspage\.io\b + +# media.giphy.com +\bmedia\.giphy\.com/media/[^/]+/[\w.?&=]+ + +# tinyurl +\btinyurl\.com/\w+ + +# getopts +\bgetopts\s+(?:"[^"]+"|'[^']+') + +# ANSI color codes +(?:\\(?:u00|x)1b|\x1b)\[\d+(?:;\d+|)m + +# URL escaped characters +\%[0-9A-F][A-F] +# IPv6 +\b(?:[0-9a-fA-F]{0,4}:){3,7}[0-9a-fA-F]{0,4}\b +# c99 hex digits (not the full format, just one I've seen) +0x[0-9a-fA-F](?:\.[0-9a-fA-F]*|)[pP] +# Punycode +\bxn--[-0-9a-z]+ +# sha +sha\d+:[0-9]*[a-f]{3,}[0-9a-f]* +# sha-... -- uses a fancy capture +(['"]|")[0-9a-f]{40,}\g{-1} +# hex runs +\b[0-9a-fA-F]{16,}\b +# hex in url queries +=[0-9a-fA-F]*?(?:[A-F]{3,}|[a-f]{3,})[0-9a-fA-F]*?& +# ssh +(?:ssh-\S+|-nistp256) [-a-zA-Z=;:/0-9+]{12,} + +# PGP +\b(?:[0-9A-F]{4} ){9}[0-9A-F]{4}\b +# GPG keys +\b(?:[0-9A-F]{4} ){5}(?: [0-9A-F]{4}){5}\b +# Well known gpg keys +.well-known/openpgpkey/[\w./]+ + +# uuid: +\b[0-9a-fA-F]{8}-(?:[0-9a-fA-F]{4}-){3}[0-9a-fA-F]{12}\b +# hex digits including css/html color classes: +(?:[\\0][xX]|\\u|[uU]\+|#x?|\%23)[0-9_a-fA-FgGrR]*?[a-fA-FgGrR]{2,}[0-9_a-fA-FgGrR]*(?:[uUlL]{0,3}|u\d+)\b +# integrity +integrity="sha\d+-[-a-zA-Z=;:/0-9+]{40,}" + +# https://www.gnu.org/software/groff/manual/groff.html +# man troff content +\\f[BCIPR] +# ' +\\\(aq + +# .desktop mime types +^MimeTypes?=.*$ +# .desktop localized entries +^[A-Z][a-z]+\[[a-z]+\]=.*$ +# Localized .desktop content +Name\[[^\]]+\]=.* + +# IServiceProvider +\bI(?=(?:[A-Z][a-z]{2,})+\b) + +# crypt +"\$2[ayb]\$.{56}" + +# scrypt / argon +\$(?:scrypt|argon\d+[di]*)\$\S+ + +# Input to GitHub JSON +content: "[-a-zA-Z=;:/0-9+]*=" + +# Python stringprefix / binaryprefix +# Note that there's a high false positive rate, remove the `?=` and search for the regex to see if the matches seem like reasonable strings +(?v# +(?:(?<=[A-Z]{2})V|(?<=[a-z]{2}|[A-Z]{2})v)\d+(?:\b|(?=[a-zA-Z_])) +# Compiler flags (Scala) +(?:^|[\t ,>"'`=(])-J-[DPWXY](?=[A-Z]{2,}|[A-Z][a-z]|[a-z]{2,}) +# Compiler flags +(?:^|[\t ,"'`=(])-[DPWXYLlf](?=[A-Z]{2,}|[A-Z][a-z]|[a-z]{2,}) +# Compiler flags (linker) +,-B +# curl arguments +\b(?:\\n|)curl(?:\s+-[a-zA-Z]{1,2}\b)*(?:\s+-[a-zA-Z]{3,})(?:\s+-[a-zA-Z]+)* +# set arguments +\bset(?:\s+-[abefimouxE]{1,2})*\s+-[abefimouxE]{3,}(?:\s+-[abefimouxE]+)* +# tar arguments +\b(?:\\n|)g?tar(?:\.exe|)(?:(?:\s+--[-a-zA-Z]+|\s+-[a-zA-Z]+|\s[ABGJMOPRSUWZacdfh-pr-xz]+\b)(?:=[^ ]*|))+ +# tput arguments -- https://man7.org/linux/man-pages/man5/terminfo.5.html -- technically they can be more than 5 chars long... +\btput\s+(?:(?:-[SV]|-T\s*\w+)\s+)*\w{3,5}\b +# macOS temp folders +/var/folders/\w\w/[+\w]+/(?:T|-Caches-)/ diff --git a/.github/actions/spelling/excludes.txt b/.github/actions/spelling/excludes.txt index 1200e9ad0c..d3d2a1a562 100644 --- a/.github/actions/spelling/excludes.txt +++ b/.github/actions/spelling/excludes.txt @@ -1,26 +1,37 @@ # See https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples:-excludes (?:^|/)(?i)COPYRIGHT (?:^|/)(?i)LICEN[CS]E +(?:^|/)3rdparty/ (?:^|/)go\.sum$ (?:^|/)package(?:-lock|)\.json$ +(?:^|/)pyproject.toml +(?:^|/)requirements(?:-dev|-doc|-test|)\.txt$ (?:^|/)vendor/ /doc/xml/ /html/ /third-party/ +/__init__\.py$ ignore$ +\.a$ \.ai$ \.avi$ \.bak$ \.bin$ \.bmp$ \.bz2$ +\.class$ +\.coveragerc$ \.crt$ \.dat$ +\.dll$ \.doc$ \.docx$ +\.drawio$ \.DS_Store$ \.eot$ +\.exe$ \.gif$ +\.git-blame-ignore-revs$ \.gitattributes$ \.graffle$ \.gz$ @@ -28,8 +39,10 @@ ignore$ \.ico$ \.inv$ \.jar$ +\.jks$ \.jpe?g$ \.key$ +\.lib$ \.lock$ \.log$ \.map$ @@ -38,6 +51,7 @@ ignore$ \.min\.. \.mod$ \.mp[34]$ +\.o$ \.ocf$ \.otf$ \.pdf$ @@ -45,17 +59,23 @@ ignore$ \.png$ \.pptx$ \.psd$ +\.pyc$ +\.pylintrc$ \.rtf$ +\.s$ \.ser$ \.sty$ \.svg$ +\.svgz?$ +\.tar$ \.tex$ +\.tiff?$ \.ttf$ \.vm$ \.vsdx$ \.wav$ -\.woff$ -\.woff2$ +\.webm$ +\.webp$ \.woff2?$ \.xls$ \.xlsx$ @@ -77,12 +97,22 @@ ignore$ ^Svc/TlmChan/TlmChan\.hpp$ ^\.github/actions/spelling/ ^\Q.github/workflows/spelling.yml\E$ +^\QAutocoders/Python/doc/tlmLayout/LayoutExampleTlmLayoutAi.csv\E$ +^\QAutocoders/Python/src/fprime_ac/generators/templates/serialize/includes1SerialH.tmpl\E$ +^\QAutocoders/Python/test/command_multi_inst/docs/Test1.md\E$ +^\QAutocoders/Python/test/event_multi_inst/docs/TestLog.md\E$ +^\QAutocoders/Python/test/tlm_multi_inst/docs/TestTlm.md\E$ +^\Qcmake/platform/README.md\E$ +^\Qdocs/Tutorials/FullSystemTutorial/Tutorial.md\E$ ^\QDrv/BlockDriver/BlockDriver.hpp\E$ ^\QDrv/LinuxGpioDriver/LinuxGpioDriver.hpp\E$ ^\QDrv/LinuxSpiDriver/LinuxSpiDriver.hpp\E$ ^\QDrv/TcpClient/TcpClient.hpp\E$ ^\QFw/Types/Linux/StandardTypes.hpp\E$ +^\QRef/SignalGen/check.xml\E$ ^\Qrequirements.txt\E$ +^\QSTest/README.md\E$ +^\QSvc/FileDownlink/check.xml\E$ ^\QSvc/LinuxTime/LinuxTime.hpp\E$ ^\QSvc/PrmDb/PrmDb.hpp\E$ ^\QSvc/TlmChan/TlmChan.hpp\E$ diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index e2921d28ba..bf0cd57c9a 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -77,6 +77,7 @@ autocoders autocoding autocompletion autodoc +autodocs Autodocumentation autogen Autogenerate @@ -105,6 +106,7 @@ bitmaps bitset ble blog +blogs BLSPSERIALDRIVERCOMPONENTIMPLCFG bocchino bodychars @@ -280,7 +282,6 @@ databinding DATAROOTDIR datastore dawbarton -db DBUILD DCMAKE DDDTHH @@ -462,7 +463,6 @@ fbuild fcheck fclose fcntl -fd fds fdset featuredarticles @@ -860,7 +860,6 @@ mname modbus MOSI MOVEFILE -mq mqd mqueue Mrf @@ -883,6 +882,7 @@ multline munmap mutex mutexattr +Mutexed mutexes mval mycompany @@ -905,7 +905,6 @@ newself newstring newtio nfds -Nh Nicolich ninjaaron NMEA @@ -1020,12 +1019,15 @@ pkts plainnat plantuml plugin +plugins pname png PNGs +POLLERR pollerr pollfd POLLIN +POLLPRI pollpri POLYDB POLYDBCOMP @@ -1080,6 +1082,7 @@ ptmcg pton ptr ptype +puml punc pushd pwd @@ -1166,7 +1169,6 @@ riverbankcomputing Rizvi rootdir ror -rp rpaetz rpi RPIDEMO @@ -1204,6 +1206,7 @@ scons scp scrollbars sdd +SDFLIGHT searchdata SEARCHENGINE segfault @@ -1293,6 +1296,7 @@ srand srandom srange src +SRCS sre sscanf ssh @@ -1344,6 +1348,7 @@ strtol strtoul subdir subfolder +subfolders subgrouping subhist subhistory @@ -1437,7 +1442,6 @@ timothycanham tions tjh TKC -tl tlc tlist tlm @@ -1487,7 +1491,6 @@ trimwhitespace trinomials TRUNC truncstring -tt tts ttype Tuszynski @@ -1529,6 +1532,7 @@ unistd Unithem unittest UNITTESTASSERT +unittests unprintables unsubscribe upcalls @@ -1567,7 +1571,6 @@ virtualization virtualized vla vlist -vm VMIN vmstat vsnprintf @@ -1600,7 +1603,6 @@ WORKDIR workflow worklist Woverloaded -wp writelines WRONLY wrs @@ -1613,6 +1615,7 @@ wxgui Xabcdefx xapian xargs +Xcode XBee xcode xdf diff --git a/.github/actions/spelling/line_forbidden.patterns b/.github/actions/spelling/line_forbidden.patterns index 4ca15837cc..760ec9b6ff 100644 --- a/.github/actions/spelling/line_forbidden.patterns +++ b/.github/actions/spelling/line_forbidden.patterns @@ -1,6 +1,11 @@ # reject `m_data` as there's a certain OS which has evil defines that break things if it's used elsewhere # \bm_data\b +# If you have a framework that uses `it()` for testing and `fit()` for debugging a specific test, +# you might not want to check in code where you were debugging w/ `fit()`, in which case, you might want +# to use this: +#\bfit\( + # s.b. GitHub \bGithub\b @@ -19,6 +24,12 @@ # s.b. greater than \bgreater then\b +# s.b. into +#\sin to\s + +# s.b. opt-in +\sopt in\s + # s.b. less than \bless then\b @@ -30,10 +41,22 @@ \b[Nn]o[nt][- ]existent\b # s.b. preexisting -[Pp]re-existing +[Pp]re[- ]existing + +# s.b. preempt +[Pp]re[- ]empt\b # s.b. preemptively -[Pp]re-emptively +[Pp]re[- ]emptively + +# s.b. reentrancy +[Rr]e[- ]entrancy + +# s.b. reentrant +[Rr]e[- ]entrant + +# s.b. workaround(s) +\bwork[- ]arounds?\b # Reject duplicate words \s([A-Z]{3,}|[A-Z][a-z]{2,}|[a-z]{3,})\s\g{-1}\s diff --git a/.github/actions/spelling/patterns.txt b/.github/actions/spelling/patterns.txt index 6241a7b50b..edd3969da1 100644 --- a/.github/actions/spelling/patterns.txt +++ b/.github/actions/spelling/patterns.txt @@ -1,5 +1,49 @@ # See https://github.com/check-spelling/check-spelling/wiki/Configuration-Examples:-patterns +# hit-count: 106 file-count: 28 +# Compiler flags +(?:^|[\t ,"'`=(])-[DPWXYLlf](?=[A-Z]{2,}|[A-Z][a-z]|[a-z]{2,}) + +# hit-count: 48 file-count: 18 +# GitHub SHAs (markdown) +(?:\[`?[0-9a-f]+`?\]\(https:/|)/(?:www\.|)github\.com(?:/[^/\s"]+){2,}(?:/[^/\s")]+)(?:[0-9a-f]+(?:[-0-9a-zA-Z/#.]*|)\b|) + +# hit-count: 29 file-count: 13 +# version suffix v# +(?:(?<=[A-Z]{2})V|(?<=[a-z]{2}|[A-Z]{2})v)\d+(?:\b|(?=[a-zA-Z_])) + +# hit-count: 8 file-count: 3 +# Wikipedia +\ben\.wikipedia\.org/wiki/[-\w%.#]+ + +# hit-count: 5 file-count: 2 +# w3 +\bw3\.org/[-0-9a-zA-Z/#.]+ + +# hit-count: 3 file-count: 3 +# Contributor +\[[^\]]+\]\(https://github\.com/[^/\s"]+\) + +# hit-count: 3 file-count: 3 +# stackexchange -- https://stackexchange.com/feeds/sites +\b(?:askubuntu|serverfault|stack(?:exchange|overflow)|superuser).com/(?:questions/\w+/[-\w]+|a/) + +# hit-count: 2 file-count: 1 +# mailto urls +\[([-a-zA-Z=;:/?%&0-9+@.]{3,})]\(mailto:\g{-1}\) + +# hit-count: 2 file-count: 1 +# apple +\bdeveloper\.apple\.com/[-\w?=/]+ + +# hit-count: 2 file-count: 1 +# shields.io +\bshields\.io/[-\w/%?=&.:+;,]* + +# hit-count: 1 file-count: 1 +# hex runs +\b[0-9a-fA-F]{16,}\b + # data urls "data:[^"]*" 'data:[^']*' @@ -47,20 +91,33 @@ value="(?:[0-9a-f]{1,2} )*" # Ignore any text between inline back-ticks `(.*?)` -# Tar archive items +# Tar archive items \b(?:\\n|)tar(?:\s+-[a-zA-Z]+|\s[a-z]+)+ # slashes after spaces are not in paths LaTeX \\.* \\ +# Questionably acceptable forms of `in to` +# Personally, I prefer `log into`, but people object +# https://www.tprteaching.com/log-into-log-in-to-login/ +\b[Ll]og in to\b + # acceptable duplicates # ls directory listings -[-bcdlpsw](?:[-r][-w][-sx]){3}\s+\d+\s+(\S+)\s+\g{-1}\s+\d+\s+ -# C types -\s(expr|long|LONG|Time)(?:\s+\g{-1})+\s +[-bcdlpsw](?:[-r][-w][-Ssx]){3}\s+\d+\s+\S+\s+\S+\s+\d+\s+ +# C types and repeated CSS values +\s(center|div|inherit|expr|long|LONG|none|normal|solid|Time|thin|transparent|very)(?: \g{-1})+\s +# go templates +\s(\w+)\s+\g{-1}\s+\`(?:graphql|json|yaml): # javadoc / .net (?:[\\@](?:groupname|page|param)|(?:public|private)(?:\s+static|\s+readonly)*)\s+(\w+)\s+\g{-1}\s +# Commit message -- Signed-off-by and friends +^\s*(?:(?:Based-on-patch|Co-authored|Helped|Mentored|Reported|Reviewed|Signed-off)-by|Thanks-to): (?:[^<]*<[^>]*>|[^<]*)\s*$ + +# Autogenerated revert commit message +^This reverts commit [0-9a-f]{40}\.$ + # Jenkins library GithubProjectProperty diff --git a/.github/workflows/spelling.yml b/.github/workflows/spelling.yml index c31e5767e9..178a500a1e 100644 --- a/.github/workflows/spelling.yml +++ b/.github/workflows/spelling.yml @@ -1,4 +1,38 @@ name: Spell checking + +# Comment management is handled through a secondary job, for details see: +# https://github.com/check-spelling/check-spelling/wiki/Feature%3A-Restricted-Permissions +# +# `jobs.comment-push` runs when a push is made to a repository and the `jobs.spelling` job needs to make a comment +# (in odd cases, it might actually run just to collapse a comment, but that's fairly rare) +# it needs `contents: write` in order to add a comment. +# +# `jobs.comment-pr` runs when a pull_request is made to a repository and the `jobs.spelling` job needs to make a comment +# or collapse a comment (in the case where it had previously made a comment and now no longer needs to show a comment) +# it needs `pull-requests: write` in order to manipulate those comments. + +# Updating pull request branches is managed via comment handling. +# For details, see: https://github.com/check-spelling/check-spelling/wiki/Feature:-Update-expect-list +# +# These elements work together to make it happen: +# +# `on.issue_comment` +# This event listens to comments by users asking to update the metadata. +# +# `jobs.update` +# This job runs in response to an issue_comment and will push a new commit +# to update the spelling metadata. +# +# `with.experimental_apply_changes_via_bot` +# Tells the action to support and generate messages that enable it +# to make a commit to update the spelling metadata. +# +# `with.ssh_key` +# In order to trigger workflows when the commit is made, you can provide a +# secret (typically, a write-enabled github deploy key). +# +# For background, see: https://github.com/check-spelling/check-spelling/wiki/Feature:-Update-with-deploy-key + on: push: branches: @@ -10,7 +44,10 @@ on: - "**" tags-ignore: - "**" - types: ['opened', 'reopened', 'synchronize'] + types: + - 'opened' + - 'reopened' + - 'synchronize' jobs: spelling: @@ -30,15 +67,26 @@ jobs: steps: - name: check-spelling id: spelling - uses: check-spelling/check-spelling@v0.0.20 + uses: check-spelling/check-spelling@v0.0.21 with: suppress_push_for_open_pull_request: 1 checkout: true + check_file_names: 1 + spell_check_this: check-spelling/spell-check-this@prerelease post_comment: 0 + use_magic_file: 1 + extra_dictionary_limit: 10 extra_dictionaries: cspell:filetypes/filetypes.txt - cspell:python/python.txt + cspell:python/src/python/python-lib.txt + cspell:python/src/python/python.txt + cspell:python/src/common/extra.txt + cspell:software-terms/src/software-terms.txt + cspell:node/node.txt + cspell:cpp/src/stdlib-c.txt + cspell:cpp/src/stdlib-cpp.txt cspell:django/django.txt cspell:html/html.txt cspell:fullstack/fullstack.txt + cspell:aws/aws.txt check_extra_dictionaries: '' diff --git a/Autocoders/Python/schema/default/interface_schema.rng b/Autocoders/Python/schema/default/interface_schema.rng index 4c9b42c1b4..87d9059ce9 100644 --- a/Autocoders/Python/schema/default/interface_schema.rng +++ b/Autocoders/Python/schema/default/interface_schema.rng @@ -4,7 +4,7 @@ xmlns:a="http://relaxng.org/ns/compatibility/annotations/1.0" datatypeLibrary="http://www.w3.org/2001/XMLSchema-datatypes"> - + diff --git a/Autocoders/Python/schema/default/internal_interface_schema.rng b/Autocoders/Python/schema/default/internal_interface_schema.rng index 87f963dfd7..f29e24c3ee 100644 --- a/Autocoders/Python/schema/default/internal_interface_schema.rng +++ b/Autocoders/Python/schema/default/internal_interface_schema.rng @@ -4,7 +4,7 @@ xmlns:a="http://relaxng.org/ns/compatibility/annotations/1.0" datatypeLibrary="http://www.w3.org/2001/XMLSchema-datatypes"> - + diff --git a/Autocoders/Python/src/fprime_ac/models/Arg.py b/Autocoders/Python/src/fprime_ac/models/Arg.py index 08447cf7e1..19f6efd9a9 100644 --- a/Autocoders/Python/src/fprime_ac/models/Arg.py +++ b/Autocoders/Python/src/fprime_ac/models/Arg.py @@ -45,7 +45,7 @@ def __init__(self, name, atype, modifier, size=None, comment=None): @param type: Type of arg (must have supporting include xml) @param modifier: Modification of the argument (i.e. pointer or reference) @param size: size of array of type (string or buffer) - @param comment: A single or multline comment + @param comment: A single or multiline comment """ self.__name = name self.__type = atype diff --git a/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py b/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py index fca03ad593..66fcb1215e 100644 --- a/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py +++ b/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py @@ -1383,8 +1383,8 @@ def __init__( @param name: Name of port (each instance must be unique). @param direction: Direction of data flow (must be input or output) @param type: Type of port (must have supporting include xml) - @param sync: Kind of port (must be one of: asynch, synch, or guarded) - @param comment: A single or multline comment + @param sync: Kind of port (must be one of: async, sync, or guarded) + @param comment: A single or multiline comment """ # TODO: ADD NAMESPACE self.__name = name diff --git a/Autocoders/Python/src/fprime_ac/parsers/XmlPortsParser.py b/Autocoders/Python/src/fprime_ac/parsers/XmlPortsParser.py index 4db40f9e6a..8b09211425 100644 --- a/Autocoders/Python/src/fprime_ac/parsers/XmlPortsParser.py +++ b/Autocoders/Python/src/fprime_ac/parsers/XmlPortsParser.py @@ -304,7 +304,7 @@ def __init__(self, name, atype, modifier, size=None, comment=None): @param type: Type of arg (must have supporting include xml) @param modifier: Whether argument is passed by value, reference, or pointer @param size: size of array for string and buffer - @param comment: A single or multline comment + @param comment: A single or multiline comment """ self.__name = name self.__type = atype diff --git a/Autocoders/Python/templates/CMakeLists.txt b/Autocoders/Python/templates/CMakeLists.txt index f9524402d3..4fe4dd16ab 100644 --- a/Autocoders/Python/templates/CMakeLists.txt +++ b/Autocoders/Python/templates/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/CFDP/Checksum/CMakeLists.txt b/CFDP/Checksum/CMakeLists.txt index 0300646cc0..d6f3a11eaa 100644 --- a/CFDP/Checksum/CMakeLists.txt +++ b/CFDP/Checksum/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/CFDP/Checksum/GTest/CMakeLists.txt b/CFDP/Checksum/GTest/CMakeLists.txt index a778b60118..d2b937e70c 100644 --- a/CFDP/Checksum/GTest/CMakeLists.txt +++ b/CFDP/Checksum/GTest/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/BlockDriver/CMakeLists.txt b/Drv/BlockDriver/CMakeLists.txt index 2789e64813..38bb8281f4 100644 --- a/Drv/BlockDriver/CMakeLists.txt +++ b/Drv/BlockDriver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/ByteStreamDriverModel/CMakeLists.txt b/Drv/ByteStreamDriverModel/CMakeLists.txt index deb8ca334c..cf19e49396 100644 --- a/Drv/ByteStreamDriverModel/CMakeLists.txt +++ b/Drv/ByteStreamDriverModel/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/DataTypes/CMakeLists.txt b/Drv/DataTypes/CMakeLists.txt index 03786646a0..fc85603c27 100644 --- a/Drv/DataTypes/CMakeLists.txt +++ b/Drv/DataTypes/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/GpioDriverPorts/CMakeLists.txt b/Drv/GpioDriverPorts/CMakeLists.txt index d0a12854be..8ed47ecc86 100644 --- a/Drv/GpioDriverPorts/CMakeLists.txt +++ b/Drv/GpioDriverPorts/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/I2cDriverPorts/CMakeLists.txt b/Drv/I2cDriverPorts/CMakeLists.txt index 3ddc5212cb..c164cb9f43 100644 --- a/Drv/I2cDriverPorts/CMakeLists.txt +++ b/Drv/I2cDriverPorts/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/Ip/CMakeLists.txt b/Drv/Ip/CMakeLists.txt index 39388ceb4e..0473c63867 100644 --- a/Drv/Ip/CMakeLists.txt +++ b/Drv/Ip/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/LinuxGpioDriver/CMakeLists.txt b/Drv/LinuxGpioDriver/CMakeLists.txt index 8d2567ceae..b20d3ed98d 100644 --- a/Drv/LinuxGpioDriver/CMakeLists.txt +++ b/Drv/LinuxGpioDriver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/LinuxI2cDriver/CMakeLists.txt b/Drv/LinuxI2cDriver/CMakeLists.txt index 4e4deb9c40..eabb7ac694 100644 --- a/Drv/LinuxI2cDriver/CMakeLists.txt +++ b/Drv/LinuxI2cDriver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/LinuxSpiDriver/CMakeLists.txt b/Drv/LinuxSpiDriver/CMakeLists.txt index 4d9aa7ecdd..10419ba038 100644 --- a/Drv/LinuxSpiDriver/CMakeLists.txt +++ b/Drv/LinuxSpiDriver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/LinuxUartDriver/CMakeLists.txt b/Drv/LinuxUartDriver/CMakeLists.txt index 3d87a0e9b2..0bc47509cc 100644 --- a/Drv/LinuxUartDriver/CMakeLists.txt +++ b/Drv/LinuxUartDriver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/SpiDriverPorts/CMakeLists.txt b/Drv/SpiDriverPorts/CMakeLists.txt index 88d03f874a..1d6bd704f4 100644 --- a/Drv/SpiDriverPorts/CMakeLists.txt +++ b/Drv/SpiDriverPorts/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/TcpClient/CMakeLists.txt b/Drv/TcpClient/CMakeLists.txt index fb2a04b56c..99ae5f1451 100644 --- a/Drv/TcpClient/CMakeLists.txt +++ b/Drv/TcpClient/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/TcpServer/CMakeLists.txt b/Drv/TcpServer/CMakeLists.txt index 59b8e3e41e..80ac3fc867 100644 --- a/Drv/TcpServer/CMakeLists.txt +++ b/Drv/TcpServer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Drv/Udp/CMakeLists.txt b/Drv/Udp/CMakeLists.txt index 699dbaab56..203b804904 100644 --- a/Drv/Udp/CMakeLists.txt +++ b/Drv/Udp/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Buffer/CMakeLists.txt b/Fw/Buffer/CMakeLists.txt index 76ca5f548d..701e233186 100644 --- a/Fw/Buffer/CMakeLists.txt +++ b/Fw/Buffer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Cfg/CMakeLists.txt b/Fw/Cfg/CMakeLists.txt index ecb0c5a769..08c0c2f2b2 100644 --- a/Fw/Cfg/CMakeLists.txt +++ b/Fw/Cfg/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Cmd/CMakeLists.txt b/Fw/Cmd/CMakeLists.txt index 5cba1e92e2..f87144d8cb 100644 --- a/Fw/Cmd/CMakeLists.txt +++ b/Fw/Cmd/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Com/CMakeLists.txt b/Fw/Com/CMakeLists.txt index f8139ca4e9..8cfcff21d1 100644 --- a/Fw/Com/CMakeLists.txt +++ b/Fw/Com/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Comp/CMakeLists.txt b/Fw/Comp/CMakeLists.txt index ba18f8b557..6865bdd831 100644 --- a/Fw/Comp/CMakeLists.txt +++ b/Fw/Comp/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/FilePacket/CMakeLists.txt b/Fw/FilePacket/CMakeLists.txt index c92c708c73..c7a1914c2c 100644 --- a/Fw/FilePacket/CMakeLists.txt +++ b/Fw/FilePacket/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/FilePacket/GTest/CMakeLists.txt b/Fw/FilePacket/GTest/CMakeLists.txt index 6c5b7d3e8d..e9b17fb627 100644 --- a/Fw/FilePacket/GTest/CMakeLists.txt +++ b/Fw/FilePacket/GTest/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Fw/Log/CMakeLists.txt b/Fw/Log/CMakeLists.txt index ce323f496b..dcd364dd95 100644 --- a/Fw/Log/CMakeLists.txt +++ b/Fw/Log/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Logger/CMakeLists.txt b/Fw/Logger/CMakeLists.txt index 844a9b8d5d..90c41d82a8 100644 --- a/Fw/Logger/CMakeLists.txt +++ b/Fw/Logger/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Logger/test/ut/Main.cpp b/Fw/Logger/test/ut/Main.cpp index 7449fcd892..14d52daaf9 100644 --- a/Fw/Logger/test/ut/Main.cpp +++ b/Fw/Logger/test/ut/Main.cpp @@ -49,7 +49,7 @@ TEST(LoggerTests, RandomLoggerTests) { /** * Test that the most basic logging function works. */ -TEST(LoggerTests, BassicGoodLogger) { +TEST(LoggerTests, BasicGoodLogger) { // Setup and register logger MockLogging::FakeLogger logger; Fw::Logger::registerLogger(&logger); @@ -61,7 +61,7 @@ TEST(LoggerTests, BassicGoodLogger) { /** * Test that null-logging function works. */ -TEST(LoggerTests, BassicBadLogger) { +TEST(LoggerTests, BasicBadLogger) { // Basic discard logging MockLogging::FakeLogger logger; Fw::Logger::registerLogger(nullptr); @@ -73,7 +73,7 @@ TEST(LoggerTests, BassicBadLogger) { /** * Test that registration works. Multiple times, as contains randomness. */ -TEST(LoggerTests, BassicRegLogger) { +TEST(LoggerTests, BasicRegLogger) { // Basic discard logging MockLogging::FakeLogger logger; LoggerRules::Register reg("Register"); diff --git a/Fw/Obj/CMakeLists.txt b/Fw/Obj/CMakeLists.txt index 25d6965e80..80a3210321 100644 --- a/Fw/Obj/CMakeLists.txt +++ b/Fw/Obj/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Port/CMakeLists.txt b/Fw/Port/CMakeLists.txt index 1308860feb..3747db3fca 100644 --- a/Fw/Port/CMakeLists.txt +++ b/Fw/Port/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Prm/CMakeLists.txt b/Fw/Prm/CMakeLists.txt index 0aeb62de0a..a468b38f91 100644 --- a/Fw/Prm/CMakeLists.txt +++ b/Fw/Prm/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/SerializableFile/CMakeLists.txt b/Fw/SerializableFile/CMakeLists.txt index 1b06bb627e..e040d1acba 100644 --- a/Fw/SerializableFile/CMakeLists.txt +++ b/Fw/SerializableFile/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/SerializableFile/test/TestSerializable/CMakeLists.txt b/Fw/SerializableFile/test/TestSerializable/CMakeLists.txt index eab663392b..681efdcf53 100644 --- a/Fw/SerializableFile/test/TestSerializable/CMakeLists.txt +++ b/Fw/SerializableFile/test/TestSerializable/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Test/CMakeLists.txt b/Fw/Test/CMakeLists.txt index f18d8ec8a0..dff1941472 100644 --- a/Fw/Test/CMakeLists.txt +++ b/Fw/Test/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Time/CMakeLists.txt b/Fw/Time/CMakeLists.txt index 996a2917fe..fa739f5ad6 100644 --- a/Fw/Time/CMakeLists.txt +++ b/Fw/Time/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Tlm/CMakeLists.txt b/Fw/Tlm/CMakeLists.txt index 5d29e9c576..c05d3a179d 100644 --- a/Fw/Tlm/CMakeLists.txt +++ b/Fw/Tlm/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Fw/Types/CMakeLists.txt b/Fw/Types/CMakeLists.txt index f784ab85d1..b9105f640c 100644 --- a/Fw/Types/CMakeLists.txt +++ b/Fw/Types/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Fw/Types/GTest/CMakeLists.txt b/Fw/Types/GTest/CMakeLists.txt index 8e864435f6..5b8dfb8ba2 100644 --- a/Fw/Types/GTest/CMakeLists.txt +++ b/Fw/Types/GTest/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Os/Baremetal/TaskRunner/BareTaskHandle.hpp b/Os/Baremetal/TaskRunner/BareTaskHandle.hpp index 5b69ef22e6..dbcdea7a44 100644 --- a/Os/Baremetal/TaskRunner/BareTaskHandle.hpp +++ b/Os/Baremetal/TaskRunner/BareTaskHandle.hpp @@ -19,7 +19,7 @@ class BareTaskHandle { bool m_enabled; //!< Save the priority NATIVE_INT_TYPE m_priority; - //!< Function passed in to the task + //!< Function passed into the task Task::taskRoutine m_routine; //!< Argument input pointer void* m_argument; diff --git a/Os/Baremetal/TaskRunner/CMakeLists.txt b/Os/Baremetal/TaskRunner/CMakeLists.txt index e570279c4f..26ab1a5774 100644 --- a/Os/Baremetal/TaskRunner/CMakeLists.txt +++ b/Os/Baremetal/TaskRunner/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Os/CMakeLists.txt b/Os/CMakeLists.txt index 12bde1fcf1..2d5fa8bb3a 100644 --- a/Os/CMakeLists.txt +++ b/Os/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Os/Stubs/CMakeLists.txt b/Os/Stubs/CMakeLists.txt index a1c4cd3686..2a3ff41f98 100644 --- a/Os/Stubs/CMakeLists.txt +++ b/Os/Stubs/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/RPI/RpiDemo/CMakeLists.txt b/RPI/RpiDemo/CMakeLists.txt index 6b66fbe00d..ecfb698cf6 100644 --- a/RPI/RpiDemo/CMakeLists.txt +++ b/RPI/RpiDemo/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/RPI/Top/CMakeLists.txt b/RPI/Top/CMakeLists.txt index 598fbfd9ef..8b504f2f06 100644 --- a/RPI/Top/CMakeLists.txt +++ b/RPI/Top/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Ref/PingReceiver/CMakeLists.txt b/Ref/PingReceiver/CMakeLists.txt index 20be4c249d..16c15bd70f 100644 --- a/Ref/PingReceiver/CMakeLists.txt +++ b/Ref/PingReceiver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Ref/RecvBuffApp/CMakeLists.txt b/Ref/RecvBuffApp/CMakeLists.txt index af7f7b9f71..d02e6346c1 100644 --- a/Ref/RecvBuffApp/CMakeLists.txt +++ b/Ref/RecvBuffApp/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Ref/SendBuffApp/CMakeLists.txt b/Ref/SendBuffApp/CMakeLists.txt index beadc881f1..c05f766586 100644 --- a/Ref/SendBuffApp/CMakeLists.txt +++ b/Ref/SendBuffApp/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Ref/SignalGen/CMakeLists.txt b/Ref/SignalGen/CMakeLists.txt index 64eea103d9..b382b9477c 100644 --- a/Ref/SignalGen/CMakeLists.txt +++ b/Ref/SignalGen/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Ref/Top/CMakeLists.txt b/Ref/Top/CMakeLists.txt index 9de37fec1a..fce5416991 100644 --- a/Ref/Top/CMakeLists.txt +++ b/Ref/Top/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies #### diff --git a/Svc/ActiveLogger/CMakeLists.txt b/Svc/ActiveLogger/CMakeLists.txt index 0521ef4012..b31e2a3103 100644 --- a/Svc/ActiveLogger/CMakeLists.txt +++ b/Svc/ActiveLogger/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/ActiveRateGroup/CMakeLists.txt b/Svc/ActiveRateGroup/CMakeLists.txt index ee845c6c64..012ddbb4cb 100644 --- a/Svc/ActiveRateGroup/CMakeLists.txt +++ b/Svc/ActiveRateGroup/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/ActiveTextLogger/CMakeLists.txt b/Svc/ActiveTextLogger/CMakeLists.txt index 9408619bb5..c9fecef4e5 100644 --- a/Svc/ActiveTextLogger/CMakeLists.txt +++ b/Svc/ActiveTextLogger/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/AssertFatalAdapter/CMakeLists.txt b/Svc/AssertFatalAdapter/CMakeLists.txt index a811de6118..03fd069f3e 100644 --- a/Svc/AssertFatalAdapter/CMakeLists.txt +++ b/Svc/AssertFatalAdapter/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/BufferLogger/CMakeLists.txt b/Svc/BufferLogger/CMakeLists.txt index 87f203baa6..4be8388af7 100644 --- a/Svc/BufferLogger/CMakeLists.txt +++ b/Svc/BufferLogger/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/BufferManager/CMakeLists.txt b/Svc/BufferManager/CMakeLists.txt index b14acdc062..24d060a050 100644 --- a/Svc/BufferManager/CMakeLists.txt +++ b/Svc/BufferManager/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/CmdDispatcher/CMakeLists.txt b/Svc/CmdDispatcher/CMakeLists.txt index bb7efe2fca..6820e752a5 100644 --- a/Svc/CmdDispatcher/CMakeLists.txt +++ b/Svc/CmdDispatcher/CMakeLists.txt @@ -2,7 +2,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/CmdSequencer/CMakeLists.txt b/Svc/CmdSequencer/CMakeLists.txt index 697a30b516..24d803b86a 100644 --- a/Svc/CmdSequencer/CMakeLists.txt +++ b/Svc/CmdSequencer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/CmdSequencer/docs/sdd.md b/Svc/CmdSequencer/docs/sdd.md index ef85342ddf..b7262b74e6 100644 --- a/Svc/CmdSequencer/docs/sdd.md +++ b/Svc/CmdSequencer/docs/sdd.md @@ -43,7 +43,7 @@ pingIn|Svc::Ping|async input|Input ping call pingOut|Svc::Ping|output|Reply for ping schedIn|Svc::Sched|async input|Scheduler input - timed commands will be checked comCmdOut|Fw::Com|output|Sends command buffers for each command in sequence -cmdResponseIn|Fw::CmdResponse|asyc input|Received status of last dispatched command +cmdResponseIn|Fw::CmdResponse|async input|Received status of last dispatched command seqRunIn|Svc::CmdSeqIn|async input|Receives requests for running sequences from other components seqDone|Fw::CmdResponse|output|outputs status of sequence run; meant to be used with `seqRunIn` diff --git a/Svc/CmdSequencer/test/ut/SequenceFiles/File.hpp b/Svc/CmdSequencer/test/ut/SequenceFiles/File.hpp index 9d3c9bc365..63b1ddb52e 100644 --- a/Svc/CmdSequencer/test/ut/SequenceFiles/File.hpp +++ b/Svc/CmdSequencer/test/ut/SequenceFiles/File.hpp @@ -75,7 +75,7 @@ namespace Svc { //! Open errors Open open; - //! Heade read errors + //! Header read errors HeaderRead headerRead; //! Data read errors diff --git a/Svc/ComLogger/CMakeLists.txt b/Svc/ComLogger/CMakeLists.txt index f4b10998e1..7bc4413faa 100644 --- a/Svc/ComLogger/CMakeLists.txt +++ b/Svc/ComLogger/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/ComSplitter/CMakeLists.txt b/Svc/ComSplitter/CMakeLists.txt index 0e9d006698..6602453c53 100644 --- a/Svc/ComSplitter/CMakeLists.txt +++ b/Svc/ComSplitter/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Cycle/CMakeLists.txt b/Svc/Cycle/CMakeLists.txt index 0f62a6a329..32dcbfa8c6 100644 --- a/Svc/Cycle/CMakeLists.txt +++ b/Svc/Cycle/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Deframer/CMakeLists.txt b/Svc/Deframer/CMakeLists.txt index f9fd350047..c90079e115 100644 --- a/Svc/Deframer/CMakeLists.txt +++ b/Svc/Deframer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Fatal/CMakeLists.txt b/Svc/Fatal/CMakeLists.txt index 5eaf08a575..53c0e656f1 100644 --- a/Svc/Fatal/CMakeLists.txt +++ b/Svc/Fatal/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/FatalHandler/CMakeLists.txt b/Svc/FatalHandler/CMakeLists.txt index 27ae77a898..6b82bb5bfa 100644 --- a/Svc/FatalHandler/CMakeLists.txt +++ b/Svc/FatalHandler/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/FileDownlink/CMakeLists.txt b/Svc/FileDownlink/CMakeLists.txt index 19497b0002..74e0fd9be6 100644 --- a/Svc/FileDownlink/CMakeLists.txt +++ b/Svc/FileDownlink/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/FileDownlinkPorts/CMakeLists.txt b/Svc/FileDownlinkPorts/CMakeLists.txt index 1cf27cdfe7..c4216dd5ab 100644 --- a/Svc/FileDownlinkPorts/CMakeLists.txt +++ b/Svc/FileDownlinkPorts/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/FileManager/CMakeLists.txt b/Svc/FileManager/CMakeLists.txt index c50de22066..ef30c5d810 100644 --- a/Svc/FileManager/CMakeLists.txt +++ b/Svc/FileManager/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/FileUplink/CMakeLists.txt b/Svc/FileUplink/CMakeLists.txt index c8ef18f404..abcc81addc 100644 --- a/Svc/FileUplink/CMakeLists.txt +++ b/Svc/FileUplink/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Framer/CMakeLists.txt b/Svc/Framer/CMakeLists.txt index c0b2c6c2a7..8de1326a00 100644 --- a/Svc/Framer/CMakeLists.txt +++ b/Svc/Framer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/FramingProtocol/CMakeLists.txt b/Svc/FramingProtocol/CMakeLists.txt index 635f4c08e6..22bbe72408 100644 --- a/Svc/FramingProtocol/CMakeLists.txt +++ b/Svc/FramingProtocol/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/GenericHub/CMakeLists.txt b/Svc/GenericHub/CMakeLists.txt index a9d80fd76b..c540994354 100644 --- a/Svc/GenericHub/CMakeLists.txt +++ b/Svc/GenericHub/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Svc/GenericHub/docs/GenricHubExampleAppAi.xml b/Svc/GenericHub/docs/GenericHubExampleAppAi.xml similarity index 100% rename from Svc/GenericHub/docs/GenricHubExampleAppAi.xml rename to Svc/GenericHub/docs/GenericHubExampleAppAi.xml diff --git a/Svc/GenericRepeater/docs/GenricRepeaterAppAi.xml b/Svc/GenericRepeater/docs/GenericRepeaterAppAi.xml similarity index 100% rename from Svc/GenericRepeater/docs/GenricRepeaterAppAi.xml rename to Svc/GenericRepeater/docs/GenericRepeaterAppAi.xml diff --git a/Svc/GroundInterface/CMakeLists.txt b/Svc/GroundInterface/CMakeLists.txt index 7a13de6dc7..9ac1f9d0c4 100644 --- a/Svc/GroundInterface/CMakeLists.txt +++ b/Svc/GroundInterface/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Health/CMakeLists.txt b/Svc/Health/CMakeLists.txt index cb38505b8a..85bb36c76b 100644 --- a/Svc/Health/CMakeLists.txt +++ b/Svc/Health/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/LinuxTime/CMakeLists.txt b/Svc/LinuxTime/CMakeLists.txt index 8683ede979..e278ae6ff8 100644 --- a/Svc/LinuxTime/CMakeLists.txt +++ b/Svc/LinuxTime/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/LinuxTimer/CMakeLists.txt b/Svc/LinuxTimer/CMakeLists.txt index 0482ff7500..0b505cfaca 100644 --- a/Svc/LinuxTimer/CMakeLists.txt +++ b/Svc/LinuxTimer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Svc/PassiveConsoleTextLogger/CMakeLists.txt b/Svc/PassiveConsoleTextLogger/CMakeLists.txt index 5a26b4ca69..34587220d7 100644 --- a/Svc/PassiveConsoleTextLogger/CMakeLists.txt +++ b/Svc/PassiveConsoleTextLogger/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Ping/CMakeLists.txt b/Svc/Ping/CMakeLists.txt index f2dd7ceb39..04567a4eaa 100644 --- a/Svc/Ping/CMakeLists.txt +++ b/Svc/Ping/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/PolyDb/CMakeLists.txt b/Svc/PolyDb/CMakeLists.txt index 74fe77f9c6..baf5524e08 100644 --- a/Svc/PolyDb/CMakeLists.txt +++ b/Svc/PolyDb/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/PolyIf/CMakeLists.txt b/Svc/PolyIf/CMakeLists.txt index 3f80a337ef..aa3ea93781 100644 --- a/Svc/PolyIf/CMakeLists.txt +++ b/Svc/PolyIf/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/PrmDb/CMakeLists.txt b/Svc/PrmDb/CMakeLists.txt index 42c616cc3d..2aa37c969c 100644 --- a/Svc/PrmDb/CMakeLists.txt +++ b/Svc/PrmDb/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/RateGroupDriver/CMakeLists.txt b/Svc/RateGroupDriver/CMakeLists.txt index 16a0130e57..d3e4d2eecd 100644 --- a/Svc/RateGroupDriver/CMakeLists.txt +++ b/Svc/RateGroupDriver/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Sched/CMakeLists.txt b/Svc/Sched/CMakeLists.txt index 04a573d268..ead9650f1d 100644 --- a/Svc/Sched/CMakeLists.txt +++ b/Svc/Sched/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Seq/CMakeLists.txt b/Svc/Seq/CMakeLists.txt index 3ad1b159ef..f887794fc1 100644 --- a/Svc/Seq/CMakeLists.txt +++ b/Svc/Seq/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/StaticMemory/CMakeLists.txt b/Svc/StaticMemory/CMakeLists.txt index 0838dfbd76..8b80148bf3 100644 --- a/Svc/StaticMemory/CMakeLists.txt +++ b/Svc/StaticMemory/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/SystemResources/CMakeLists.txt b/Svc/SystemResources/CMakeLists.txt index f7b2e5a07b..f5d65b1c6e 100644 --- a/Svc/SystemResources/CMakeLists.txt +++ b/Svc/SystemResources/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/Time/CMakeLists.txt b/Svc/Time/CMakeLists.txt index f90de3eb46..0241f89c63 100644 --- a/Svc/Time/CMakeLists.txt +++ b/Svc/Time/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/TlmChan/CMakeLists.txt b/Svc/TlmChan/CMakeLists.txt index 09f6fc3bbe..c2c564bcd1 100644 --- a/Svc/TlmChan/CMakeLists.txt +++ b/Svc/TlmChan/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/TlmPacketizer/CMakeLists.txt b/Svc/TlmPacketizer/CMakeLists.txt index 722637c07e..b4162cebd2 100644 --- a/Svc/TlmPacketizer/CMakeLists.txt +++ b/Svc/TlmPacketizer/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Svc/WatchDog/CMakeLists.txt b/Svc/WatchDog/CMakeLists.txt index a5ba4d7ea5..b155117329 100644 --- a/Svc/WatchDog/CMakeLists.txt +++ b/Svc/WatchDog/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # # Note: using PROJECT_NAME as EXECUTABLE_NAME diff --git a/Utils/Hash/CMakeLists.txt b/Utils/Hash/CMakeLists.txt index e58862fa6c..c04cec2859 100644 --- a/Utils/Hash/CMakeLists.txt +++ b/Utils/Hash/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/Utils/Types/CMakeLists.txt b/Utils/Types/CMakeLists.txt index 66051527a8..5e098fb115 100644 --- a/Utils/Types/CMakeLists.txt +++ b/Utils/Types/CMakeLists.txt @@ -1,7 +1,7 @@ #### # F prime CMakeLists.txt: # -# SOURCE_FILES: combined list of source and autocoding diles +# SOURCE_FILES: combined list of source and autocoding files # MOD_DEPS: (optional) module dependencies # #### diff --git a/docs/UsersGuide/dev/testAPI/user_guide.md b/docs/UsersGuide/dev/testAPI/user_guide.md index bedc06666f..e000c3ff6e 100644 --- a/docs/UsersGuide/dev/testAPI/user_guide.md +++ b/docs/UsersGuide/dev/testAPI/user_guide.md @@ -719,7 +719,7 @@ I see two options to address this: ### The openpyxl library has thrown WorkbookAlreadySaved error -While running unit tests on the API, there was an error thrown by openpyxl that caused the log to close early. The behavior wasn't able to be recreated, but the [Test Logger](../../../../Gds/src/fprime_gds/common/logger/test_logger.py) was updated to [catch the exception](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L124) to prevent tests from failing due to the logger. +While running unit tests on the API, there was an error thrown by openpyxl that caused the log to close early. The behavior wasn't able to be recreated, but the [Test Logger](../../../../Gds/src/fprime_gds/common/logger/test_logger.py) was updated to [catch the exception](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L124) to prevent tests from failing due to the logger. ~~~~ ___________________________________ APITestCases.test_find_history_item _________________________________ @@ -790,11 +790,11 @@ To fully resolve this would require being able to reproduce the issue and explai Recommendation for adding a csv logger to the TestLogger class: -1. Set up the csv log file in the constructor [here](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L49). -2. Add a `_log_csv_row()` helper along similar lines to the `_get_ws_row()` helper [here](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L159) -3. Log the start time at the top of the file like the excel output does [here](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L85). -4. Log the column headers to csv like the excel does [here](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L88). -5. Log messages in the lock block [here](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L119). +1. Set up the csv log file in the constructor [here](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L49). +2. Add a `_log_csv_row()` helper along similar lines to the `_get_ws_row()` helper [here](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L159) +3. Log the start time at the top of the file like the excel output does [here](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L85). +4. Log the column headers to csv like the excel does [here](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L88). +5. Log messages in the lock block [here](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/logger/test_logger.py#L119). ## Idiosyncrasies @@ -805,7 +805,7 @@ In this document, idiosyncrasies refer to needed-improvements and future feature ### Timeout implementation -Presently timeouts are using the signal library and throw an exception to end the search. This timeout behavior can be modified very easily by changing the [__search_test_history](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/6cd4c8007a7f562d5b0b616eb494270ac5c7b95d/Gds/src/fprime_gds/common/testing_fw/api.py#L911) method. All searches use this method to accomplish scoping, logging and history substitution. Changing the timeout to something like below would be better. +Presently timeouts are using the signal library and throw an exception to end the search. This timeout behavior can be modified very easily by changing the [__search_test_history](https://github.com/nasa/fprime/blob/6cd4c8007a7f562d5b0b616eb494270ac5c7b95d/Gds/src/fprime_gds/common/testing_fw/api.py#L911) method. All searches use this method to accomplish scoping, logging and history substitution. Changing the timeout to something like below would be better. ~~~~{.python} # in IntegrationTestAPI's __search_test_history method on ~line 912 of api.py @@ -833,13 +833,13 @@ return searcher.get_return_value() In order to properly support ERT ordering, I recommend: -1. Add a TimeType field to the [SysData](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/data_types/sys_data.py#L19) class and add an accessor for `get_ert_time()`. +1. Add a TimeType field to the [SysData](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/data_types/sys_data.py#L19) class and add an accessor for `get_ert_time()`. 2. Have the GDS record ERT at some point. -3. Preserve the use of the `fsw_order` argument in the test API's [constructor](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L29) and [sub-history](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L244) functions by passing the fsw_order argument to the chronological [history constructor](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L23). +3. Preserve the use of the `fsw_order` argument in the test API's [constructor](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L29) and [sub-history](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L244) functions by passing the fsw_order argument to the chronological [history constructor](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L23). 4. Modify chronological history to choose whether to use `get_time()` or `get_ert_time()` for its ordering/returning operations: - - [clearing history](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L111) - - `__insert_chrono()` [helper](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L165) - - `__get_index()` [helper](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L206) + - [clearing history](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L111) + - `__insert_chrono()` [helper](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L165) + - `__get_index()` [helper](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/history/chrono.py#L206) #### Better History Markers @@ -847,11 +847,11 @@ As part of the work to add ERT and have chronological histories work for both ER ### Color-coding interlaced Events in the API Log -One feature that wasn't completed this summer was to color-code interlaced event logs based on severity. Presently, interlacing events are implemented by making the API a consumer of the event decoder in the GDS and then filtering events. Modifying the color of these log messages can be done [here](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L1258). +One feature that wasn't completed this summer was to color-code interlaced event logs based on severity. Presently, interlacing events are implemented by making the API a consumer of the event decoder in the GDS and then filtering events. Modifying the color of these log messages can be done [here](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L1258). ### Moving StandardPipeline to API constructor -Presently, a user of the integration test API needs to instantiate the GDS manually before instantiating the API. This code should really be moved to inside the API. To do this, the IntegrationTestAPI's [constructor](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/d0309a9e265b8650ca6be03b9132dfdc682e0622/Gds/src/fprime_gds/common/testing_fw/api.py#L27) should be modified to include the pipeline instantiation and the API's [teardown](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/d0309a9e265b8650ca6be03b9132dfdc682e0622/Gds/src/fprime_gds/common/testing_fw/api.py#L64) method should be modified to disconnect from the F Prime deployment. +Presently, a user of the integration test API needs to instantiate the GDS manually before instantiating the API. This code should really be moved to inside the API. To do this, the IntegrationTestAPI's [constructor](https://github.com/nasa/fprime/blob/d0309a9e265b8650ca6be03b9132dfdc682e0622/Gds/src/fprime_gds/common/testing_fw/api.py#L27) should be modified to include the pipeline instantiation and the API's [teardown](https://github.com/nasa/fprime/blob/d0309a9e265b8650ca6be03b9132dfdc682e0622/Gds/src/fprime_gds/common/testing_fw/api.py#L64) method should be modified to disconnect from the F Prime deployment. #### Modification to the Integration Test API @@ -912,7 +912,7 @@ Currently the StandardPipeline (GDS Helper layer) uses a path to a directory to ### Better test identifiers using decorators -When a new test case [is started](https://github.jpl.nasa.gov/FPRIME/fprime-sw/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L85), the API user can specify a `case_id` that will be used in the logs to identify the current test case without scrolling to the test case header. Future uses of the API should investigate using decorators to specify an ID to put in this column. Present tests just use a counter and assign a number to each test case. +When a new test case [is started](https://github.com/nasa/fprime/blob/717bc6fab85c53680108fc961cad6338e779816f/Gds/src/fprime_gds/common/testing_fw/api.py#L85), the API user can specify a `case_id` that will be used in the logs to identify the current test case without scrolling to the test case header. Future uses of the API should investigate using decorators to specify an ID to put in this column. Present tests just use a counter and assign a number to each test case. ### GDS command arguments should allow non-string types From 0ffaaf0c89309543d2cfcdd37b425fd0143774d1 Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Tue, 6 Dec 2022 19:29:19 +0100 Subject: [PATCH 106/169] Add Cppcheck Static Code Analysis to CI Workflow (#1782) * Add cppcheck scan workflow to Actions * Improve step names * Spell check * Consider only `error` severity on CppCheck CI report * Use relative paths in CppCheck output * Modify Cppcheck trigger policy * Add comment about cppcheck Scan CI failure * Add newline at end of spellcheck expect * Typo GitHub * Try fixing spellcheck w/ cppcheck issue --- .github/actions/spelling/expect.txt | 6 +++ .github/scripts/cppcheck-xml2text.xslt | 17 +++++++ .github/workflows/cppcheck-scan.yml | 68 ++++++++++++++++++++++++++ 3 files changed, 91 insertions(+) create mode 100644 .github/scripts/cppcheck-xml2text.xslt create mode 100644 .github/workflows/cppcheck-scan.yml diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index bf0cd57c9a..7bd0eb1a42 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -234,6 +234,7 @@ Cpkt cplusplus CPOL cpos +cppcheck cppreference cprogramming cpuset @@ -272,6 +273,7 @@ culates curdir curmsgs cuz +ctu cwd CYCLEOUT cygwin @@ -879,6 +881,7 @@ multiarch multioptionals multirequired multline +multitool munmap mutex mutexattr @@ -934,6 +937,7 @@ NOTYPE Nowicki npm nproc +npx NSHUFF NSPACES nukenewlines @@ -1356,6 +1360,7 @@ subpage subseconds subtargets sudo +suppr SVCLOGFILE SVCLOGFILEL svipc @@ -1630,6 +1635,7 @@ xon xor XPath xsh +xsltproc xxxx XYZZY yacc diff --git a/.github/scripts/cppcheck-xml2text.xslt b/.github/scripts/cppcheck-xml2text.xslt new file mode 100644 index 0000000000..808d5ad0a7 --- /dev/null +++ b/.github/scripts/cppcheck-xml2text.xslt @@ -0,0 +1,17 @@ + + + +## CppCheck Summary + +| error | warning | style | performance | portability | information | +| --- | --- | --- | --- | --- | --- | +| | | | | | | + +| severity | location | error id | issue | +| --- | --- | --- | --- | +| | : | | | + + +** error(s) reported** + + diff --git a/.github/workflows/cppcheck-scan.yml b/.github/workflows/cppcheck-scan.yml new file mode 100644 index 0000000000..a6d6361d25 --- /dev/null +++ b/.github/workflows/cppcheck-scan.yml @@ -0,0 +1,68 @@ +# Adapted from https://github.com/nasa/cFS/blob/c36aa2c1df0fb47a3838577908af3d0d0ab0ef54/.github/workflows/static-analysis.yml +name: "Cppcheck Scan" + +on: + push: + branches: [ master, devel ] + pull_request: + # The branches below must be a subset of the branches above + branches: [ master, devel ] + + +jobs: + cppcheck: + name: Cppcheck + runs-on: ubuntu-latest + permissions: + actions: read + contents: read + security-events: write + + steps: + - name: "Checkout F´ Repository" + uses: actions/checkout@v3 + with: + fetch-depth: 0 + - uses: ./.github/actions/setup + + - name: Install cppcheck + run: sudo apt-get install cppcheck xsltproc -y + + - name: Install sarif tool + run: npm install @microsoft/sarif-multitool + + # With a CMake-based project, we get the list of files by setting up a build with CMAKE_EXPORT_COMPILE_COMMANDS=ON and + # referencing the compile_commands.json file produced by the tool. This will capture the correct include paths and + # compile definitions based on how the source is actually compiled. See https://cppcheck.sourceforge.io/manual.html + - name: Generate & build F´ + run: | + fprime-util generate -DCMAKE_EXPORT_COMPILE_COMMANDS=ON + fprime-util build --all --jobs "$(nproc || printf '%s\n' 1)" + echo CPPCHECK_OPTS=--project="$GITHUB_WORKSPACE/build-fprime-automatic-native/compile_commands.json" >> $GITHUB_ENV + + - name: Run cppcheck + run: cppcheck --force --relative-paths=$(pwd) --inline-suppr --std=c++11 -j "$(nproc || printf '%s\n' 1)" --max-ctu-depth=16 --enable=warning,performance,portability --suppress=variableScope --inconclusive --xml $CPPCHECK_OPTS 2> cppcheck_err.xml + + - name: Convert cppcheck results to SARIF + run: npx "@microsoft/sarif-multitool" convert "cppcheck_err.xml" --tool "CppCheck" --output "cppcheck_err.sarif" --force + + - name: Convert cppcheck results to Markdown & Integrate them in the workflow summary + run: xsltproc .github/scripts/cppcheck-xml2text.xslt cppcheck_err.xml | tee $GITHUB_STEP_SUMMARY cppcheck_err.txt + + - name: Upload SARIF file to GitHub Code Scanning Alerts + uses: github/codeql-action/upload-sarif@v2 + with: + sarif_file: ${{ github.workspace }}/cppcheck_err.sarif + checkout_path: ${{ github.workspace }}/source + category: "cppcheck" + + - name: Archive static analysis artifacts to download and view + uses: actions/upload-artifact@v3 + with: + name: cppcheck-errors + path: ./*cppcheck_err.* + + # Make the whole step fail if there is an error detected by cppcheck. By default, GitHub Actions enables the set -e. + # See https://stackoverflow.com/questions/73066461/github-actions-why-an-intermediate-command-failure-in-shell-script-would-cause. + - name: Check for reported errors + run: tail -n 1 cppcheck_err.txt | grep -q '^\*\*0 error(s) reported\*\*$' \ No newline at end of file From d99507b49cead8652dc16ab1f1895575a67a852e Mon Sep 17 00:00:00 2001 From: M Starch Date: Wed, 7 Dec 2022 11:32:38 -0800 Subject: [PATCH 107/169] fixes old autocoder printf types to newly setup types (#1799) * fixes old autocoder printf types to newly setup types * revert inappropriate status print * fixing the variable types for the new printing * changing back to platform int type --- .../generators/templates/component/cpp.tmpl | 12 ++++++------ .../fprime_ac/generators/templates/test/cpp.tmpl | 14 +++++++------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl index 0974c86792..56e4a59f0d 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/component/cpp.tmpl @@ -430,8 +430,8 @@ namespace ${namespace} { #for $instance, $type, $sync, $priority, $full, $role, $max_num in $input_ports: // Connect input port $instance for ( - NATIVE_INT_TYPE port = 0; - port < this->getNum_${instance}_InputPorts(); + PlatformIntType port = 0; + port < static_cast(this->getNum_${instance}_InputPorts()); port++ ) { @@ -447,7 +447,7 @@ namespace ${namespace} { (void) snprintf( portName, sizeof(portName), - "%s_${instance}_InputPort[%d]", + "%s_${instance}_InputPort[%" PRI_PlatformIntType "]", this->m_objName, port ); @@ -463,8 +463,8 @@ namespace ${namespace} { \#if FW_ENABLE_TEXT_LOGGING == 1 #end if for ( - NATIVE_INT_TYPE port = 0; - port < this->getNum_${instance}_OutputPorts(); + PlatformIntType port = 0; + port < static_cast(this->getNum_${instance}_OutputPorts()); port++ ) { this->m_${instance}_OutputPort[port].init(); @@ -474,7 +474,7 @@ namespace ${namespace} { (void) snprintf( portName, sizeof(portName), - "%s_${instance}_OutputPort[%d]", + "%s_${instance}_OutputPort[%" PRI_PlatformIntType "]", this->m_objName, port ); diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl index a148bbfa0b..0a0c90b812 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl @@ -121,8 +121,8 @@ $emit_cpp_params([ $param_instance ]) \#if FW_ENABLE_TEXT_LOGGING == 1 #end if for ( - NATIVE_INT_TYPE _port = 0; - _port < this->getNum_from_${instance}(); + PlatformIntType _port = 0; + _port < static_cast(this->getNum_from_${instance}()); ++_port ) { @@ -139,7 +139,7 @@ $emit_cpp_params([ $param_instance ]) (void) snprintf( _portName, sizeof(_portName), - "%s_${port_name}[%d]", + "%s_${port_name}[%" PRI_PlatformIntType "]", this->m_objName, _port ); @@ -157,8 +157,8 @@ $emit_cpp_params([ $param_instance ]) // Initialize output port $instance for ( - NATIVE_INT_TYPE _port = 0; - _port < this->getNum_to_${instance}(); + PlatformIntType _port = 0; + _port < static_cast(this->getNum_to_${instance}()); ++_port ) { this->m_to_${instance}[_port].init(); @@ -168,7 +168,7 @@ $emit_cpp_params([ $param_instance ]) snprintf( _portName, sizeof(_portName), - "%s_to_${instance}[%d]", + "%s_to_${instance}[%" PRI_PlatformIntType "]", this->m_objName, _port ); @@ -1114,7 +1114,7 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) fprintf( file, - "EVENT: (%d) (%d:%d,%d) %s: %s\n", + "EVENT: (%" PRI_FwEventIdType ") (%" PRI_FwTimeBaseStoreType ":%" PRIu32 ",%" PRIu32 ") %s: %s\n", e.id, const_cast(e).timeTag.getTimeBase(), const_cast(e).timeTag.getSeconds(), From e7715efde76769c05a051126c59f8139354c81c1 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Wed, 7 Dec 2022 11:51:17 -0800 Subject: [PATCH 108/169] Automatically compute bounds for configurable integer types (#1800) * Revise F Prime configuration limits Use a macro to auto-generate the limits from the underlying configurations. This way each manual configuration happens once. * Add limits header to FpConfig.hpp --- config/FpConfig.hpp | 49 ++++++++++++++++++--------------------------- 1 file changed, 19 insertions(+), 30 deletions(-) diff --git a/config/FpConfig.hpp b/config/FpConfig.hpp index 0924ecc618..5eb8201d17 100644 --- a/config/FpConfig.hpp +++ b/config/FpConfig.hpp @@ -12,6 +12,7 @@ #ifndef _FW_CONFIG_HPP_ #define _FW_CONFIG_HPP_ #include +#include typedef PlatformIndexType FwIndexType; #define PRI_FwIndexType PRI_PlatformIndexType @@ -77,37 +78,25 @@ typedef U16 FwTlmPacketizeIdType; * includes the limits included within those files. * **/ +#define FP_CONFIG_NUMERIC_LIMITS(T) \ + static const T T##_MIN = std::numeric_limits::min(); \ + static const T T##_MAX = std::numeric_limits::max(); struct FpLimits : BasicLimits { - static const FwIndexType FwIndexType_MIN = PlatformIndexType_MIN; - static const FwIndexType FwIndexType_MAX = PlatformIndexType_MAX; - static const FwSizeType FwSizeType_MIN = PlatformSizeType_MIN; - static const FwSizeType FwSizeType_MAX = PlatformSizeType_MAX; - static const FwAssertArgType FwAssertArgType_MIN = PlatformAssertArgType_MIN; - static const FwAssertArgType FwAssertArgType_MAX = PlatformAssertArgType_MAX; - static const FwNativeIntType FwNativeIntType_MIN = PlatformIntType_MIN; - static const FwNativeIntType FwNativeIntType_MAX = PlatformIntType_MAX; - static const FwNativeUIntType FwNativeUIntType_MIN = PlatformUIntType_MIN; - static const FwNativeUIntType FwNativeUIntType_MAX = PlatformUIntType_MAX; - static const FwBuffSizeType FwBuffSizeType_MIN = U16_MIN; - static const FwBuffSizeType FwBuffSizeType_MAX = U16_MAX; - static const FwEnumStoreType FwEnumStoreType_MIN = I32_MIN; - static const FwEnumStoreType FwEnumStoreType_MAX = I32_MAX; - static const FwTimeBaseStoreType FwTimeBaseStoreType_MIN = U16_MIN; - static const FwTimeBaseStoreType FwTimeBaseStoreType_MAX = U16_MAX; - static const FwTimeContextStoreType FwTimeContextStoreType_MIN = U8_MIN; - static const FwTimeContextStoreType FwTimeContextStoreType_MAX = U8_MAX; - static const FwPacketDescriptorType FwPacketDescriptorType_MIN = U32_MIN; - static const FwPacketDescriptorType FwPacketDescriptorType_MAX = U32_MAX; - static const FwOpcodeType FwOpcodeType_MIN = U32_MIN; - static const FwOpcodeType FwOpcodeType_MAX = U32_MAX; - static const FwChanIdType FwChanIdType_MIN = U32_MIN; - static const FwChanIdType FwChanIdType_MAX = U32_MAX; - static const FwEventIdType FwEventIdType_MIN = U32_MIN; - static const FwEventIdType FwEventIdType_MAX = U32_MAX; - static const FwPrmIdType FwPrmIdType_MIN = U32_MIN; - static const FwPrmIdType FwPrmIdType_MAX = U32_MAX; - static const FwTlmPacketizeIdType FwTlmPacketizeIdType_MIN = U16_MIN; - static const FwTlmPacketizeIdType FwTlmPacketizeIdType_MAX = U16_MAX; + FP_CONFIG_NUMERIC_LIMITS(FwAssertArgType) + FP_CONFIG_NUMERIC_LIMITS(FwBuffSizeType) + FP_CONFIG_NUMERIC_LIMITS(FwChanIdType) + FP_CONFIG_NUMERIC_LIMITS(FwEnumStoreType) + FP_CONFIG_NUMERIC_LIMITS(FwEventIdType) + FP_CONFIG_NUMERIC_LIMITS(FwIndexType) + FP_CONFIG_NUMERIC_LIMITS(FwNativeIntType) + FP_CONFIG_NUMERIC_LIMITS(FwNativeUIntType) + FP_CONFIG_NUMERIC_LIMITS(FwOpcodeType) + FP_CONFIG_NUMERIC_LIMITS(FwPacketDescriptorType) + FP_CONFIG_NUMERIC_LIMITS(FwPrmIdType) + FP_CONFIG_NUMERIC_LIMITS(FwSizeType) + FP_CONFIG_NUMERIC_LIMITS(FwTimeBaseStoreType) + FP_CONFIG_NUMERIC_LIMITS(FwTimeContextStoreType) + FP_CONFIG_NUMERIC_LIMITS(FwTlmPacketizeIdType) }; // Boolean values for serialization From f10c96a04953fd1102a473f12d3e43ce196900e9 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Thu, 8 Dec 2022 10:44:34 -0800 Subject: [PATCH 109/169] Revise Linux platform types (#1803) * Revise Linux platform types * Fix regression in test autocoder TimeBaseStoreType is not the same as TimeBase * Revise test autocoder Cast to the TimeBaseStore type with a known size * Revise test autocoder Remove unnecessary const casting * Fix integer type mismatch in ComQueue --- .../generators/templates/test/cpp.tmpl | 6 +-- Svc/ComQueue/ComQueue.cpp | 2 +- cmake/platform/types/PlatformTypes.hpp | 46 ++++++------------- 3 files changed, 17 insertions(+), 37 deletions(-) diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl index 0a0c90b812..6345cfcd2a 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test/cpp.tmpl @@ -1116,9 +1116,9 @@ $emit_cpp_params([ $param_const_timeTag, $param_val ]) file, "EVENT: (%" PRI_FwEventIdType ") (%" PRI_FwTimeBaseStoreType ":%" PRIu32 ",%" PRIu32 ") %s: %s\n", e.id, - const_cast(e).timeTag.getTimeBase(), - const_cast(e).timeTag.getSeconds(), - const_cast(e).timeTag.getUSeconds(), + static_cast(e.timeTag.getTimeBase()), + e.timeTag.getSeconds(), + e.timeTag.getUSeconds(), severityString, e.text.toChar() ); diff --git a/Svc/ComQueue/ComQueue.cpp b/Svc/ComQueue/ComQueue.cpp index 41038ad1e2..7ddf34f3a2 100644 --- a/Svc/ComQueue/ComQueue.cpp +++ b/Svc/ComQueue/ComQueue.cpp @@ -50,7 +50,7 @@ void ComQueue::configure(QueueConfigurationTable queueConfig, NATIVE_UINT_TYPE allocationId, Fw::MemAllocator& allocator) { FwIndexType currentPriorityIndex = 0; - FwSizeType totalAllocation = 0; + NATIVE_UINT_TYPE totalAllocation = 0; // Store/initialize allocator members this->m_allocator = &allocator; diff --git a/cmake/platform/types/PlatformTypes.hpp b/cmake/platform/types/PlatformTypes.hpp index cc120cfdf7..a5b9fe064d 100644 --- a/cmake/platform/types/PlatformTypes.hpp +++ b/cmake/platform/types/PlatformTypes.hpp @@ -71,7 +71,7 @@ typedef PlatformIntType PlatformAssertArgType; #error "Compiler does not support __SIZEOF_POINTER__, cannot use Linux/Darwin types" #endif - // Pointer sizes are determined by size of compiler + // Pointer sizes are determined by compiler #if __SIZEOF_POINTER__ == 8 typedef uint64_t PlatformPointerCastType; #define PRI_PlatformPointerCastType PRIx64 @@ -81,9 +81,11 @@ typedef PlatformIntType PlatformAssertArgType; #elif __SIZEOF_POINTER__ == 2 typedef uint16_t PlatformPointerCastType; #define PRI_PlatformPointerCastType PRIx16 - #else + #elif __SIZEOF_POINTER__ == 1 typedef uint8_t PlatformPointerCastType; #define PRI_PlatformPointerCastType PRIx8 + #else + #error "Expected __SIZEOF_POINTER__ to be one of 8, 4, 2, or 1" #endif #endif /** @@ -93,37 +95,15 @@ typedef PlatformIntType PlatformAssertArgType; * within this file. These must be defined as `static const` members to * ensure that unnecessary storage is not allocated. */ +#define FP_PLATFORM_NUMERIC_LIMITS(T) \ + static const T T##_MIN = std::numeric_limits::min(); \ + static const T T##_MAX = std::numeric_limits::max(); struct PlatformLimits { - static const PlatformIntType PlatformIntType_MIN = std::numeric_limits::min(); - static const PlatformIntType PlatformIntType_MAX = std::numeric_limits::max(); - - static const PlatformUIntType PlatformUIntType_MIN = std::numeric_limits::min(); - static const PlatformUIntType PlatformUIntType_MAX = std::numeric_limits::max(); - - static const PlatformIndexType PlatformIndexType_MIN = PlatformIntType_MIN; - static const PlatformIndexType PlatformIndexType_MAX = PlatformIntType_MAX; - - static const PlatformSizeType PlatformSizeType_MIN = PlatformUIntType_MIN; - static const PlatformSizeType PlatformSizeType_MAX = PlatformUIntType_MAX; - - static const PlatformAssertArgType PlatformAssertArgType_MIN = PlatformIntType_MIN; - static const PlatformAssertArgType PlatformAssertArgType_MAX = PlatformIntType_MAX; - - // Pointer sizes are determined by size of compiler - #if __SIZEOF_POINTER__ == 8 - static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); - static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); - #elif __SIZEOF_POINTER__ == 4 - static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); - static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); - #elif __SIZEOF_POINTER__ == 2 - static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); - static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); - #elif __SIZEOF_POINTER__ == 1 - static const PlatformPointerCastType PlatformPointerCastType_MIN = std::numeric_limits::min(); - static const PlatformPointerCastType PlatformPointerCastType_MAX = std::numeric_limits::max(); - #else - #error "Unsupported pointer size" - #endif + FP_PLATFORM_NUMERIC_LIMITS(PlatformAssertArgType) + FP_PLATFORM_NUMERIC_LIMITS(PlatformIndexType) + FP_PLATFORM_NUMERIC_LIMITS(PlatformIntType) + FP_PLATFORM_NUMERIC_LIMITS(PlatformPointerCastType) + FP_PLATFORM_NUMERIC_LIMITS(PlatformSizeType) + FP_PLATFORM_NUMERIC_LIMITS(PlatformUIntType) }; #endif //PLATFORM_TYPES_HPP_ From ee44a890b39fc58bdaa5e29772f7a94f766e83c2 Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Thu, 8 Dec 2022 19:45:15 +0100 Subject: [PATCH 110/169] Update Github Actions to run on Node 16 instead of Node 12 - Bump to @v3 (#1804) * Switch `actions/checkout` from `v2` to `v3` * Switch `actions/upload-artifact` from `v2` to `v3` * Switch `actions/download-artifact` from `v2` to `v3` --- .github/workflows/autodocs.yml | 2 +- .github/workflows/build-test-macos.yml | 12 ++++++------ .github/workflows/build-test-rpi.yml | 10 +++++----- .github/workflows/build-test.yml | 16 ++++++++-------- .github/workflows/python-format.yml | 2 +- 5 files changed, 21 insertions(+), 21 deletions(-) diff --git a/.github/workflows/autodocs.yml b/.github/workflows/autodocs.yml index 4db1b4b4c3..977e7cb8f5 100644 --- a/.github/workflows/autodocs.yml +++ b/.github/workflows/autodocs.yml @@ -10,7 +10,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup diff --git a/.github/workflows/build-test-macos.yml b/.github/workflows/build-test-macos.yml index 352096ff2d..2de9038f70 100644 --- a/.github/workflows/build-test-macos.yml +++ b/.github/workflows/build-test-macos.yml @@ -16,7 +16,7 @@ jobs: runs-on: macos-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -24,7 +24,7 @@ jobs: run: ./ci/tests/Framework.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: ci-framework-logs @@ -35,7 +35,7 @@ jobs: runs-on: macos-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -43,7 +43,7 @@ jobs: run: ./ci/tests/Ref.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: ci-ref-logs @@ -54,7 +54,7 @@ jobs: runs-on: macos-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -64,7 +64,7 @@ jobs: run: ./ci/tests/30-ints.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: ci-int-logs diff --git a/.github/workflows/build-test-rpi.yml b/.github/workflows/build-test-rpi.yml index f1763f9c08..e4441c812c 100644 --- a/.github/workflows/build-test-rpi.yml +++ b/.github/workflows/build-test-rpi.yml @@ -16,7 +16,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -28,14 +28,14 @@ jobs: run: mkdir -p artifact/RPI; cp -rp RPI/test RPI/build-artifacts artifact/RPI; cp -rp ci artifact # Build Artifacts - name: 'RPI Build Output' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 with: name: rpi-build path: artifact retention-days: 5 # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: rpi-logs @@ -47,14 +47,14 @@ jobs: needs: RPI steps: - name: RPI Build Download - uses: actions/download-artifact@v2 + uses: actions/download-artifact@v3 with: name: rpi-build - name: RPI Integration Tests run: chmod +x RPI/build-artifacts/raspberrypi/bin/RPI; /bin/bash ci/tests/RPI-Ints.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: pi-int-logs diff --git a/.github/workflows/build-test.yml b/.github/workflows/build-test.yml index cb10277d45..ce0a7f1554 100644 --- a/.github/workflows/build-test.yml +++ b/.github/workflows/build-test.yml @@ -16,7 +16,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -24,7 +24,7 @@ jobs: run: ./ci/tests/Framework.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: ci-framework-logs @@ -35,7 +35,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -43,7 +43,7 @@ jobs: run: ./ci/tests/Ref.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: ci-ref-logs @@ -54,7 +54,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -66,7 +66,7 @@ jobs: run: ./ci/tests/30-ints.bash # Archive the outputs - name: 'Archive Logs' - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 if: always() with: name: ci-int-logs @@ -77,7 +77,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup @@ -99,7 +99,7 @@ jobs: runs-on: ubuntu-latest steps: - name: "Checkout F´ Repository" - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 - uses: ./.github/actions/setup diff --git a/.github/workflows/python-format.yml b/.github/workflows/python-format.yml index 06ec37189a..742fb3930f 100644 --- a/.github/workflows/python-format.yml +++ b/.github/workflows/python-format.yml @@ -6,7 +6,7 @@ jobs: name: Format runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Setup Python 3.7 uses: actions/setup-python@v2 with: From be8a79c7181356364273cb1a7e519b5198dcad84 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Mon, 19 Dec 2022 10:56:30 -0800 Subject: [PATCH 111/169] Add built-in types to FPP model (#1812) * Revise Linux platform types * Fix regression in test autocoder TimeBaseStoreType is not the same as TimeBase * Revise test autocoder Cast to the TimeBaseStore type with a known size * Revise test autocoder Remove unnecessary const casting * Fix integer type mismatch in ComQueue * Add built-in types * Add new built-in types to Python code generator * Revert data product built-in types for now * Add trailing commas --- .../src/fprime_ac/generators/visitors/PortHVisitor.py | 10 +++++++++- Autocoders/Python/src/fprime_ac/utils/TypesList.py | 11 ++++++++++- config/FpConfig.fpp | 10 +++++++++- 3 files changed, 28 insertions(+), 3 deletions(-) diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py index 8506e2f816..bb9cd72f24 100644 --- a/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/PortHVisitor.py @@ -176,10 +176,18 @@ def _get_args_sum_string(self, obj): "F32", "F64", "bool", - "FwOpcodeType", + "FwBuffSizeType", "FwChanIdType", + "FwEnumStoreType", "FwEventIdType", + "FwIndexType", + "FwOpcodeType", + "FwPacketDescriptorType", "FwPrmIdType", + "FwSizeType", + "FwTimeBaseStoreType", + "FwTimeContextStoreType", + "FwTlmPacketizeIdType", "NATIVE_INT_TYPE", "NATIVE_UINT_TYPE", "POINTER_CAST", diff --git a/Autocoders/Python/src/fprime_ac/utils/TypesList.py b/Autocoders/Python/src/fprime_ac/utils/TypesList.py index d8a58e8208..914dc52399 100644 --- a/Autocoders/Python/src/fprime_ac/utils/TypesList.py +++ b/Autocoders/Python/src/fprime_ac/utils/TypesList.py @@ -16,12 +16,21 @@ # additional types allowed in ports port_types_list = [ - "FwOpcodeType", + "FwBuffSizeType", "FwChanIdType", + "FwEnumStoreType", "FwEventIdType", + "FwIndexType", + "FwOpcodeType", + "FwPacketDescriptorType", "FwPrmIdType", + "FwSizeType", + "FwTimeBaseStoreType", + "FwTimeContextStoreType", + "FwTlmPacketizeIdType", "NATIVE_INT_TYPE", "NATIVE_UINT_TYPE", + "POINTER_CAST", ] diff --git a/config/FpConfig.fpp b/config/FpConfig.fpp index 2f6a848e77..5341ba661b 100644 --- a/config/FpConfig.fpp +++ b/config/FpConfig.fpp @@ -1,7 +1,15 @@ -type FwEventIdType +type FwBuffSizeType type FwChanIdType +type FwEnumStoreType +type FwEventIdType +type FwIndexType type FwOpcodeType +type FwPacketDescriptorType type FwPrmIdType +type FwSizeType +type FwTimeBaseStoreType +type FwTimeContextStoreType +type FwTlmPacketizeIdType type NATIVE_INT_TYPE type NATIVE_UINT_TYPE type POINTER_CAST From 64d08b7f001ab46a5c213d91139390ec49a7ef25 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Mon, 19 Dec 2022 10:58:47 -0800 Subject: [PATCH 112/169] Fixes to math component tutorial Markdown (#1802) * Revise math tutorial Migrate manual changes in generated code back into source * Revise Math tutorial md * Revise Math tutorial md * Revise Math tutorial md * Revise Math tutorial MD * Revise Math component md * Revise math component tutorial md * Revise math component tutorial md * Revise math component tutorial md * Regenerate math component tutorial md * Revise math component tutorial md * Revise math component tutorial md --- docs/Tutorials/MathComponent/Tutorial.md | 105 ++++++--------- docs/Tutorials/MathComponent/md/Tutorial.md | 135 ++++++++++---------- 2 files changed, 112 insertions(+), 128 deletions(-) diff --git a/docs/Tutorials/MathComponent/Tutorial.md b/docs/Tutorials/MathComponent/Tutorial.md index 2543bf6a21..cf735ac809 100644 --- a/docs/Tutorials/MathComponent/Tutorial.md +++ b/docs/Tutorials/MathComponent/Tutorial.md @@ -585,14 +585,14 @@ After the second command, the build system should run for a bit. At the end there should be two new files in the directory: -`MathSenderComponentImpl.cpp-template` and -`MathSenderComponentImpl.hpp-template`. +`MathSender.cpp-template` and +`MathSender.hpp-template`. Run the following commands: ```bash -mv MathSenderComponentImpl.cpp-template MathSender.cpp -mv MathSenderComponentImpl.hpp-template MathSender.hpp +mv MathSender.cpp-template MathSender.cpp +mv MathSender.hpp-template MathSender.hpp ``` These commands produce a template, or stub implementation, @@ -751,12 +751,11 @@ in three steps: #### 4.5.1. Set Up the Unit Test Environment **Create the stub Tester class:** -Do the following in directory `Ref/MathSender`: - -1. Run `mkdir -p test/ut` to create the directory where +In the directory `Ref/MathSender`, run `mkdir -p test/ut`. +This will create the directory where the unit tests will reside. -2. Update Ref/MathSender/CMakeLists.txt: +**Update Ref/MathSender/CMakeLists.txt:** Go back to the directory `Ref/MathSender`. Add the following lines to `CMakeLists.txt`: @@ -768,66 +767,47 @@ set(UT_SOURCE_FILES register_fprime_ut() ``` -This code tells the build system how to build -and run the unit tests. - -4. Run `fprime-util generate --ut` to generate the unit test cache. - -5. Run the command `fprime-util impl --ut`. -It should generate files `Tester.cpp` and `Tester.hpp`. +**Generate the unit test stub:** +We will now generate a stub implementation of the unit tests. +This stub contains all the boilerplate necessary to write and +run unit tests against the `MathSender` component. +In a later step, we will fill in the stub with tests. -6. Move these files to the `test/ut` directory: - -```bash -mv Tester.* test/ut -``` - -**Create a stub main.cpp file:** -Now go to the directory `Ref/MathSender/test/ut`. -In that directory, create the file `main.cpp` and add the following contents: +1. If you have not yet run `fprime-util generate --ut`, + then do so now. This step generates the CMake build cache for the unit + tests. -```c++ -#include "Tester.hpp" +1. Run the command `fprime-util impl --ut`. + It should generate files `Tester.cpp`, `Tester.hpp`, and `TestMain.cpp`. -int main(int argc, char **argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} -``` +1. Move these files to the `test/ut` directory: -This file is a stub for running tests using the -[Google Test framework](https://github.com/google/googletest). -Right now there aren't any tests to run; we will add one -in the next section. + ```bash + mv Tester.* TestMain.cpp test/ut + ``` -7. Add the new files to the build. +**Update Ref/MathSender/CMakeLists.txt:** +Open `MathSender/CMakeLists.txt` and update the definition of +`UT_SOURCE_FILES` by adding your new test files: -Open `MathSender/CMakeLists.txt` and modify the `UT_SOURCE_FILES` by adding -your new test files: ```cmake # Register the unit test build set(UT_SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/MathSender.fpp" - "${CMAKE_CURRENT_LIST_DIR}/test/ut/main.cpp" "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/main.cpp" ) register_fprime_ut() ``` **Run the build:** Now we can check that the unit test build is working. - -1. If you have not yet run `fprime-util generate --ut`, -then do so now. -This step generates the CMake build cache for the unit -tests. - -1. Run `fprime-util build --ut`. +Run `fprime-util build --ut`. Everything should build without errors. **Inspect the generated code:** -The generated code is located at -`Ref/build-fprime-automatic-native-ut/Ref/MathSender`. +The unit test build generates some code to support unit testing. +The code is located at `Ref/build-fprime-automatic-native-ut/Ref/MathSender`. This directory contains two auto-generated classes: 1. `MathSenderGTestBase`: This is the direct base @@ -1052,8 +1032,7 @@ the tests pass. Add a test for exercising the scenario in which the `MathReceiver` component sends a result back to `MathSender`. -1. Add the following function signature in the "Tests" - section of to `Tester.hpp`: +1. Add the following function signature in the "Tests" section of `Tester.hpp`: ```c++ //! Test receipt of a result @@ -1543,7 +1522,7 @@ of the function. Here we do the following: 1. If the parameter identifier is `PARAMID_FACTOR` (the parameter -identifier corresponding to the `FACTOR` parameter, +identifier corresponding to the `FACTOR` parameter), then get the parameter value and emit an event report. 1. Otherwise fail an assertion. @@ -1825,13 +1804,13 @@ This test is the same as the SUB test, except that it uses DIV instead of SUB. **Write a throttle test:** -Add the following to the top of the `Tester.cpp` file: +Add the following constant definition to the top of the `Tester.cpp` file: ```C++ #define CMD_SEQ 42 ``` -Add the following function to the "Tests" section of `Tester.cpp`: +Then add the following function to the "Tests" section of `Tester.cpp`: ```c++ void Tester :: @@ -1975,8 +1954,8 @@ add the following lines: ```fpp instance mathSender: Ref.MathSender base id 0xE00 \ - queue size Default.queueSize \ - stack size Default.stackSize \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ priority 100 ``` @@ -2001,7 +1980,7 @@ add the following lines: ```fpp instance mathReceiver: Ref.MathReceiver base id 0x2700 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE ``` This code defines an instance `mathReceiver` of @@ -2051,20 +2030,18 @@ Those ports will include the ports for the new instances Find the line that starts `connections RateGroups`. This is the beginning of the definition of the `RateGroups` connection graph. -After the last entry for the `rateGroup1Comp` (rate group 1) add the line: +After the last entry for the `rateGroup1Comp` (rate group 1) add +the following line: + ```fpp -rateGroup1Comp.RateGroupMemberOut[5] -> mathReceiver.schedIn +rateGroup1Comp.RateGroupMemberOut -> mathReceiver.schedIn ``` -> You might need to change the array index 5 to be one greater than the previous -`rateGroup1Comp` index. Otherwise you'll get a duplicate connection error. - This line adds the connection that drives the `schedIn` port of the `mathReceiver` component instance. **Re-run the check for unconnected ports:** -When this capability exists, you will be able to see -that `mathReceiver.schedIn` is now connected +You should see that `mathReceiver.schedIn` is now connected (it no longer appears in the list). **Add the Math connections:** @@ -2308,7 +2285,7 @@ Select the log you wish to inspect from the drop-down menu. By default, there is no log selected. -### 8. Conclusion +## 8. Conclusion The Math Component tutorial has shown us how to create simple types, ports and components for our application using the FPP modeling language. We have learned diff --git a/docs/Tutorials/MathComponent/md/Tutorial.md b/docs/Tutorials/MathComponent/md/Tutorial.md index 97c161b4b9..f2fc52daaa 100644 --- a/docs/Tutorials/MathComponent/md/Tutorial.md +++ b/docs/Tutorials/MathComponent/md/Tutorial.md @@ -51,15 +51,13 @@ in the [F Prime git repository](https://github.com/nasa/fprime). You may also wish to work through the Getting Started tutorial at `docs/GettingStarted/Tutorial.md`. -**Git branch:** This tutorial is designed to work on the branch `release/v3.0.0`. - -Working on this tutorial will modify some files under version control in the -F Prime git repository. +**Version control:** +Working on this tutorial will modify some files under version control +in the F Prime git repository. Therefore it is a good idea to do this work on a new branch. For example: ```bash -git checkout release/v3.0.0 git checkout -b math-tutorial ``` @@ -394,7 +392,7 @@ for `Ref/MathTypes`. ### Build the Stub Implementation **Run the build:** -Go into the directory `Ref/MathTypes`. +Go into the directory `Ref/MathSender`. Run the following commands: ```bash @@ -409,14 +407,14 @@ After the second command, the build system should run for a bit. At the end there should be two new files in the directory: -`MathSenderComponentImpl.cpp-template` and -`MathSenderComponentImpl.hpp-template`. +`MathSender.cpp-template` and +`MathSender.hpp-template`. Run the following commands: ```bash -mv MathSenderComponentImpl.cpp-template MathSender.cpp -mv MathSenderComponentImpl.hpp-template MathSender.hpp +mv MathSender.cpp-template MathSender.cpp +mv MathSender.hpp-template MathSender.hpp ``` These commands produce a template, or stub implementation, @@ -572,42 +570,44 @@ in three steps: #### Set Up the Unit Test Environment **Create the stub Tester class:** -Do the following in directory `Ref/MathSender`: - -1. Run `mkdir -p test/ut` to create the directory where +In the directory `Ref/MathSender`, run `mkdir -p test/ut`. +This will create the directory where the unit tests will reside. -1. Run the command `fprime-util impl --ut`. -It should generate files `Tester.cpp` and `Tester.hpp`. +**Update Ref/MathSender/CMakeLists.txt:** +Go back to the directory `Ref/MathSender`. +Add the following lines to `CMakeLists.txt`: -1. Move these files to the `test/ut` directory: +```cmake +# Register the unit test build +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/MathSender.fpp" +) +register_fprime_ut() +``` - ```bash - mv Tester.* test/ut - ``` +**Generate the unit test stub:** +We will now generate a stub implementation of the unit tests. +This stub contains all the boilerplate necessary to write and +run unit tests against the `MathSender` component. +In a later step, we will fill in the stub with tests. -**Create a stub main.cpp file:** -Now go to the directory `Ref/MathSender/test/ut`. -In that directory, create a file `main.cpp` with the -following contents: +1. If you have not yet run `fprime-util generate --ut`, + then do so now. This step generates the CMake build cache for the unit + tests. -```c++ -#include "Tester.hpp" +1. Run the command `fprime-util impl --ut`. + It should generate files `Tester.cpp`, `Tester.hpp`, and `TestMain.cpp`. -int main(int argc, char **argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} -``` +1. Move these files to the `test/ut` directory: -This file is a stub for running tests using the -[Google Test framework](https://github.com/google/googletest). -Right now there aren't any tests to run; we will add one -in the next section. + ```bash + mv Tester.* TestMain.cpp test/ut + ``` **Update Ref/MathSender/CMakeLists.txt:** -Go back to the directory `Ref/MathSender`. -Add the following lines to `CMakeLists.txt`: +Open `MathSender/CMakeLists.txt` and update the definition of +`UT_SOURCE_FILES` by adding your new test files: ```cmake # Register the unit test build @@ -619,23 +619,14 @@ set(UT_SOURCE_FILES register_fprime_ut() ``` -This code tells the build system how to build -and run the unit tests. - **Run the build:** Now we can check that the unit test build is working. - -1. If you have not yet run `fprime-util generate --ut`, -then do so now. -This step generates the CMake build cache for the unit -tests. - -1. Run `fprime-util build --ut`. +Run `fprime-util build --ut`. Everything should build without errors. **Inspect the generated code:** -The generated code is located at -`Ref/build-fprime-automatic-native-ut/Ref/MathSender`. +The unit test build generates some code to support unit testing. +The code is located at `Ref/build-fprime-automatic-native-ut/Ref/MathSender`. This directory contains two auto-generated classes: 1. `MathSenderGTestBase`: This is the direct base @@ -858,8 +849,7 @@ the tests pass. Add a test for exercising the scenario in which the `MathReceiver` component sends a result back to `MathSender`. -1. Add the following function signature in the "Tests" - section of to `Tester.hpp`: +1. Add the following function signature in the "Tests" section of `Tester.hpp`: ```c++ //! Test receipt of a result @@ -937,7 +927,7 @@ and 10. This line tells the build system to make the unit test build depend on the `STest` build module. -1. Add `#include STest/Random/Random.hpp` to `main.cpp`. +1. Add `#include "STest/Random/Random.hpp"` to `main.cpp`. 1. Add the following line to the `main` function of `main.cpp`, just before the return statement: @@ -1237,7 +1227,7 @@ of the function. Here we do the following: 1. If the parameter identifier is `PARAMID_FACTOR` (the parameter -identifier corresponding to the `FACTOR` parameter, +identifier corresponding to the `FACTOR` parameter), then get the parameter value and emit an event report. 1. Otherwise fail an assertion. @@ -1515,7 +1505,13 @@ This test is the same as the SUB test, except that it uses DIV instead of SUB. **Write a throttle test:** -Add the following function to the "Tests" section of `Tester.cpp`: +Add the following constant definition to the top of the `Tester.cpp` file: + +```C++ +#define CMD_SEQ 42 +``` + +Then add the following function to the "Tests" section of `Tester.cpp`: ```c++ void Tester :: @@ -1653,8 +1649,8 @@ add the following lines: ```fpp instance mathSender: Ref.MathSender base id 0xE00 \ - queue size Default.queueSize \ - stack size Default.stackSize \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ priority 100 ``` @@ -1679,7 +1675,7 @@ add the following lines: ```fpp instance mathReceiver: Ref.MathReceiver base id 0x2700 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE ``` This code defines an instance `mathReceiver` of @@ -1712,7 +1708,7 @@ These lines add the `mathSender` and `mathReceiver` instances to the topology. **Check for unconnected ports:** -Run the following commands: +Run the following commands in the `Ref/Top` directory: ```bash fprime-util fpp-check -u unconnected.txt @@ -1728,21 +1724,18 @@ Those ports will include the ports for the new instances Find the line that starts `connections RateGroups`. This is the beginning of the definition of the `RateGroups` connection graph. -Inside the block of that definition, -find the line -`rateGroup1Comp.RateGroupMemberOut[3] -> fileDownlink.Run`. -After that line, add the line +After the last entry for the `rateGroup1Comp` (rate group 1) add +the following line: ```fpp -rateGroup1Comp.RateGroupMemberOut[4] -> mathReceiver.schedIn +rateGroup1Comp.RateGroupMemberOut -> mathReceiver.schedIn ``` This line adds the connection that drives the `schedIn` port of the `mathReceiver` component instance. **Re-run the check for unconnected ports:** -When this capability exists, you will be able to see -that `mathReceiver.schedIn` is now connected +You should see that `mathReceiver.schedIn` is now connected (it no longer appears in the list). **Add the Math connections:** @@ -1974,3 +1967,17 @@ You can also view these logs via the GDS browser interface. Click the Logs tab to go the Logs view. Select the log you wish to inspect from the drop-down menu. By default, there is no log selected. + +## Conclusion + +The Math Component tutorial has shown us how to create simple types, ports and +components for our application using the FPP modeling language. We have learned +how to use `fprime-util` to generate implementation stubs, the build cache, and +unit tests. We learned how to define our topology and use tools provided by +F´ to check and visualize the topology. Lastly, we learned how to use the +ground system to interact with our deployment. + +The user is now directed back to the [Tutorials](../README.md) for further +reading or to the [Cross-Compilation Tutorial](../CrossCompilation/Tutorial.md) +for instructions on how to cross-compile the Ref application completed in this +tutorial for the Raspberry Pi. From c06b5e890faed3f895c13985ff2c67aa7fcce702 Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Mon, 19 Dec 2022 23:07:27 +0100 Subject: [PATCH 113/169] Remove LGTM badges from README.me (#1816) --- README.md | 3 --- 1 file changed, 3 deletions(-) diff --git a/README.md b/README.md index 210954c3bc..f85916e81e 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,5 @@ # F´: A Flight-Proven, Multi-Platform, Open-Source Flight Software Framework -[![Language grade: C++](https://img.shields.io/lgtm/grade/cpp/g/nasa/fprime.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/nasa/fprime/context:cpp) -[![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/nasa/fprime.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/nasa/fprime/context:python) - **F´ (F Prime)** is a component-driven framework that enables rapid development and deployment of spaceflight and other embedded software applications. Originally developed at the [Jet Propulsion Laboratory](https://www.jpl.nasa.gov/), F´ has been successfully deployed on several space applications. It is tailored but not limited to small-scale spaceflight systems such as CubeSats, SmallSats, and instruments. **Please Visit the F´ Website:** [https://nasa.github.io/fprime/](https://nasa.github.io/fprime/). This website contains project information, user guides, documentation, tutorials, and more! From 950f4bb74815c10e50c95c53f7fcefabdf1abdd1 Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 20 Dec 2022 14:21:41 -0800 Subject: [PATCH 114/169] initial implementation, UTs, and SDD for BufferRepeater (#1785) * initial implementation, UTs, and SDD for BufferRepeater * fixing compile warnings as errors * Fixing typo per review * fixing review comments --- Svc/BufferRepeater/BufferRepeater.cpp | 83 ++++++++++++ Svc/BufferRepeater/BufferRepeater.fpp | 45 +++++++ Svc/BufferRepeater/BufferRepeater.hpp | 85 ++++++++++++ Svc/BufferRepeater/CMakeLists.txt | 21 +++ Svc/BufferRepeater/docs/sdd.md | 76 +++++++++++ Svc/BufferRepeater/test/ut/TestMain.cpp | 30 +++++ Svc/BufferRepeater/test/ut/Tester.cpp | 166 ++++++++++++++++++++++++ Svc/BufferRepeater/test/ut/Tester.hpp | 96 ++++++++++++++ Svc/CMakeLists.txt | 1 + config/AcConstants.fpp | 3 + 10 files changed, 606 insertions(+) create mode 100644 Svc/BufferRepeater/BufferRepeater.cpp create mode 100644 Svc/BufferRepeater/BufferRepeater.fpp create mode 100644 Svc/BufferRepeater/BufferRepeater.hpp create mode 100644 Svc/BufferRepeater/CMakeLists.txt create mode 100644 Svc/BufferRepeater/docs/sdd.md create mode 100644 Svc/BufferRepeater/test/ut/TestMain.cpp create mode 100644 Svc/BufferRepeater/test/ut/Tester.cpp create mode 100644 Svc/BufferRepeater/test/ut/Tester.hpp diff --git a/Svc/BufferRepeater/BufferRepeater.cpp b/Svc/BufferRepeater/BufferRepeater.cpp new file mode 100644 index 0000000000..d081f4bd17 --- /dev/null +++ b/Svc/BufferRepeater/BufferRepeater.cpp @@ -0,0 +1,83 @@ +// ====================================================================== +// \title BufferRepeater.cpp +// \author lestarch +// \brief cpp file for GenericRepeater component implementation class +// +// \copyright +// Copyright 2009-2015, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include +#include + +namespace Svc { + +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +BufferRepeater ::BufferRepeater(const char* const compName) + : BufferRepeaterComponentBase(compName), + m_allocation_failure_response(BufferRepeater::NUM_BUFFER_REPEATER_FAILURE_OPTIONS) {} + +void BufferRepeater ::init(const NATIVE_INT_TYPE instance) { + BufferRepeaterComponentBase::init(instance); +} + +BufferRepeater ::~BufferRepeater() {} + +void BufferRepeater ::configure(BufferRepeater::BufferRepeaterFailureOption allocation_failure_response) { + this->m_allocation_failure_response = allocation_failure_response; +} + +bool BufferRepeater ::check_allocation(FwIndexType index, + const Fw::Buffer& new_allocation, + const Fw::Buffer& incoming_buffer) { + FW_ASSERT(index < NUM_PORTOUT_OUTPUT_PORTS, index); + bool is_valid = (new_allocation.getData() != nullptr) && (new_allocation.getSize() >= incoming_buffer.getSize()); + + // Respond to invalid buffer allocation + if (!is_valid) { + switch (this->m_allocation_failure_response) { + case NO_RESPONSE_ON_OUT_OF_MEMORY: + // No response intended + break; + case WARNING_ON_OUT_OF_MEMORY: + this->log_WARNING_HI_AllocationSoftFailure(index, incoming_buffer.getSize()); + break; + case FATAL_ON_OUT_OF_MEMORY: + this->log_FATAL_AllocationHardFailure(index, incoming_buffer.getSize()); + break; + default: + FW_ASSERT(0); + break; + } + } + return is_valid; +} + +// ---------------------------------------------------------------------- +// Handler implementations for user-defined serial input ports +// ---------------------------------------------------------------------- + +void BufferRepeater ::portIn_handler(NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& buffer /*!< The serialization buffer*/ +) { + FW_ASSERT(this->m_allocation_failure_response < NUM_BUFFER_REPEATER_FAILURE_OPTIONS); + for (FwIndexType i = 0; i < NUM_PORTOUT_OUTPUT_PORTS; i++) { + if (isConnected_portOut_OutputPort(i)) { + Fw::Buffer new_allocation = this->allocate_out(0, buffer.getSize()); + if (this->check_allocation(i, new_allocation, buffer)) { + // Clone the data and send it + ::memcpy(new_allocation.getData(), buffer.getData(), buffer.getSize()); + new_allocation.setSize(buffer.getSize()); + this->portOut_out(i, new_allocation); + } + } + } + this->deallocate_out(0, buffer); +} +} // end namespace Svc diff --git a/Svc/BufferRepeater/BufferRepeater.fpp b/Svc/BufferRepeater/BufferRepeater.fpp new file mode 100644 index 0000000000..133cb918fc --- /dev/null +++ b/Svc/BufferRepeater/BufferRepeater.fpp @@ -0,0 +1,45 @@ +module Svc { + + @ A component for repeating Fw.BufferSend calls to multiple consumers + passive component BufferRepeater { + @ Port to duplicate across the repeater + sync input port portIn: Fw.BufferSend + + @ Duplicated output ports + output port portOut: [BufferRepeaterOutputPorts] Fw.BufferSend + + @ Port to allocate new memory for each buffer output + output port allocate: Fw.BufferGet + + @ Port to deallocate original buffer output + output port deallocate: Fw.BufferSend + + @ Event port + event port Log + + @ Text event port + text event port LogText + + @ Time get port + time get port Time + + @ Soft failure in allocation + event AllocationSoftFailure( + $port: I32 @< The port index that needed an allocation + $size: U32 @< The requested allocation size + ) \ + severity warning high \ + id 0 \ + format "Failed to allocate {} byte buffer for port {}" + + + @ Hard failure in allocation + event AllocationHardFailure( + $port: I32 @< The port index that needed an allocation + $size: U32 @< The requested allocation size + ) \ + severity fatal \ + id 1 \ + format "Failed to allocate {} byte buffer for port {}" + } +} diff --git a/Svc/BufferRepeater/BufferRepeater.hpp b/Svc/BufferRepeater/BufferRepeater.hpp new file mode 100644 index 0000000000..34873565f1 --- /dev/null +++ b/Svc/BufferRepeater/BufferRepeater.hpp @@ -0,0 +1,85 @@ +// ====================================================================== +// \title BufferRepeater.hpp +// \author lestarch +// \brief hpp file for GenericRepeater component implementation class +// +// \copyright +// Copyright 2009-2015, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef BufferRepeater_HPP +#define BufferRepeater_HPP + +#include "Svc/BufferRepeater/BufferRepeaterComponentAc.hpp" + +namespace Svc { + +class BufferRepeater : public BufferRepeaterComponentBase { + public: + /** + * Set of responses to failures to allocate a buffer when requested + */ + enum BufferRepeaterFailureOption { + NO_RESPONSE_ON_OUT_OF_MEMORY, /*!< The component will continue regardless of allocation failures */ + WARNING_ON_OUT_OF_MEMORY, /*!< The component will produce a warning on allocation failures */ + FATAL_ON_OUT_OF_MEMORY, /*!< The component will produce a FATAL on allocation failures */ + NUM_BUFFER_REPEATER_FAILURE_OPTIONS /*!< Maximum value of this setting. Used to mark as uninitialized. */ + }; + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object BufferRepeater + //! + BufferRepeater(const char* const compName /*!< The component name*/ + ); + + //! Initialize object BufferRepeater + //! + void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ + ); + + //! Destroy object BufferRepeater + //! + ~BufferRepeater(); + + /** + * Set the response used when an allocation request fails to produce a buffer. By default this will assert. + * @param allocation_failure_response: set response + */ + void configure(BufferRepeaterFailureOption allocation_failure_response); + + private: + // ---------------------------------------------------------------------- + // Helper functions + // ---------------------------------------------------------------------- + + /** + * Checks the allocation for viability and reports if it fails. + * @param index: index of the port that needs this allocation + * @param new_allocation: new allocation for a copy of the incoming buffer. + * @param incoming_buffer: buffer that is to be cloned + * @return true when the allocation is valid, false otherwise + */ + bool check_allocation(FwIndexType index, const Fw::Buffer& new_allocation, const Fw::Buffer& incoming_buffer); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined serial input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for portIn + //! + void portIn_handler(NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& Buffer /*!< The serialization buffer*/ + ); + + BufferRepeaterFailureOption m_allocation_failure_response; //!< Local storage for configured response +}; + +} // end namespace Svc + +#endif diff --git a/Svc/BufferRepeater/CMakeLists.txt b/Svc/BufferRepeater/CMakeLists.txt new file mode 100644 index 0000000000..23cc894018 --- /dev/null +++ b/Svc/BufferRepeater/CMakeLists.txt @@ -0,0 +1,21 @@ +#### +# F prime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoded files +# MOD_DEPS: (optional) module dependencies +# +#### +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/BufferRepeater.fpp" + "${CMAKE_CURRENT_LIST_DIR}/BufferRepeater.cpp" +) + +register_fprime_module() + +### UTs ### +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/BufferRepeater.fpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/TestMain.cpp" + "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" +) +register_fprime_ut() diff --git a/Svc/BufferRepeater/docs/sdd.md b/Svc/BufferRepeater/docs/sdd.md new file mode 100644 index 0000000000..3e859dcc11 --- /dev/null +++ b/Svc/BufferRepeater/docs/sdd.md @@ -0,0 +1,76 @@ +\page SvcBufferRepeaterComponent Svc::BufferRepeater Component +# Svc::BufferRepeater: Buffer Repeater (Passive Component) + +## 1. Introduction + +The BufferRepeater component is designed to take in an `Fw::buffer` port call and repeat it to multiple output ports. +New memory is allocated from a `Svc::BufferManager` and the data is copied to ensure that each downstream component has +full ownership of its data. The original buffer is deallocated. Users call `configure` to set the response of the +component when allocation requests fail. + +## 2. Requirements + +| Name | Description | Validation | +|--------------------|-------------------------------------------------------------------------------|------------| +| BUFFER_REPEATER_01 | The buffer repeater shall accept incoming `Fw::Buffer` port calls | Unit Test | +| BUFFER_REPEATER_02 | The buffer repeater shall copy the incoming data before each repeated send | Unit Test | +| BUFFER_REPEATER_03 | The buffer repeater shall only send a copy to connected components | Unit Test | +| BUFFER_REPEATER_04 | The buffer repeater shall have a configurable response to allocation failures | Unit Test | + +## 3. Design + +The buffer repeater has a single `portIn` port of type `Fw.BufferSend` and an array of `portOut` ports of the same type. +Each port call received on `portIn` is repeated to each connected `portOut` port. These repetitions emit a copy of the +`Fw::Buffer` data. + +## 3.1 Ports + +`Svc::BufferRepeater` has the following ports: + +| Kind | Name | Port Type | Usage | +|--------------|--------------|---------------------------------------------|---------------------------------------| +| `sync input` | `portIn` | `Fw.BufferSend` | Port for receiving initial Fw::Buffer | +| `output` | `portOut` | `[BufferRepeaterOutputPorts] Fw.BufferSend` | Port array for repeating Fw::Buffers | +| `output` | `deallocate` | `Fw.BufferSend` | Deallocate the original buffer | +| `output` | `allocate` | `Fw.BufferGet` | Port for allocating new memory | +| `event` | `Log` | `Fw.Log` | Port for emitting events | +| `text event` | `LogText` | `Fw.LogText` | Port for emitting text events | +| `time get` | `Time` | `Fw.Time` | Port for getting the time | + +#### 3.1.1 portIn handler + +The `portIn` port handler receives an `Fw::Buffer` data type and a port number. For each connected `portOut` port it +allocates new memory large enough to hold a copy of the `Fw::Buffer` data via the `allocate` port, copies the data to +the new invocation, and sends it to the active `portOut` port. This continues until each `portOut` port has been tried +and at the end it returns the original buffer via `deallocate`. + +Should an allocation fail, `portOut` is not called and an event may be emitted (see below). + +### 3.2 Events + +| Name | Description | +|-----------------------|--------------------------------------------------------------------------------------| +| AllocationSoftFailure | WARNING_HI indicating allocation failure when configured to WARNING_ON_OUT_OF_MEMORY | +| AllocationHardFailure | FATAL indicating allocation failure when configured to FATAL_ON_OUT_OF_MEMORY | + +## 4. Configuration + +Buffer repeater maximum output ports are configured using `AcConstants.fpp` as shown below: + +```ini +constant BufferRepeaterOutputPorts = 10 +``` + +The component's response to allocation failures is configured with a call to the configure method during system +initialization. Possible values include: + +| Setting | Description | +|------------------------------|-------------------------------------------------------------------------------| +| NO_RESPONSE_ON_OUT_OF_MEMORY | The component drops the `portOut` call and otherwise takes no response action | +| WARNING_ON_OUT_OF_MEMORY | The component drops the `portOut` call and emits a WARNING_HI event | +| FATAL_ON_OUT_OF_MEMORY | The component drops the `portOut` call and emits a FATAL event | + +```c++ +bufferRepeater.configure(Svc::BufferRepeater::FATAL_ON_OUT_OF_MEMORY); +``` + diff --git a/Svc/BufferRepeater/test/ut/TestMain.cpp b/Svc/BufferRepeater/test/ut/TestMain.cpp new file mode 100644 index 0000000000..106dc86e96 --- /dev/null +++ b/Svc/BufferRepeater/test/ut/TestMain.cpp @@ -0,0 +1,30 @@ +// ---------------------------------------------------------------------- +// TestMain.cpp +// ---------------------------------------------------------------------- + +#include "Tester.hpp" + +TEST(Nominal, TestRepeater) { + Svc::Tester tester; + tester.testRepeater(); +} + +TEST(OffNominal, NoMemoryResponse) { + Svc::Tester tester; + tester.testFailure(Svc::BufferRepeater::NO_RESPONSE_ON_OUT_OF_MEMORY); +} + +TEST(OffNominal, WarningMemoryResponse) { + Svc::Tester tester; + tester.testFailure(Svc::BufferRepeater::WARNING_ON_OUT_OF_MEMORY); +} + +TEST(OffNominal, FatalMemoryResponse) { + Svc::Tester tester; + tester.testFailure(Svc::BufferRepeater::FATAL_ON_OUT_OF_MEMORY); +} + +int main(int argc, char** argv) { + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/Svc/BufferRepeater/test/ut/Tester.cpp b/Svc/BufferRepeater/test/ut/Tester.cpp new file mode 100644 index 0000000000..a65c8acb01 --- /dev/null +++ b/Svc/BufferRepeater/test/ut/Tester.cpp @@ -0,0 +1,166 @@ +// ====================================================================== +// \title BufferRepeater.hpp +// \author lestarch +// \brief cpp file for BufferRepeater test harness implementation class +// ====================================================================== + +#include "Tester.hpp" + +#define INSTANCE 0 +#define MAX_HISTORY_SIZE 10 + +namespace Svc { + +// ---------------------------------------------------------------------- +// Construction and destruction +// ---------------------------------------------------------------------- + +Tester ::Tester() + : BufferRepeaterGTestBase("Tester", MAX_HISTORY_SIZE), + component("BufferRepeater"), + m_port_index_history(MAX_HISTORY_SIZE), + m_initial_buffer(), + m_failure(false) { + this->initComponents(); + this->connectPorts(); +} + +Tester ::~Tester() {} + +// ---------------------------------------------------------------------- +// Tests +// ---------------------------------------------------------------------- + +void Tester ::testRepeater() { + this->component.configure(BufferRepeater::FATAL_ON_OUT_OF_MEMORY); + m_initial_buffer.setSize(1024); + m_initial_buffer.setData(new U8[1024]); + for (U32 i = 0; i < m_initial_buffer.getSize(); i++) { + m_initial_buffer.getData()[i] = static_cast(i); + } + + invoke_to_portIn(0, m_initial_buffer); + ASSERT_EVENTS_AllocationHardFailure_SIZE(0); + ASSERT_EVENTS_AllocationSoftFailure_SIZE(0); + ASSERT_from_portOut_SIZE(this->component.getNum_portOut_OutputPorts()); + ASSERT_EQ(fromPortHistory_portOut->size(), this->m_port_index_history.size()); + for (NATIVE_INT_TYPE i = 0; i < this->component.getNum_portOut_OutputPorts(); i++) { + NATIVE_INT_TYPE port_index = this->m_port_index_history.at(i); + ASSERT_EQ(i, port_index); + Fw::Buffer buffer_under_test = this->fromPortHistory_portOut->at(i).fwBuffer; + ASSERT_EQ(buffer_under_test.getSize(), m_initial_buffer.getSize()); + for (U32 j = 0; j < FW_MIN(buffer_under_test.getSize(), m_initial_buffer.getSize()); j++) { + ASSERT_EQ(buffer_under_test.getData()[j], m_initial_buffer.getData()[j]) + << "Data not copied correctly at offset: " << j; + } + // Deallocate allocated data + if (buffer_under_test.getData() != nullptr) { + delete[] buffer_under_test.getData(); + } + } + // Check proper deallocation + ASSERT_from_deallocate_SIZE(1); + ASSERT_EQ(m_initial_buffer.getData(), fromPortHistory_deallocate->at(0).fwBuffer.getData()); + ASSERT_EQ(m_initial_buffer.getSize(), fromPortHistory_deallocate->at(0).fwBuffer.getSize()); + delete[] m_initial_buffer.getData(); + m_initial_buffer.setData(nullptr); +} + +void Tester ::testFailure(BufferRepeater::BufferRepeaterFailureOption failure_option) { + this->m_failure = true; + this->component.configure(failure_option); + m_initial_buffer.setSize(1024); + m_initial_buffer.setData(new U8[1024]); + + invoke_to_portIn(0, m_initial_buffer); + switch (failure_option) { + case BufferRepeater::WARNING_ON_OUT_OF_MEMORY: + ASSERT_EVENTS_AllocationHardFailure_SIZE(0); + ASSERT_EVENTS_AllocationSoftFailure_SIZE(this->component.getNum_portOut_OutputPorts()); + break; + case BufferRepeater::FATAL_ON_OUT_OF_MEMORY: + ASSERT_EVENTS_AllocationHardFailure_SIZE(this->component.getNum_portOut_OutputPorts()); + ASSERT_EVENTS_AllocationSoftFailure_SIZE(0); + break; + // Cascade intended + case BufferRepeater::NO_RESPONSE_ON_OUT_OF_MEMORY: + case BufferRepeater::NUM_BUFFER_REPEATER_FAILURE_OPTIONS: + ASSERT_EVENTS_AllocationHardFailure_SIZE(0); + ASSERT_EVENTS_AllocationSoftFailure_SIZE(0); + break; + } + + ASSERT_from_portOut_SIZE(0); + + // Check proper deallocation + ASSERT_from_deallocate_SIZE(1); + ASSERT_EQ(m_initial_buffer.getData(), fromPortHistory_deallocate->at(0).fwBuffer.getData()); + ASSERT_EQ(m_initial_buffer.getSize(), fromPortHistory_deallocate->at(0).fwBuffer.getSize()); + delete[] m_initial_buffer.getData(); + m_initial_buffer.setData(nullptr); +} + +// ---------------------------------------------------------------------- +// Handlers for typed from ports +// ---------------------------------------------------------------------- + +Fw::Buffer Tester ::from_allocate_handler(const NATIVE_INT_TYPE portNum, U32 size) { + this->pushFromPortEntry_allocate(size); + Fw::Buffer new_buffer; + + if (m_failure) { + new_buffer.setSize(0); + new_buffer.setData(nullptr); + } else { + new_buffer.setSize(size); + new_buffer.setData(new U8[size]); + } + return new_buffer; +} + +void Tester ::from_deallocate_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { + this->pushFromPortEntry_deallocate(fwBuffer); + EXPECT_EQ(fwBuffer.getData(), m_initial_buffer.getData()) << "Deallocated non-initial buffer"; +} + +void Tester ::from_portOut_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { + this->m_port_index_history.push_back(portNum); + this->pushFromPortEntry_portOut(fwBuffer); + EXPECT_NE(fwBuffer.getData(), nullptr) << "Passed invalid buffer out port"; +} + +// ---------------------------------------------------------------------- +// Helper methods +// ---------------------------------------------------------------------- + +void Tester ::connectPorts() { + // portIn + this->connect_to_portIn(0, this->component.get_portIn_InputPort(0)); + + // Log + this->component.set_Log_OutputPort(0, this->get_from_Log(0)); + + // LogText + this->component.set_LogText_OutputPort(0, this->get_from_LogText(0)); + + // Time + this->component.set_Time_OutputPort(0, this->get_from_Time(0)); + + // allocate + this->component.set_allocate_OutputPort(0, this->get_from_allocate(0)); + + // deallocate + this->component.set_deallocate_OutputPort(0, this->get_from_deallocate(0)); + + // portOut + for (NATIVE_INT_TYPE i = 0; i < this->component.getNum_portOut_OutputPorts(); ++i) { + this->component.set_portOut_OutputPort(i, this->get_from_portOut(i)); + } +} + +void Tester ::initComponents() { + this->init(); + this->component.init(INSTANCE); +} + +} // end namespace Svc diff --git a/Svc/BufferRepeater/test/ut/Tester.hpp b/Svc/BufferRepeater/test/ut/Tester.hpp new file mode 100644 index 0000000000..02b3660bc2 --- /dev/null +++ b/Svc/BufferRepeater/test/ut/Tester.hpp @@ -0,0 +1,96 @@ +// ====================================================================== +// \title BufferRepeater/test/ut/Tester.hpp +// \author lestarch +// \brief hpp file for GenericRepeater test harness implementation class +// +// \copyright +// Copyright 2009-2015, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef TESTER_HPP +#define TESTER_HPP + +#include "GTestBase.hpp" +#include "Svc/BufferRepeater/BufferRepeater.hpp" + +namespace Svc { + +class Tester : public BufferRepeaterGTestBase { + // ---------------------------------------------------------------------- + // Construction and destruction + // ---------------------------------------------------------------------- + + public: + //! Construct object Tester + //! + Tester(); + + //! Destroy object Tester + //! + ~Tester(); + + public: + // ---------------------------------------------------------------------- + // Tests + // ---------------------------------------------------------------------- + + //! Test the repeating capability of the buffer + //! + void testRepeater(); + + //! Test the repeating capability of the buffer + //! + void testFailure(BufferRepeater::BufferRepeaterFailureOption failure_option); + + private: + // ---------------------------------------------------------------------- + // Handlers for serial from ports + // ---------------------------------------------------------------------- + + //! Handler for from_allocate + //! + Fw::Buffer from_allocate_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + U32 size); + + //! Handler for from_deallocate + //! + void from_deallocate_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& fwBuffer); + + //! Handler for from_portOut + //! + void from_portOut_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Buffer& fwBuffer); + + private: + // ---------------------------------------------------------------------- + // Helper methods + // ---------------------------------------------------------------------- + + //! Connect ports + //! + void connectPorts(); + + //! Initialize components + //! + void initComponents(); + + private: + // ---------------------------------------------------------------------- + // Variables + // ---------------------------------------------------------------------- + + //! The component under test + //! + BufferRepeater component; + History m_port_index_history; + Fw::Buffer m_initial_buffer; + bool m_failure; +}; + +} // end namespace Svc + +#endif diff --git a/Svc/CMakeLists.txt b/Svc/CMakeLists.txt index 92febc9ffa..af79af4507 100644 --- a/Svc/CMakeLists.txt +++ b/Svc/CMakeLists.txt @@ -15,6 +15,7 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ActiveRateGroup/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/AssertFatalAdapter/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferManager/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferLogger/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BufferRepeater/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComLogger/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComQueue/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComSplitter/") diff --git a/config/AcConstants.fpp b/config/AcConstants.fpp index 20199faebe..7a810b787e 100644 --- a/config/AcConstants.fpp +++ b/config/AcConstants.fpp @@ -33,6 +33,9 @@ constant ComQueueComPorts = 2 @ Used for number of Fw::Buffer type ports supported by Svc::ComQueue constant ComQueueBufferPorts = 1 +@ Used for maximum number of connected buffer repeater consumers +constant BufferRepeaterOutputPorts = 10 + # ---------------------------------------------------------------------- # Hub connections. Connections on all deployments should mirror these settings. # ---------------------------------------------------------------------- From 323ba68d1aedb25b7690c5b35aeba2fddfc50fed Mon Sep 17 00:00:00 2001 From: Luca Soares Date: Tue, 20 Dec 2022 16:42:11 -0800 Subject: [PATCH 115/169] Remove generic repeater component from Svc (#1822) --- Svc/CMakeLists.txt | 1 - Svc/GenericRepeater/CMakeLists.txt | 25 ---- Svc/GenericRepeater/GenericRepeater.fpp | 14 --- .../GenericRepeaterComponentImpl.cpp | 47 -------- .../GenericRepeaterComponentImpl.hpp | 54 --------- .../docs/GenericRepeaterAppAi.xml | 25 ---- Svc/GenericRepeater/docs/img/repeater.png | Bin 31702 -> 0 bytes Svc/GenericRepeater/docs/sdd.md | 42 ------- Svc/GenericRepeater/test/ut/TestMain.cpp | 15 --- Svc/GenericRepeater/test/ut/Tester.cpp | 111 ------------------ Svc/GenericRepeater/test/ut/Tester.hpp | 92 --------------- cmake/test/src/test_unittests.py | 1 - config/AcConstants.fpp | 3 - config/AcConstants.ini | 3 - 14 files changed, 433 deletions(-) delete mode 100644 Svc/GenericRepeater/CMakeLists.txt delete mode 100644 Svc/GenericRepeater/GenericRepeater.fpp delete mode 100644 Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp delete mode 100644 Svc/GenericRepeater/GenericRepeaterComponentImpl.hpp delete mode 100644 Svc/GenericRepeater/docs/GenericRepeaterAppAi.xml delete mode 100644 Svc/GenericRepeater/docs/img/repeater.png delete mode 100644 Svc/GenericRepeater/docs/sdd.md delete mode 100644 Svc/GenericRepeater/test/ut/TestMain.cpp delete mode 100644 Svc/GenericRepeater/test/ut/Tester.cpp delete mode 100644 Svc/GenericRepeater/test/ut/Tester.hpp diff --git a/Svc/CMakeLists.txt b/Svc/CMakeLists.txt index af79af4507..d06bcca1ce 100644 --- a/Svc/CMakeLists.txt +++ b/Svc/CMakeLists.txt @@ -29,7 +29,6 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FileDownlink/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FileManager/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FileUplink/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/GenericHub/") -add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/GenericRepeater/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/GroundInterface/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Framer/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FramingProtocol/") diff --git a/Svc/GenericRepeater/CMakeLists.txt b/Svc/GenericRepeater/CMakeLists.txt deleted file mode 100644 index c8295622fa..0000000000 --- a/Svc/GenericRepeater/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -#### -# F prime CMakeLists.txt: -# -# SOURCE_FILES: combined list of source and autocoded files -# MOD_DEPS: (optional) module dependencies -# -#### -set(SOURCE_FILES - "${CMAKE_CURRENT_LIST_DIR}/GenericRepeater.fpp" - "${CMAKE_CURRENT_LIST_DIR}/GenericRepeaterComponentImpl.cpp" -) - -register_fprime_module() - -### UTs ### -set(UT_SOURCE_FILES - "${CMAKE_CURRENT_LIST_DIR}/GenericRepeater.fpp" - "${CMAKE_CURRENT_LIST_DIR}/test/ut/TestMain.cpp" - "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" -) - -set(UT_MOD_DEPS - Fw/Com -) -register_fprime_ut() diff --git a/Svc/GenericRepeater/GenericRepeater.fpp b/Svc/GenericRepeater/GenericRepeater.fpp deleted file mode 100644 index 2ee2934fb7..0000000000 --- a/Svc/GenericRepeater/GenericRepeater.fpp +++ /dev/null @@ -1,14 +0,0 @@ -module Svc { - - @ A generic component for repeating input - passive component GenericRepeater { - - @ Port to duplicate across the repeater - sync input port portIn: serial - - @ Duplicated output port - output port portOut: [GenericRepeaterOutputPorts] serial - - } - -} diff --git a/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp b/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp deleted file mode 100644 index 7c1b710faf..0000000000 --- a/Svc/GenericRepeater/GenericRepeaterComponentImpl.cpp +++ /dev/null @@ -1,47 +0,0 @@ -// ====================================================================== -// \title GenericRepeaterComponentImpl.cpp -// \author joshuaa -// \brief cpp file for GenericRepeater component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#include -#include - -namespace Svc { - -// ---------------------------------------------------------------------- -// Construction, initialization, and destruction -// ---------------------------------------------------------------------- - -GenericRepeaterComponentImpl ::GenericRepeaterComponentImpl(const char* const compName) - : GenericRepeaterComponentBase(compName) {} - -void GenericRepeaterComponentImpl ::init(const NATIVE_INT_TYPE instance) { - GenericRepeaterComponentBase::init(instance); -} - -GenericRepeaterComponentImpl ::~GenericRepeaterComponentImpl() {} - -// ---------------------------------------------------------------------- -// Handler implementations for user-defined serial input ports -// ---------------------------------------------------------------------- - -void GenericRepeaterComponentImpl ::portIn_handler(NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::SerializeBufferBase& Buffer /*!< The serialization buffer*/ -) { - for (NATIVE_INT_TYPE i = 0; i < NUM_PORTOUT_OUTPUT_PORTS; i++) { - if (!isConnected_portOut_OutputPort(i)) { - continue; - } - - portOut_out(i, Buffer); - } -} - -} // end namespace Svc diff --git a/Svc/GenericRepeater/GenericRepeaterComponentImpl.hpp b/Svc/GenericRepeater/GenericRepeaterComponentImpl.hpp deleted file mode 100644 index 612ec3b718..0000000000 --- a/Svc/GenericRepeater/GenericRepeaterComponentImpl.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// ====================================================================== -// \title GenericRepeaterComponentImpl.hpp -// \author joshuaa -// \brief hpp file for GenericRepeater component implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef GenericRepeater_HPP -#define GenericRepeater_HPP - -#include "Svc/GenericRepeater/GenericRepeaterComponentAc.hpp" - -namespace Svc { - -class GenericRepeaterComponentImpl : public GenericRepeaterComponentBase { - public: - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object GenericRepeater - //! - GenericRepeaterComponentImpl(const char* const compName /*!< The component name*/ - ); - - //! Initialize object GenericRepeater - //! - void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ - ); - - //! Destroy object GenericRepeater - //! - ~GenericRepeaterComponentImpl(); - - PRIVATE: - // ---------------------------------------------------------------------- - // Handler implementations for user-defined serial input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for portIn - //! - void portIn_handler(NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::SerializeBufferBase& Buffer /*!< The serialization buffer*/ - ); -}; - -} // end namespace Svc - -#endif diff --git a/Svc/GenericRepeater/docs/GenericRepeaterAppAi.xml b/Svc/GenericRepeater/docs/GenericRepeaterAppAi.xml deleted file mode 100644 index f9fcc0e2ea..0000000000 --- a/Svc/GenericRepeater/docs/GenericRepeaterAppAi.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/Svc/GenericRepeater/docs/img/repeater.png b/Svc/GenericRepeater/docs/img/repeater.png deleted file mode 100644 index e9f0072265d743869100406983154afcdcb6e9c6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 31702 zcmeFZc{J4h`#-L`cXhW&QWP0Az7z{eOo4;z1Fl#uWcZ2f~35cWMg4gTiheB4y?bh zFtbb}OOLd#&`*+95#rcXdqX`XtMT%0k5+nKY>~c_@Mi!Q9Tn>GEKB6R5pPLT%iXBL zIeb&(lkldoGeg}6q6!H_fxBy4mj~zlQs-N|%d7`ZFza-X<3(-0b^$L7y#?5>cK4W) zzqG5~yf<;YtS~3M&W4{qK&GtFUNi$x8^mxTFr-XLY1KGf#P^e-z6KElE_tRzJdU| zOEW{khnRVlf$rzX;$e;|3DfY)<3y09`EFeK39R$kvh<38+gF@kOcU?^RlU7MWARMu zj0kefFFgD|j1)b?r~~Yqdv1__6S|v9KCGf{YE93v_o3&=5Fus0=JD>4)w1K@)B0m{{%~0{n-MfrIt<8O#=8VQG(AUTIzChJDRkc{I)1 z#UE$Z z+?uG^?0AB-$}cYd1b_Tu68997b~x|yc+32wV3lqBq{I~RTl@j`+8)>)R9fG4y3I{- z@oc-K#IxO{^zB$!_7-#g(hYOKDpPvM)9|JTMf%jEOhw_maOvZ&AAYfR@W*{R)7;`h z!gT)P7Ywp2oUVTl=xQsMuZ@`|-v4O&vheJ|kg=oUXYOk5d~TdFQQnSSgn<#QvN9}n zx$nc|yzP5)kjTVx`H*O6LZXftYJVs+!9G77A#lkSy7#Tas(_Ie&|2(syiX|SuOM#( zO!~A4lQ7*6fdENH*17NFKaAf}y7X|G=y<;Ko)PsFGxP%T-gngg%^5{Ru!loZ_exY~ z`u1BX_v~t>S=;&J?obHi(}z0z48VH!HD|2pl(Ty}O67~5OxNcDB4fQCe7fJ}IT%V> z-3{0xXlMQzi7?z62)4GuE((DW?XtOY2cR9IN@ea~x!C>uhpQfmTo;K9E!=)KL(rub zMGtu#-qe&bel}s6=ybl*#r$nloedyXxy;%^p6MaH-66jF>hGCq-GlTXB*JWK>gE!4 zMqrql$(6weBuwwaObbJ+lfTc@2M+Q4Q_A)0tV7=wPJvU1oLnU6(`}Xiig*D@rWQE( zueI+|hav+q&W!Ouv}@ZZb*qL$(-ctx{HCH5<>;rh)bJ+PX!7X;jn3lO7F)t|t7tM3 zX-f3xmAFGVA?_(cQQq?m49Z(Ng!>^#QRX-9RYWyhK7@-1A8z#L)rJPW(`lC9bG%;_Ox<9Srt^L4(A7!mvY6!G7p3Vg*SNtVUQzHe8%5ll>TVhdy#k1 zb)#%rBgQ!~h8$Ob=(rCL9*#pR2P_56v$ky6;*@4CCB`3;7SUApTht21iumAx3w>c? zaB_|VcR#7}S@^6n*moDjXT+9pVrdM>X3{imP+TU~*EUxWF|4-H>ZT;HtTQG^J|%(^ z8TMX&#xrtX^rOGQI3$@sd<$&O50tET*vr)mgjj{=p@8JSK8+&7f$(x;0AB)v2z?z6 zBb*q=uhtHi*SDGlznlq78I7Qp1r5v%u#?={s%OV+${I+Fk*6E60uE{{InL2mK)~ou zPhW*JxE0Id?aLdw;D0sA?U|xgPR`GD%#Qq^HLJ~!rK64rS4wuijJKSbr&fB~nh_() z(lhQ(39c9nKImnbtDtQBLZ0XYR?NEcA$%8#rLxvl9@0{q+yRww{?3HhTWpW#zOpfv zV1M_S#=;f%j+47EMjaltF8;xuhG8Cyf{fCEvI3?WM8o*IqQeS?ndWOh#{-_l6=-$j z&8obbbBrxk%Goe1@!GXRcFemMtuS3MyEdZgsBNZTb;TEA&Wdj4+G{|(HL26vFJo(x zd&`_%nZv5#N%okqSXO$s+g#7jP<=$<(h7gvH|X+5#c&eluIPlPVh9(fxC`x?!Z(-kWvO34kYPNN0^6!C7IBpuaE< zwvesIzISE6W+PMwx?2>4{tEKU=dKRbs=T==5`h<+?Po`?a1mWat3rYn9#1<^spcHE z(8bQ-;HldBS#HMj)otuT_)O2NqKtGW!xOrKkj@Hj;K#`J38Tw0BDgG3^_BaJUl;>m zdb#jQABhJ@Og)g8OFxTf%#>u}k=-XXl9U6B8_Wl}+}mMp4&|+9RrwGel%h(m*k2lM zoaF^p=+2DVvp8(lGW7W$w_?lMnS5#!fg{GwzULkf`oV+PWA22!`ng&;OEg9Or1{j^ z$gj~xL`^8-=+X18!z*9QlxsU!R(NhT7LlxyeL_@_-49F~q>pKR{;s9DYN_-i*Y;og zL^EV@HKKzmo5X7n9lAxMNu=qjy*5>1LheCpC0@l_D_4%de?1CA_n_GW<|u{w*oy4C zd{+0ql0KjL`E&(u&kjrXWUsGQI&tyTsCG+Um|qVA-7ShyRzO%wQIzA*U;TM23CgIj z4(m*jzcl)Xzx_&DW}^GD(AQb1p@crJJ-+mmFiwVA=P-mWV$X?{#TS1dP|p{0zc*8hGsdYEn1UR(qyi6%xAuuDsrm}6=FKjNh06<7EWPO`w$Vn2HYt3 zVxe>C)Yamex=(Mu8^Y@gXMARf&LM*dp5kZjL8i<-hHUUz94B0CU2vb!w|b4Z;BZws ze=oZx!n$UGxjngD$jxGW5JOI6w6$hq91+<-m3>{1?*!Vx22xdEzMm?(c;kC+Ox4NTUijubAPq}y%zBN`ZuAHbMhQ9o8q(vHjm~U$Hx2N_oow7!2Vedae4;Cc z4*b=$WNz)4+}%hG)mOE5v~l*g`PRwIDnR#|+U4?+Y&ej4$PF>l(DmKaF^#oWJ$E+R z#Mv|YVsrlM^X(({@-3B3zqxJ;1a6SgBgXt;!JW;^Q`Tt7`ndTpJ=ki+xqbKjZLX~g zbV2mVmj3)uX_w|+j(Y|yYk_qIb&s?St9m7JCiO_YoaY3^$Dr5*f%40cH(eXsg1q

    E3HG+V)qAn=vi5lEAO-sFP!WBi|74EeA~vC zxboqUT3_**uRj(j)!&N1{j3OsY2)52X zhz&|?4Z0SRAI6T!;>8oEQ37!d;!3E7o3plrK15Y{lX>P{N(CAby3p}fuCBWaHR3bE z;FYgpsWHtT;6*g>{lMk{^kB8__?3=Wg$BuRtKEW&7idG`=2|H7xH^M^ui=Z66mJ0H zu1#z7A1UO%SenXb3Po9r%lyrmGGE#H`7unESFIR3s;k^)AK91S#+{57XHVcMG{nLO zmU&d+IaInP?pn#?#PPFs61W!(oh_?_gjzJ32-<^^bG$4cLmR6!?H-@c*5%dI|;sNMbnkX_|9ZU~C13*ZmY9m#*W>pU1V-B9L zxu#K3vp*aN{?&P^pNcCjgUZk(5wC{^Vjz?tSGo$sd%f6thtt1E!;4VS^u}Fz_MCLb zI%E*&Q#n0Zdy%YE6%^Ho7t8&HjG9ZKS#o`U5GAmNx;M$=H^*fVza9frUJj&9QoNC> zk%pH=>v)!N6f&HYgNKdDmXI|Z>2!1xD-QZYqZV9}IYG1vn>FOL_91&PVdA&&;t0jf zK4(w@>%Y}zG?{7gr2Jb(e787xBauAlL3{qZGTpB>GfX2a89j=Gj5R%ZmF_Urw z@m>T@{vpG*1C0264>2@#PX_TY(47lIHED=dSD-0g!ftNr-W_uHjsC!+`x>c0MV{i$ z<2X+Q<(3k259H7L7m2z+5N#V1nVs0c|#?}eqM&c~<0;;N&8ti>(z4J(lTf?Zp= zWsTPCrX;!vJiOHBKXPg^X6ZsDmX2%c zt9uK>)wEx2!_AKIr;rH#mZ3OPZWGMb8lFpSYAY-)rE(uM5ljt^?`W)1`pF*>q&q?XW2-?#E{ z4*^TJXMRapt&i+YSkSb)@TexM{a?h8xm->8V$p#f4H;9|QoXeuGX6g){KmNqcZIGx zKUTH@`Wu&(k^5C>+Qw0I-?hNKF7sS;PEb}SL{mnMX61(SNT3bPce2q{!&(fN9Qw*J zPT$C8>2l?$%`|!;rgD@Ml#t18%{qYSFBv)v#6ERJBshTJyMA;}ky!%~%+WQdp52My zU-yNaaDZW$%Qq^5T(5ZOBs&5#dUt-l!E)2{;s{kTrOH>~-76yO9j8#-RS^X;`B~>7& zuYq3z^cc~aT~heTK-K0OjHMo(WpOWV1U8l3H}^mj!rV-AqcI2~#tiu~uLOw|nUZL0 zkd7f|HR_8rF}BvIzs}RL))(7_X!a1{1?~9B2JTy)P z1YNp698Ul)WbIOLHRKdl+%_#%4OQVkECsBXDU9OdI?G=vxd?&ZT|i7-z@dC0pLvj= zP7CMUGKYKPqQ%9R%%J;~h$fp(EYKy8NX9n$JqZUUT@KkGw~-mVae{Wn$wmhgcrW*F*Ecs9bw z=luDH%t|XajZVc^;lanjIqk-2mIZ!~(?>jh$~yFKB&K8H!)JlpeJFxNq;6?dwewA@ zI$1x|rn4UW@fiQkNSg5TpY2`{6?cGNb8$+(a~|l}f!4+;HU2nv$o~k2Hs23)RP>i= zC=jt_QyPQ7AD1TnZ_w)hJtP-b-xtsqnO#KeWG&^tk{(knA*?$;;3{%=&cc6Qr~EpE z7h_^QZh9ML|C*kU`Fz)Y3??YxV}zu;VqwcaSRlIBWJ5iypfO~WWLSAfnUW^;{Oa1w z*j6Hkb9>BOp|9J6RdeZ%;@6mlyS}QsFnZO9;OSqiz)J{erXuX_{3*?i4f)*VB5T8` zLF;E7TWfYj#V&XXW(>{CUauXAB|MI@D%~Awwb;aVY~~c=>}A3XV@K(FnbRz3{U%q3sSlW4rDPrLs#Uf3xl?Jy``YSUOB|BOKs~BjC0qdhWK{23EhKdG%l2WKYQd^ zM*}u&CiP`GVtMYiMf1K8GziY>N0T2!fyu$Ob*(B>|5=5(e&~Msp}^R`?G5Ym^9rGm zBM;r77lfW}20{>}wU@lqUwZ>Anps(yH{CeWfxSht^>$6Iq<(WGtvZNft0Bbzu_HO^ z>S)q>p5vT5Hmj}ghu$yDs?MGuB)x>E?#bqceU!;iY37<$rLCWL;k4}*O(|q(? zuyo+lVr_I??fm(YX%>hnyZ&>XtsD>{rGH(9}X)wGs54 zS|6pg(&tKumEH$Fn###KN5cRL$M&4QNUpZqQCcS$G6v2JBHF*tT$TI0mXhGE;d>Zo zv;&FUFs0LY>K;MFRTX;_?2Xb|2*k3qvu*Z;Xg+k9^A)U@4h$}KcHGvXPZII9i>N~j z@b{khJGxz$+MGG*pSM^bq=R_GXnHu}b$>UBxOHti0BTDUma&;M{IqScL!{yF#XJS= zqQtV`q@WfDDdbpvM7Waxz%+NE!^mlRXxFVt;lzY-4YsI*U~l)$LoOJ1i)gXb4w@ej zT+W}SY?+m3e~H*$lcAH011m^s(@XjAd&cp-|=}c z@5~*}6gG^c=Sc4$d3BMNp9sV@I=rgvk;+a{*LwkPQGbNET-tB2JC6z|kcDjXgy^O06P z#Ib|_h?IHIB!0DSKl@9smyS@x|D37%L6OM@tb3mPYAOr>y zga-fIH{PLft%nXyP~Olujyu^^Pfb218>)rpD(w4 zmD`Tl(EMOB&Bs^1xM5os`lR!DbSMkSwS(D5)VcPyr%`;SrYn06mrW(YDk+n4*I2Qk zX*6L|uzUuAVXN%)>o%Uf+*vR`RB0Z>pytY#wuZt{3aqnJQBR15w{E^yr9Pb=I-@k= zagR%)Op)!!(RKi|Tk3KK*t(dktg=>*!fJ%=TvA8?3nPZ8S0k@m+a;%zvb(X+=eWPd zOfqysEms^Drm$Su@My8$;(x}B&o6dO>-5QfXD)5PcBShvTG`Q8@$|`?ynA+;xd(k{ zK0eRo1OLquK1bIF?syE^t>BJ(dSH%jy*ogXd6ftmfNn!{>x-_$=NLw%6=)6mJrzE4 zudw>|9Rl=^>CcUeChv=cqQgP5cfXSXrwDhap^$PaLp0b7UDyY!S#%m)3Z5RGSXZts zHcXfjLUd)1Rl=uwH^z!wp$JQAV;;nK^c})r%Tg+|Ta9Zlauzd-rWQ#SQ3wjaNrsA5Z-%89POw}`yDztv}B3%K*?bi4Jzgps!)J2K|Wrr9oFdGUlw zJMZ*Eem6z%u&8imbz^0X{@UuJ3!j`IsK#WLErFfC*S`*WRCHo})C?}NLb654 z5`x7Y1KTUX0PKPF~RsmW>^ioJAQTNU#JiEG9x?EI{tLN zQVjfyt!8fRJ@pwkMP6Cmd~Uu5)BMq=Ts2|zn3CWH{JCi;r}O1;Z$NRj_aahFwRtTfy=z%vZKxvS=rH?g8CmBh+{I@_U6po;>b-K`J4#B#S%qF$i7vX!5Zq z`nt1g{#4Vc>b^_!99x1nb6=x#R&ER#h)z_poC$(MFH`4hT3kFOnm<(G?AKdW9JDg~ z=K0g7c@@ge8+Qp6^X=-4P_rMZ)HA#5p>82*mm|&VX|4h7yx%NohiqE!`eX1|Fg; z`)uyL-cJMtqT4`nWn&!LKIq2}FA=Zwv5uknbH(+pOj@9QHKnQLNq|jVl@GcO+^(0e zTI_LH3qr$<%6V*;H4(}&=KO$Fj34CwRX=|)hOCX~&!}QvJo6}Q1p4X}F}_3P(wYr_?f8>Vg%r&nKU>n89`WM#acKY!ost&LvWGeeTI;9t{ z?#3)Es8a=s5d6YyS<45i^*JpykK+vT9JX(^(mvv>jmAhGcZct=?W{1b9&|BYiPD3U zVfd0k@#MPC>YFCYcg{l|2pQY2vTm%JqXD;9koG4euNOd@nzr>{!4!lD)@K#5H9*Fa z2q_D5Z`r=sMShi_1qnFQ+9Tvs#zl1AZ=u5(q~rtD-;q-P>)oP3sCz6#rLvnmMfp?? z3Dh?i?=!ulMhU#@n;|E;(Y{sr8VHb2 ziPWySHQ8)}2GSVkvD5>D^zrCSH@ccL_a($4SGJVZ{ro=nma&y*R9$70Ifg8uHJnhp z*hCwHR*e>r;=cL-q`;KI*i=+mjw5M4UEqQecP!Vn;l8V{!r-AOmQsJZ6;q!lWCteW z!(ZGfZD5!8g}6vA-S{u*h|yMO9{^XZ1z+p!4C=6o8*{un{6j;`J@gph_`JGO$v3br zhzmw-1rInV6|oxB^s1St5uFt9{J}vwa29I;$4t#VFLLi5Obog@N<%;4XSWoscTdyFb)fdGru2_a$%7!HhoVIgLeAbrLH5b6Vsr0POFX*5}h|HTsClitPdG zQ-$iU{2IZH^zK;hIPmgi9&7@}`6Lc9j|D5y8@S0i-y=goYyIw!K)qXTG7_w^r!ZC? zHy|3N!(!c8!X3kaiu+8fxOd>Bs2D3fVx zZU2M3IJZ%FnH2zuE;@+yNImQM)25S9W)uKk+cz*=>y9b;ALe^HtQ}4W&ej+668U$_ zXDya?{^T8C(yH5ma6wmKAE%I&Kg$dP*ZL>0d$750>~x*tQ4nZlPo)O}%i+CF+a|aNd@15MS3nO_sWdHMGw^a&& z6wK;3Jhx%g_FH&3UA`PXIP+B~B#_Ye{O4-fu6hz0P8rXS8uS;ahL~(!}*zV5fk^tUCpa20|ln z1HnY7&L?j^K6Q_V77vm-;)5+tw|GG7+uhH;>kSW--9A}K1hm^|A9W3sBea+=E z9F3BIhP#hg7|DikVOiaiPBR}iC>yak0;!fhr6rN5VBT1=9jq^p`%Q{0)l{NXdj@4w zZdoMfsxm~0mxRA~^~&G;?%ki<;#*Zq?pTZfIJPbqCwqzF79Bamix53_Sw62#Ir=VX@KsAu zT<(ptsCsL4ROf1!Km63nNV7^>5%0QNvxtfdNW}M9I#w1qRt5BmyM@)rfVL zSe6RIuvO$3-+w#?#$YjyQa_RWGEYs)h^EwWp7hDfc|jpe>&H2<)zhwzO&z_1a% z1M|<^d`SN2DqnSSv zY1NTZhUm-j-pKfz_ISx!hq3|LojZ3LDOgp^!LXQPd1wfXW~rbmVXF(qY_f!T=*#?C zfp<_cIZ@PMh@d`$ynXHc;AF3!6p;SQn*hKXg6Ga$gKH%8j{7>t-8;Xbnyq`)a4_Kd zPGBfLb8Q3fB=u&?cXc=yWvGmgsF`P7{{k|!b8TwGVcx8Jb7q6{x&>ZUImh*TFe~%8 zzK2JYs_BHjC#b`gGmhHZ_X>}9Q}8O~9hcd2kzO3<+>x7}N2iwYu^VN~ZvW|4*`Q}D zkKrj&mx4b?Y1n9Ny9`ttg#00_x1bR`w+daS!9eHw_^%QhJlaMC2SB1Zr`TkEqf1#7 zhxfYYtQMP`X;ocHQ(vUdEO~iYjki*K>|p(Q?tUba4W1jq#8GWxw4jS0^sl9Nr|)Nj zkaM%mKmOPi1ga7MFG#vwm7KZ`!aDjLNY&{O=rN}5ML6T=O!EYLbM}sIYa^{76w6}M zvB(_0BufYmxZN&bb599>pxSXP|pmPqc-b06jaF&dfA#q^jn2Si0dYZJYh9 z@NOe@snH`td&N98jvA%YiXjhgB_f(I8%PMK+2o1RV^+?L*R8pKk{YSx%DL9w zIh>;3%1=971YFt;PBK90MH|CJS|u4GkUU|(`c#1_zs!_C0t4$A`0xAo|AkL)mo`j?ED;EslQ`TBU`{ctaxtw%J#cRU-$EP4=b!|up z?HRJW6od=!t9*Z>1pVzn?zg4N2FI!8p3zyT@GZA=2s{D&ilo2OHr)3vL+Pb256x>8 zQ8n->A4rEDmy|3|kaYYYsi&eBzhd_5%c(K@vUaQT`y^Y2$DRvpQ1hMCsu**pm&v-oN@i$XqTN99OXRq*Qm93 z`9|-zL1_dan%k+=Evj4IT6Bu_>+2lAExeF|0~W10?23(bQOJn6%wD!y8AH2Lr;xLpkt>4tx+?{|GUqsF6_hhfGbI3^?m_8mphD-ekJ!2%n&aw6!G|_UErtEp{k?tJ zvn2IduC1YNT3v2*z`kvqGAQs(E2?h-0C!U8a9j3ZfQr?tun^L)=G^Z2GoZlBb3!*| z6+Xl_;Xmf*WE2fX=p^q)==YnyNLu+qAJ>#^)BOcdolGf|qS@>a-IwUv`4?n}qaOlxYx-Jeu6=C$ z^5u(&i;9)5Uc9|t{LABdU0KyqRxI$BEbs|;YQ}cQ7Z9I^Zu_^J4gy-6QW<(I*l2kw z6mzRqt^vTwy_8WnHlzrop>@^2cF2W-nk^)BBQOWaX1O&~yVu^$Kb+SMjbRBc|I>LiDnuD_3*l8=uuAm~Pu{?WF z+Njzv$}f=8*{%#C08nIC&2BLo0RN4|dT)7+OhlK%Q{Cb)+93CX2+noq&RM4GP>=Pt zXUf8HL6?wukUd_CfuU%Ol}-e%!j)_|l9EB`rZBEfeB*b$F^ZAJ8r! z^H)+Z-LC-Q;e~t?^jmez#>+{~r7{&xvCnui;)LM<$1!eYaY0t|7N`G}ACsOn7$!N3 zv*`gyQ-QBF0GMYrU`IcvMsIrV`L#~$ZzTyrP;j!Vem3~6=X5wn{T9(V=n}_#@MHb4 zA&VIe&+uRXcA=v7dxdlg9*8D?-^<}kop`QJP*;BK@hWQcQ<=>B&!c1E#kI`Yim zP7tcO(CN2MV$8Qf;3`!oDfE7VGsb(7Z9U$CIm1YXN>V#(K^-I%oZ}6wYsL5}yIOFP zs*1aRX8382Zd}xv8lam2e?=sWm}h$;xsDmQLH{6wsK`;VbcH`_Z9|+(S23dRj-s^O0x{AOrSa#c%v2aud#kz3fUxw7~v5n^PyIkk-U51 z08_iW?n%dX5MZcvl~w}^k8ZJap~CmwX|nmtASfhzM?xyktiUt_j()^k)N1H${Gm8o zQ1S-WcP_Zg8)MzMmA|0{Gi1bjq)25(W65F@Zv+2#N!ht4<8TUII4;?3?K}vX776zi zRHmjT6fF1(=9}1enn6lsW?9JJ?n80sW|emid*Jxshg;XKV<$7z*|{r`z~>&w1xQ-@ zVmWTci+%KBRPeg?5k~HpZ;gxXRpy}|e?UljJVUD}c95TJGdpAjL)<}tJ82lZ2z>M#Rs%PS*vpS=EzHw1Y2DdGZi3BqEEFT+d?;e=h8!n4 zR-*p?7!0^zF7p*`&2r385K6iX0=I#``XdUoUX@~@P{P``lCDR$WLD`j`n0TjNm)s= zPYOS~%c#Rv$3?T$@l-AExi8OVZ^3?N+(FVII!pR^FMr7cA5?CC)z>?_&89$`2X2k? z@L-w}RGJB*@VZcx-*K#db*8T#{_VBZGuXF7c>A#IDZ;^Z(Z){AE)ZA$!!MT=ev4*o zkNI%i6xH!Ees&r-%E+PtV+FK42yx@3YC(j%`t;~K`Dl!}P$RJ*5z$9p!kB`WEPiOnAFATL4L4&4a)JlI_v*di5PR5B&g+9Xz z*Davu0;Tq$xab=)44g#bvwf#1G|Rxv)^)khzlgVgH-*x><`0GBXSkvVS;geoAxQZ& z-cfAVfeBnw1(CU(5fQV`MK!3Jk_scg9u3l-3H4OW59Vjo_?m*?V{T(doM@4 z#zhO7DZq0QLK^_hI74nJWP@?y+Rcd7D6OSG$1r8l%wKvnXdX9Eyzq zpjt++YthcAP0Q%=UY^>g^l0 zE6b@Gt^H~PDSEQgKWRMWMryU*<;#CoS{Bv6jOkx&E!`Mngos@80&9&I0H5}Lm!~I6 z0DevhB|yUeomdjLiJ?_5?BBm%SU>*8O_keI3Mj&w8-L~2UVv|rb;6)PWYfA3&xe(765-Y)2-Q?^(C->lD9Fm!7@p`)Q=Bc zga4%lJlgOtppgA{X4YBRcjfR8qg(LR|E!sih)*7ZGQfgfW~$rAP$Yf+6W9;r6?YpA zzfjolr+!-4DblDA7&4rR#hN4eIx??Fdvm1!kHqRRfl0JHNUY{M9S|%tpwrIVmJK|= z98b@c)EiU0EyA~%<_s}+X%-A2FsA)QLHEpNrqk$-2aJ?mmOGef^}v`Ok{+I?^6#lL zvs^TegEglbsnZ8QkgoRW)2EN(CE1R6%g*APCD_-~Lr+>aNsYQPnsSWkPbJZ+WAYzC z3r{9su|iM^cebIBFoql>{&#k}h_#{o6`S=T(1oxU6AQB24*;gIvdi74XKu<+z`FBY zfjFxmr1>4s4cD3s9RDCH=ye?==6#Y;4}PjZ^j=YWx%_0Br3xwopo-^BKI;^Xr11AR zuN@~D-G-CcuSp6Z=Y0eCs|I#kSG-A;+ulILCI>n7Yk(?-$v}I8N}tBtYe6-;GNg1s z`uzTAv39P`|4zg&lq8?nkY(<4$;jdfBi^c(xcd#H&G}A=w=Rtx*HahQi%)&^s{aCg zehb85-}$>mxjHaExc6KrR7j9nGBk5bKG1&!=^k8Od7jQr`!D`ZZ2TaQV?JlAMrsM( zIR5)xbm+&^8-9L`S`-WkDh7o)$njQ&b%h#{Jf_@xQgc#OtB{0VYY4zqP6~45nRTF{ z4m4G5cHOOe8aw;hgW`?(?x{|fp3TaGKl~*1gs=HBUxZ-YTk)}*6&Fd_4#9HFeyijK zzNkzo=1rbXP!6ju8ThbRe^ELsV_!)9e^*D;%6rJfhKGt>()2)(B`02J03D$kzXKqFzhzgqRLfL1rn^>|L6TSB6XNFS@qlYAgoGs& z1Pp6+e+URX!2G8cz@g0xi`nw4c;uPR6JH^9u0-I=VndO#rO?CcKcIpjTTlV>PZ37e zta{KyoG!MJbAqYoHenQM+W~5V0<7t_XxC=YGMm<(1eE?8@Um``DyJ;JKy^qr#wOCd zQu)wR8YJS>sohbih8<^78eLJ5sq^x(R}R7r&CQ_Npf9ztO4!93Br+3}z`5xRB%UUr zjU&P}tufo2BcWmwA5f}wY3(#|QTUlI&iRPoh&kQ1PD&E^jWR(D1`Co2P@5UPQ4-pU zXxW)^nj1yjj^PgQ5MA-cH|ce(1}ss@(xzrb@F4vC&`k7@^|b6h_)VE-9r~pbt3H+FOJMTpjX8H8F<-zi#-+i~rpuO3KPATUHz8Q9|mu!U`OLFD~&pvJlwV!>H zcRJ;I*K?8YP(N`KXlAblEyjn2Kl0}D>Tq?Ai=T1&yA$~mKNwvz ztPma^ElhO%0D6#BM7}G?@W;_CleI3CM_aMTpq}`5>+WV_ zHsx&a!>^fwGE8XhF{|Xh3t(=XUVILS+%-GlN2Qq+w`3q=1oh_HM#QkAKnFVS1E`bw zhJDcBr{wVr)rinn&-uO+K$ow%LsFu5Ygmx`0rnx+djRH@&-EMwm9a_A+cwV)tn|4g zpBdXdzZW=R@gqR;ot`Ndv^mP?aNmGa-_%_9(KhX^2isf5=fEIn2tDU*;5j4RC~Le8 zimgFzimffV+drT|AM=R>!ZJV9C4MYUS_5`wAh8z9{Rz6Ik0n@JxLYQTo~PTEDZC$W zv2E=Lf!_e{RS>GYsRG?~&+o-2hW=hed|7=$j)ZCbbs>1y8UDDRr(0X(fA>tEU`2k7 z65^V~=PZL@*TE30zX<`+xH~CiX|FvGV8_Jwr#2TCx+P?WW=s?Bt({DO3LrgXY~9Elull9h=_@@YBWy<>*E zkNt|;dc%~hpch{kFF6xr0X6fltU*s{v+3I5Ro~l+(*Ewd2BoDVo8MM|u?LO(W!5Q< z6*8hah|!otq0xqpse^!o3!JT?71tryqD#B!ACFo?$KpI zDA5Ek;n=a)1>gXkkc9>CJ=n`|wW|56LS4<8KdZT~+qJQsRm!mPs?T#X+M8BdW$f?m zg5UjL&vtZ7NnP^f&qQ=YXdw~b{F0De@?T#y5w(TGN(s+9kz&%-Ca5Oo{TEzW(kW)? z{WQ^(hv%Uuh(mv}%iXKTA7Zrus(ks^Z9zfTxisDw`0DvAe)L)3uIP|YYBFzuqPODziQ+A79iBx@i}957MvPDKj_woXv&Jbe9PvW%l$bulC4jow(m{)Tb8!X zdgU|`y*cUH4wW?5s{{GkpF#UDXmA87`}*p7vko6a#ODJ2oORJ>Y`x17!R}k2Ds%Iv z=lb>QUA2Hhi{s3SH5o{$g$2rA^-zfoUpHAhX`PK#I6JFW{%o4^dwkw;z4%=KT}ZVq z*+5%BR-q2Hn8UXuHp`mTq1k#DZJ%>rz=XR=0t3GJTU2?vxJ}N zaR0WBVw-aw3ST#6)Jp=2^sd(dHenz(C2!Ujk|<@mvxi;xhiLv@9)DCX{uYRz)*u1l z4G`hCqT;&i4{B)!Vc)-+z+!f6j{8ecQtym@d=7|7+yu^z>L%3L#^*ne_#EcI*K<;K zG6$6BZ4S+Q_C`N>^g76e34wz_3U}SfxLHF9LYH%Y7cTz0W=oRfjDx8uR~#@}0Ah46 zv$#KAF7Uz1zo7T`qTBT1M-u?QE?>TX;@`2K1yskQ#M0sFs4(83YoMBOb1cL$>P>Ja zRp?Bgp)*-df5sb*&KLnH-IkANAaY9ek zZozi~V==Y_=v#|;coNG%nr*YNVd%iWV<+2b)vWh4r(wc2rvV4K)2OY`(1-8dlPC$Qtq- zA#ZQcyk* z11_&4A|i|=Pn_W3rfq*qXC4xSHOlOaR;0q~BhDzGJ z1e8ayFVi`3;)K>Q=Bqz!PlvqVU@mwLnw+qhafnYOz4d815M^y~J1G$Ys){T9aP9_?0fH2M5BjPcObvFa9jqzN`rFIj!AZCjWN7mP^?{U%yL*mW)~9 z{gcddPnfoGi96a#<4-c{^pH3BijGL;!jCgOguvxq2fRpJMv=i6eSk;BIfo)odIUGe zAFl)`kzPLF;t?+ya{be*`IA9DD!GG8CX@J~#j`_+DfSj>lFU%B8gAfVfrTNjAp6`N z9&UZD1|O!hZdFT+RldW}3NvV8MK!?`=@$^QiEnb533KA&>fT8Y zT#UIYV&leG%!EW^`j8N2Sqw9E4o42cg|7|PN@zHIe!7#}Ergb0>Nci#NsI&>_X6Qm zu#tSjl3dk@*7Ba|sy)uMnd%$7#RcK8x>(@pXnaIKy(1C3c1>? ziBLx&-mqkwL78oMJP6pV8D9y}M=l(Qiy`r|W)7Am4vMZqP6g}X#?sBc-`Svy#*?}JsT z9FBzem7X)pA($EPeLp-r{XiSb zCzj7rdo9uZ)&PV_ECfa0>#PQBuWkz-qgK~*!^8LEuNIV_U!|Po;Q>*naWj5nz*FCU zR%*)#?AEUF#&pnTMls!8U3PU@tzc&Pz$MfkbmML^0aU@Wk)n|5TU z9`Xc3C_;^p%6_P)d)>h1sEty?~~EO*+F zqNYt`DI|OMHb_Whi87K9LYBc;hI`#KmJ(UAPRYKFeHmk>ax+TEIx&VMW-=K2WXAA2 z@2T&-pYQK)_|D@|J@kIO=bZC8uk(66pU?9;htZ=Z3-G$RY1X*~VR)}RyxHK32%RA% zxFJak$fiOCC6j%%p#!f+DY^bAM;g|L9r*8TKy1#Sso)|ttYbz=$y6cy| zQZut%rc+Z0-De&{)SnQ}JRSgQoR5&c6aNq2CwE_J^G8Qdjs)@ed{_+%Y@w)fVrPZFe=! zS5Zf`jd^nPx6S27Bh8#IFwP@0lg~jnC>bhFuayzE6R=^anVF$^b4wyWgQ-It1Tv?P z(5?*1#K~V_lMBI*`odFhgCZ?N@nF#}+a8knOZs~2lcF5J#GK_*fr)_zCSXBMpOrZbEo zjPOr~-805uiRJKWL*PS@oM%x;FXvThNl8X8AeMU_CV*MM)mHylJUH6P^jDZm#?%m) zG$xodtQL@$cl!DJ3&*uL!x#6mNppg`vVIsOhstVs?CBE-tq+UB)5xGiC&`BSbs9(T z>UT%b$?tc9_a295?%26g_^X~dT(HK}+E_}Km!Lp|#oh&xrkT+Fq~yQe+6F_P;m+Yj zfN8)veFP#K1Rv38C!Iav8!e6;J48U#rQCPn6{_S- zg}@#lrD#Y+kH_e3iuHu2TJ_sbpzQ54E}58IrQ~2%-F}%5H$wEk5G=G_6_JTkFbnt@ z6OP?3LBAkNJaNw`G{QwFg0>C*ospziCrJgwZR+1KyA!COvk(n}I;(pKUW&L~=$@h9 z4_bqg+7AaV4sID8?};E}mGVx3)2v{1_etVIU#i46=dwu~adS0!`@t-7mp_+u;MNPn z2mF1u`()Z*Llx<>>WlAN+v@NyF-zPi!akXVO8M}%+?Okc$XW2miyLnsJhE9(_GgBP zY{coX&c>POcsr9V4VRHu!dnt;L!&hCtIyohZLCm3PbOx@l`lGTYjd}D`LXiQJpM+a z&t<$cxBX*5rvGTg>7Ct**JYQC8 zllS>S&fWj7iwc%}IyIj~m9--T&Kl=GS7#{J&BiqkuSZ9h=GZq9i?wy@Z#MBi-H2$F zbxj*&Vtg+l`o%%cee5LJ2Mn)g1YFQK;t^HDWpDq1jR|M6si($1Z9X%t(Cclx!Vt%8 zor9%`NmkG#w2_qi4L9#B*v;$ta;-bB(&OvJ}7uLqmoJ}TqUnx*6Q#XC#8$P8sg zcVTd#@Z4tRZ`|6khaqgpcNB6k$G*g~#$?ojyUpyjse6OtO(F9zqgfqZ^!xfanc!QU za^3FsmvgitoG@5D){vC zb5pQ#k066vPOHGs<_NvIQ>;yieP{H<2^^ZZmRFxP9{iH`xR~${aa6)58E>v?;r}L^JOlen^cQ4^Y3xy82oJyY%4!)|(e=Oo<@WIg8>5nYyW<|$O-~5$Fe26lW z>2{3u5NLW(Bbp2^KW>k*Iqh@UEVbd`=%@NsS-elST7tOy(f#MYcN5A_yAx;Oy{>kH zwkUdGBu6#2F8zMD(2B@yzat_ z4}2w)7aSUZc%=4N0D+8wilo84uv|*$?zNtLJ|9J(FlFjF#ksM^|7|V{z*N&9vdo-a`!f+DpPmp3Gh1qZYMx zEVZzoGD_wLhp(9IUd^5qrr_q^Y>NmBn|(!?nk?J?-@P$M{0`40BH8yrchX(P=c`-} zhuUrt>CyFYx-eg=y=YQL#vX%DgJ|7yTe7Vco~t9%Eei7B4$vs}5}wfA5SA{{p7*c|yFGpEqv}EitPRNI_cu4VDRyUc||wWr>Fe#J1#J1i|)? zWp@MXE<9QH&V0`G6Xcq)L%N?=POfN}XI-6G&sfN~^9iWeLPAM7*sR_B!`!HmkrC$r z9OKIR_B8(LG!uvOBD~794c%ZG*^{7=9Ek{7 zug|RB;W3N@MTB>5fb*Vi>9 zB1VSz*$Z4K^nCOsh8t}xfAgYBqwBoEVedPK1Srii+DUS)C+JT;0PbQ1{q+$Ap}~)g zNLPZp9cntheKLe!8kEFOykxD6!os^+Kp;lwAF{yud4gDU2dA0epnT;+H(R&Sb>~06a<^$ zA2C*Q;ZGC2*zgmaXKYy#>#s4fwR3@adf-1vQuq_f;PCU06`KrbM38eugzgOvdRU=h zR)pT_PYm%J_tR@k6tK*5?O?WVAOd6CEkSq>1W+c(rmgJQAD)hH>FnWNVOEH_eBBdH@k9%S2W|1rqPgq-sX!!4ko#Z2-Ve?mlr@#~7g}k?2+6o`dJAqT;P)0m>}r=0_4n(NGo zpOO-`L)L^ce3qWG#i!wjDYdMC9v4|Hj{e5TPW>MKW(+n7=*obJ`2iB-h^Rj{968%C zYfLa=1g{k6&sWSzR0I4Lzo2y)Eb4Y9!%U|HaFtVu6qaoEqT}^mF<<_4oNP$-P!n5p zYUTpcoJWh=&X&@|$g|6i=X!s4Rm*^v8-}FfIo@SLi+) z&6351v`u*;yF5PdHy>b=lm$bo7HO5-b+D3b`qxi1*=pNqne2&yWNURC6LZ)E(GQ^1 z#6?m8fcAC3sHF%QeD;~eOIxTUt>O)kEQTPD&!+1`a1P|C;DMTnC=CX&Q~1;_iv&UB zJ*nvWa`Z6VIUwg)N*l{v!BgYwKVRIg67Lv?-30@%_I8R0fYFH+0@(3R6@szu4@s)0 z^noCA?;ry@o_`74#5D1KV&NlvF&&Tz=p_MW70|1j=T*#>{sXf+5FYeVt5v0InytD_ z37+*7IfJAW8>g(W%da(iQ)&l9Z;WNi)qxeS3RIpLJ@RN7m?#056;Rcekg_CbJjwePxq27yGZioAfKL!jlT#{a&AOj;A>3*JRb^5TuF> zszR@fo4vY-n5-xZ?FO4;8FDVp#JR2TTQOJxdjxXH(7z;B^6_!=oOO1zKm;`~nlXem z6)A6a#WXe15QxqYo|pB0kvA@gu6NzGN@*qzz5~`gdX6uZ4mHm}%HozMP+ji`K{Yo0 zhB@*Tm2TVj>t8$IG0L?uV@?#tD$J~M!mIMC(U;5l3$LRKIt^Y;byhjof>^LIe!V4- zJKZL}VQ&RHlSZxIE1cQz{u;f~_suX$`_DwIyr;(+yfn9>)9c_lZrbAb-B3wSS_qH`r>jMimBvp(H`77X%f_U5tN}$<5TSf4g;ln(HDiU3QQ{!8(nZ3W`oE*P41D9S(I zNm3aQ-OS^rPw%)68>U*Z+v0ahF#Q4I%OtZIZv=_6P~iI>Dk3inG_Gi;_+Jwj;JapS zMj{p9ONcK9Adszuw1`Va`=$ZO1N>9&B$?)7o>ANKVnK@=MapQo_gsGGkb^WnPGT1H zUFHjSs5M&jD)91_oXpH!6DS_7e;Xj1g`w*asEf14j59;8lOXUK(gYg znhGp<6^GRoJi9*Zj=AvdDmYx07rQ_ZPcK-z02@+*XBL>IFX{r>2NIBe$UYy;1Tt&I zS&<0~So%>&S?G8k?GCfp?e8BH5GV_?XzByk91ysdg})f6*YVm|4QYz(`RcPLz1D zX|cKukR$Pq*W-?)FkXp+zIk}3Zwx73rj^W2*c1<5Hh%@nLHP8-Unu( zd9|RZ`esodY^X`Cefjl$9v!)_nj=bc2tN^&n?PmvNBA2*o{1$~1gj$_AOaLy zML+CXDPl)769=2dc7=8h0)Gu#&FH4vFeX+&rjpJE)n_r5XWLkMkOFvnd6??BKYAeo zg)3A}zMoOCLK}C%XcKiuyQ_4Iiw-XjB&Q7EbX2HgkA=pZ5eQ#!w@KG(r9t^6WJu7*8wvtdU~(^^8vzOoF%0X}UqbDBn=o=hcM{D4=x_YZk$x?XRatBVz5}9RBTRqoW z*Z1*FX@*S$h`ic?)P}lQw7>hxc7|TpAulDo`$K+9_bGdK+w!qr50a_ufa|357}Wd= z=7aN?&-GzHv8yv6>rWvfX4M+zSig**I@ixng;L92Mm2<_PcQiLgP@ymwpEH3UaZ@s*Mx0|N){mA1L~kE*e; z)=tWldyqN~^dnv(HtP^v8}TI^K%ZQmj;@94gI0nOb96ZtUv0g_IRN_s5t%2tf_2^7 zMCuw#?0MofZ_fZUg(yvF)(sD2+u}hl5}0(F}B6+^V~dqb_fCj=P1GDe*nE4EB3J_0GF@5UaxD+ z@%Pr@j&1As^OyM+AfL`cxKoJx7DS=}LPW3&h`P6kgNGsT*{T8;@NXPgcct%sU)>H` zU0~K#4|x5rS7Y>VJecJ+y7wt1kNw z0^c2p&5LW7NuVsl$vtT;Wn2Ld0O1Fpw%7I-TE4tey6BcfPaO!qx?@a-=kNQ5n#*oMd zNZYwO&gh@j`{~NJf$AhVf!cD$Y)KowSdE?8n|KgJtFmM*Q${-1kC=mOyplhLF5DmZ z_L#@VN~dXVrjO0;#Zzspb1ScttUDD3D`-{c`iWpW1zQA;6M$Xa<=tSD!KI#Wyd}Q7 zWqLLvdiEcs=jb>h*(+0@&@HF!Tx+L@6l774uFZ`kTLxDp7wA#*FiAgoa$OuAj!h0BZwR zXYC%Tb?@6ybLjg3km2jxD*Ap{%Pa0Kmf|AuheUtc=U7dkEWjdMVZjN zj3_WtK9-Bf>jiR#6Oj8>DP#IA&ps)_ETXBUqe_Z#9ZSsXE{+NP7ox>10*0*2Pamn^hC zm{KhFCv8x3V?QhpJd}-JDo1LQh#_?CmDK_?YPE2pqm*;l?^w?jTV59)LuM0 z50Y)@$_*}+;Rvw_2Mv$@pB$Sx&-Eb#&+S(|4vwE6Tg@m33AE0q_Z@*VlBztP&wjuLkRUs+Xpp}%YiM1)_Al8YJxECY4lWdz0f$uV?>?M#-b$CLGn z0i}s0oOP4TsV6v1d|RAeIre<2J1P-d0yqQ>C_X8QEb^v|)bbmbc{*w1^w zEOm5t>RKW;Zc7?kH~XS9vF{}k$=G%kkdS&a$&8y5b^cO`4Y3j{OwEP24`35YYja9ND9hd+Tci?qLvNNrzo7L0t07~Q)K0IzWhIr55gV(_jBF5Wzl0;Rr z0geZu4~@U{%_1qs;aV33;cma8mj{=9hL%$t`b>{`=im-@mz@QFJj$OhN^q>*1$%S4 zjkPD~$rJxtCrR&C6<2IKMOZ3RAC_ndLt7&@gn28G4ZO)yeL(v9+ENdR#x_qos z8_XU=1G|D-{zldetPxay*QmuTDX~6|F>cs`HVE}~Ugk4w|IuT}1Kg>kBZ%Z{f|z(T zviB3$nMB%G&$qFYTTiceMQA+S=s#VOVUCoyYuXU6F#%f^*T9xV&{s4GMvz_V2?FsE zkN9%ARRwuk#5o4!(oer`U3N{N)C{Y{gUV-fglo*jM^2J5Ff@92W~c+u)Hon|_~zPI zhN07NZj|+}ESCM4Z#Q!*Y3jz=FRR*f7pE77(GQk(n%Ep%cJ%5LQNw(|BnLt+s{jVJ zFgd`=UI@YPHQ2F%hD?Y`-imOvrFb%^mq#b-0Hyf_oO2QqI=@BUfxOY)TjyymFIukY zQ|#q9lAUv-@zl5e*OO)rvsK$VW`!ACX+w$R(>A*;rqdk#isvZ7%Xp@Xp%Tz28lgd5VFX6D+=M));s_8EF z_ZjOVwJ-QVB8;<-@{Y4UNWe0anip9?;97`hvKbAvT~Z{RU2QMez=MPB1`xL&`<*%E zST!e+4(f;Or`{)xF)>+&pWlL2aR#b%>QggUGg}I1Rl(?nug-j~ctizE*MWP8QoJM~ z2c?4M^~J5EK$GPpIDYcW@s(hQTlh5{V6EzcROKw1pUt2FkZ($89|)W#u*|_l5SH#Y zANu2pQ$(eqa6tb+a0Apq9Uz=0aGn>Sv*ai4Da7YIgX1uZ*Ju5Esz8BH;sLGZsXDCO zX%UxB$7h$Mqa0)s@zUy-0Jm0mpQG{UdNWBT{g0nt82CI)$dkc4Q@-x?q=q+@HBFi@ z0JoxLg5Y^&pZ6LZbc{PV*kUrHejWV5X&ACqRX=?D14vK+FSUCKd@=7p!({VyPMj$` z7jX&{pc!$T)sl?BN&BwkVh@XFCA1@cmtP$Kmp%Tf{+TP?pTrc_)8lnV$OCKSM1+Uo zKqZtW5|Vm4^9Q7-A?oo01w!+EQ8V85&roJk5XG;-S6Lu9Oxg5}o*0mzDd$_cERaRM3WFyy_~f3+zg2Ld)}lXb#8F2py8miz9Y zy^UR#AiZKX0ftDv_r1aW`C|TzwSuph=f;TSJNeg1{sH=kBj^Kni8&c*g{glpRLd;c zSjl-B$1I{Is*k)?1Ds;ztYFsnBqutC05{A4ZfI37sfyA+d!*@afwy^VRJ(-hsepro zuvu`%4=k|QceR(=rZH8ZmH)Wdld3Zd(+=QyzEW>pLVkO7U3cw#8^VmkISjKfzXg@& zUbK*E%8yblOS(ZFtZINaNHw2^<2! zw*XamzJ?_BsKwytBcO;0j)safzJl9HK_#Hj+ovSvmv|kVcHd$;!4XK?Z)!|CG&GKM zbAm%iK1FjB`#k8nS~y=|QjwcM*9`RUnLGNuo>i5=rFgG(9fn^jIOCd@ljM{l)!~n=7}K?+y`R=jI49rQk*Pt9>V-O^Xz0^D8tG4xcs_q#E#WRxV#`i8d~d67ODUzqUWvkt1Y) z=zk)x0eCF-+UG%B0C>h6f)ec3J^y2V@a!B`z#3ZpeXfs44x>2NU9A6i!}oqwfG0+* zJeVVRP%7a$!l>Rj5N|f25`!dFK`S*I2z7*$Y2U8{bDhINB?F0p)w)9)ma>J!|s}6X)js zsf8kOssSZ#ia>-zt^*1mv8|J=9stn--{!`qwRTu0@e2l#r=A}g3`&GQmQ5q z1w3EilHhamC0J0SA9SH7_USgpm<-DYUor9DE88V2&$y+o8*(lppfwG(iwXPj$mEzK`Qsw)UvJ=BU@2D@!H;i{&<(cGxBZ-|vCyoS{#o zSUkX^Z`+p~($m?Qd7-AjS6FAtlh)(yj=k{Cv|QJvCy>9l!-R9*8&F*BO$=S9){uT6 zJ~b(hg=tXRj^`d#?2|wF{ynF&y^(za}Hf`!T2_WjlW`}_Ya@P8Kg-xfFz a|F${nZ@xEeZ`CIB#Mt06qT=_PfBrvw|Ai0$ diff --git a/Svc/GenericRepeater/docs/sdd.md b/Svc/GenericRepeater/docs/sdd.md deleted file mode 100644 index fe7106bb52..0000000000 --- a/Svc/GenericRepeater/docs/sdd.md +++ /dev/null @@ -1,42 +0,0 @@ -\page SvcGenericRepeaterComponent Svc::GenericRepeater Component -# Svc::GenericRepeater Generic Repeater Component - -The GenericRepeater component is designed to take in a port and repeat it to the output multiple times. GenericRepeater is -typically used to take in `Fw::ComBuffer` and log the buffer to a file and send it to the ground interface. - -## Design - -The generic component has an input port and an array of output ports that receive the repeated calls. A typical logging -use case is shown below. - -![Generic Repeater](./img/repeater.png) - -## Configuration - -Generic repeater maximum output ports are configured using `AcConstants.ini` as shown below: - -```ini -GenericRepeaterOutputPorts = 2 -``` - -Here the repeater will bifurcate the incoming port calls. - -## Idiosyncrasies - -The generic repeater does not copy data, and thus reference port calls will not clone references. Care should be taken -when passing pointers and references through the repeater. Special care must be taken with items that need to be -deallocated, like `Svc::BufferManager` allocations. - - -## Requirements - -| Name | Description | Validation | -|---|---|---| -| GENREP-001 | The generic repeater shall repeat calls from input to output | unit test | - -## Change Log - -| Date | Description | -|---|---| -| 2020-12-21 | Initial Draft | -| 2021-01-29 | Updated | \ No newline at end of file diff --git a/Svc/GenericRepeater/test/ut/TestMain.cpp b/Svc/GenericRepeater/test/ut/TestMain.cpp deleted file mode 100644 index 8017863c5f..0000000000 --- a/Svc/GenericRepeater/test/ut/TestMain.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// ---------------------------------------------------------------------- -// TestMain.cpp -// ---------------------------------------------------------------------- - -#include "Tester.hpp" - -TEST(Nominal, TestRepeater) { - Svc::Tester tester; - tester.testRepeater(); -} - -int main(int argc, char **argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/Svc/GenericRepeater/test/ut/Tester.cpp b/Svc/GenericRepeater/test/ut/Tester.cpp deleted file mode 100644 index 77fcbfa0d7..0000000000 --- a/Svc/GenericRepeater/test/ut/Tester.cpp +++ /dev/null @@ -1,111 +0,0 @@ -// ====================================================================== -// \title GenericRepeater.hpp -// \author joshuaa -// \brief cpp file for GenericRepeater test harness implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#include "Tester.hpp" - - -#define INSTANCE 0 -#define MAX_HISTORY_SIZE 10 - -namespace Svc { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - Tester :: - Tester() : - GenericRepeaterGTestBase("Tester", MAX_HISTORY_SIZE), - component("GenericRepeater"), - m_num_msg_per_port() - { - this->initComponents(); - this->connectPorts(); - } - - Tester :: - ~Tester() - { - - } - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - void Tester :: - testRepeater() - { - m_msg.resetSer(); - for(U8 i = 0; i < 32; i++) { - m_msg.serialize(i); - } - - invoke_to_portIn(0, m_msg); - - ASSERT_EQ(m_num_msg_per_port[0], 1); - ASSERT_EQ(m_num_msg_per_port[1], 1); - } - - // ---------------------------------------------------------------------- - // Handlers for serial from ports - // ---------------------------------------------------------------------- - - void Tester :: - from_portOut_handler( - NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::SerializeBufferBase &Buffer /*!< The serialization buffer*/ - ) - { - ASSERT_LT(portNum, 2); - m_num_msg_per_port[portNum]++; - - ASSERT_TRUE(Buffer == m_msg); - } - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - void Tester::connectPorts() - { - // Only connecting 2/4 ports to verify that repeater doesn't send to disconnected ports - for (NATIVE_INT_TYPE i = 0; i < 2; ++i) { - this->component.set_portOut_OutputPort( - i, - this->get_from_portOut(i) - ); - } - - - // ---------------------------------------------------------------------- - // Connect serial input ports - // ---------------------------------------------------------------------- - // portIn - this->connect_to_portIn( - 0, - this->component.get_portIn_InputPort(0) - ); - - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init( - INSTANCE - ); - } - -} // end namespace Svc diff --git a/Svc/GenericRepeater/test/ut/Tester.hpp b/Svc/GenericRepeater/test/ut/Tester.hpp deleted file mode 100644 index faf4daad32..0000000000 --- a/Svc/GenericRepeater/test/ut/Tester.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// ====================================================================== -// \title GenericRepeater/test/ut/Tester.hpp -// \author joshuaa -// \brief hpp file for GenericRepeater test harness implementation class -// -// \copyright -// Copyright 2009-2015, by the California Institute of Technology. -// ALL RIGHTS RESERVED. United States Government Sponsorship -// acknowledged. -// -// ====================================================================== - -#ifndef TESTER_HPP -#define TESTER_HPP - -#include "GTestBase.hpp" -#include -#include "Svc/GenericRepeater/GenericRepeaterComponentImpl.hpp" - -namespace Svc { - - class Tester : - public GenericRepeaterGTestBase - { - - // ---------------------------------------------------------------------- - // Construction and destruction - // ---------------------------------------------------------------------- - - public: - - //! Construct object Tester - //! - Tester(); - - //! Destroy object Tester - //! - ~Tester(); - - public: - - // ---------------------------------------------------------------------- - // Tests - // ---------------------------------------------------------------------- - - //! To do - //! - void testRepeater(); - - private: - - // ---------------------------------------------------------------------- - // Handlers for serial from ports - // ---------------------------------------------------------------------- - - //! Handler for from_portOut - //! - void from_portOut_handler( - NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::SerializeBufferBase &Buffer /*!< The serialization buffer*/ - ); - - private: - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - //! Connect ports - //! - void connectPorts(); - - //! Initialize components - //! - void initComponents(); - - private: - - // ---------------------------------------------------------------------- - // Variables - // ---------------------------------------------------------------------- - - //! The component under test - //! - GenericRepeaterComponentImpl component; - U8 m_num_msg_per_port[2]; - Fw::ComBuffer m_msg; - }; - -} // end namespace Svc - -#endif diff --git a/cmake/test/src/test_unittests.py b/cmake/test/src/test_unittests.py index c287447128..8dd9f0f3ea 100644 --- a/cmake/test/src/test_unittests.py +++ b/cmake/test/src/test_unittests.py @@ -49,7 +49,6 @@ "Svc_FileUplink_ut_exe", "Svc_Framer_ut_exe", "Svc_GenericHub_ut_exe", - "Svc_GenericRepeater_ut_exe", "Svc_GroundInterface_ut_exe", "Svc_Health_ut_exe", "Svc_LinuxTime_ut_exe", diff --git a/config/AcConstants.fpp b/config/AcConstants.fpp index 7a810b787e..c3a2e81da2 100644 --- a/config/AcConstants.fpp +++ b/config/AcConstants.fpp @@ -15,9 +15,6 @@ constant CmdDispatcherComponentCommandPorts = 30 @ Used for uplink/sequencer buffer/response ports constant CmdDispatcherSequencePorts = 5 -@ Outputs from the generic repeater -constant GenericRepeaterOutputPorts = 2 - @ Number of static memory allocations constant StaticMemoryAllocations = 4 diff --git a/config/AcConstants.ini b/config/AcConstants.ini index a3de80c54b..da417a0c2c 100644 --- a/config/AcConstants.ini +++ b/config/AcConstants.ini @@ -16,8 +16,5 @@ GenericHubOutputPorts = 10 GenericHubInputBuffers = 10 GenericHubOutputBuffers = 10 -; Outputs from the generic repeater. -GenericRepeaterOutputPorts = 2 - StaticMemoryAllocations = 4 \ No newline at end of file From c8cd23b3e832c5c6098157ea992c13ef15908923 Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 20 Dec 2022 17:35:25 -0800 Subject: [PATCH 116/169] adding config directory to build (#1775) * adding config directory to build * adding missing cmake lists file * cleaning up fpp module dependencies to not include includes * fixing config in externalized deployments --- Fw/Cfg/CMakeLists.txt | 5 +++-- cmake/FPrime-Code.cmake | 2 +- cmake/autocoder/fpp.cmake | 29 +++++++++++++++++------------ cmake/target/fpp_locs.cmake | 2 -- config/CMakeLists.txt | 10 ++++++++++ 5 files changed, 31 insertions(+), 17 deletions(-) create mode 100644 config/CMakeLists.txt diff --git a/Fw/Cfg/CMakeLists.txt b/Fw/Cfg/CMakeLists.txt index 08c0c2f2b2..b3d675f59a 100644 --- a/Fw/Cfg/CMakeLists.txt +++ b/Fw/Cfg/CMakeLists.txt @@ -8,9 +8,10 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/ConfigCheck.cpp" ) +set(MOD_DEPS config) register_fprime_module() if (FPRIME_USE_BAREMETAL_SCHEDULER) - target_compile_definitions(Fw_Cfg PUBLIC FW_BAREMETAL_SCHEDULER=1) + target_compile_definitions(config PUBLIC FW_BAREMETAL_SCHEDULER=1) else() - target_compile_definitions(Fw_Cfg PUBLIC FW_BAREMETAL_SCHEDULER=0) + target_compile_definitions(config PUBLIC FW_BAREMETAL_SCHEDULER=0) endif() diff --git a/cmake/FPrime-Code.cmake b/cmake/FPrime-Code.cmake index b2f4ee2f82..39dee7a408 100644 --- a/cmake/FPrime-Code.cmake +++ b/cmake/FPrime-Code.cmake @@ -25,8 +25,8 @@ if (FPRIME_ENABLE_FRAMEWORK_UTS) set(__FPRIME_NO_UT_GEN__ OFF) endif() # Faux libraries used as interfaces to non-autocoded fpp items -add_library(config INTERFACE) add_library(Fpp INTERFACE) +add_subdirectory("${FPRIME_CONFIG_DIR}" "${CMAKE_BINARY_DIR}/config") add_subdirectory("${FPRIME_FRAMEWORK_PATH}/Fw/" "${CMAKE_BINARY_DIR}/F-Prime/Fw") add_subdirectory("${FPRIME_FRAMEWORK_PATH}/Svc/" "${CMAKE_BINARY_DIR}/F-Prime/Svc") add_subdirectory("${FPRIME_FRAMEWORK_PATH}/Os/" "${CMAKE_BINARY_DIR}/F-Prime/Os") diff --git a/cmake/autocoder/fpp.cmake b/cmake/autocoder/fpp.cmake index 6e64de32ea..cc8fc613a7 100644 --- a/cmake/autocoder/fpp.cmake +++ b/cmake/autocoder/fpp.cmake @@ -69,8 +69,12 @@ endfunction(fpp_is_supported) #### function(fpp_get_framework_dependency_helper MODULE_NAME FRAMEWORK) # Subset the framework dependencies, or where possible use the Fw interface target - if (NOT DEFINED FPRIME_FRAMEWORK_MODULES) + if (MODULE_NAME STREQUAL "config") + # config has no automatic dependencies + elseif (NOT DEFINED FPRIME_FRAMEWORK_MODULES) message(FATAL_ERROR "Fw/CMakeLists.txt not included in deployment") + elseif (MODULE_NAME STREQUAL Fw_Cfg) + # Skip Fw_Cfg as it is the root dependency elseif (NOT TARGET Fw OR MODULE_NAME IN_LIST FPRIME_FRAMEWORK_MODULES) list(APPEND FRAMEWORK ${FPRIME_FRAMEWORK_MODULES}) list(FIND FRAMEWORK "${MODULE_NAME}" START_INDEX) @@ -137,8 +141,14 @@ function(fpp_info AC_INPUT_FILES) message(FATAL_ERROR) endif() - # Module dependencies are: detected "direct" + framework dependencies - fpp_to_modules("${DIRECT_DEPENDENCIES}" "${AC_INPUT_FILES}" MODULE_DEPENDENCIES) + # Module dependencies are: detected "direct" + framework dependencies - "included" files + set(FILTERED_DIRECT_DEPENDENCIES) + foreach(ITEM IN LISTS DIRECT_DEPENDENCIES) + if (NOT ITEM IN_LIST INCLUDED) + list(APPEND FILTERED_DIRECT_DEPENDENCIES "${ITEM}") + endif() + endforeach() + fpp_to_modules("${FILTERED_DIRECT_DEPENDENCIES}" MODULE_DEPENDENCIES) list(APPEND MODULE_DEPENDENCIES ${FRAMEWORK}) list(REMOVE_DUPLICATES MODULE_DEPENDENCIES) # File dependencies are any files that this depends on @@ -210,23 +220,18 @@ endfunction(fpp_setup_autocode) # Helper function. Converts a list of files and a list of autocoder inputs into a list of module names. # # FILE_LIST: list of files -# AC_INPUT_FILES: list of autocoder input files # OUTPUT_VAR: output variable to set with result #### -function(fpp_to_modules FILE_LIST AC_INPUT_FILES OUTPUT_VAR) +function(fpp_to_modules FILE_LIST OUTPUT_VAR) init_variables(OUTPUT_DATA) get_module_name("${CMAKE_CURRENT_SOURCE_DIR}") set(CURRENT_MODULE "${MODULE_NAME}") - foreach(INCLUDE IN LISTS AC_INPUT_FILES FILE_LIST) + foreach(INCLUDE IN LISTS FILE_LIST) get_module_name(${INCLUDE}) - # Here we are adding a module to the modules list if all three of the following are true: + # Here we are adding a module to the modules list if all of the following are true: # 1. Not present already (deduplication) # 2. Not the current module directory as learned by the path to the autocoder inputs - # 3. Not a child of the fprime configuration directory - # NOTE: item 3 is build on the assumption that configuration .fpp files do not require autocode, but maintain - # only definitions useful to other modules. This assumption holds as of v3.0.0, but should this assumption break - # remove the check here, return a known module name (e.g. 'config') for this directory, and place a - # CMakeLists.txt in that directory that sets up the aforementioned known module and associated target. + # 3. Not withing the config directory. Config dependencies are attached to every module automatically. if ("${MODULE_NAME}" IN_LIST OUTPUT_DATA OR CURRENT_MODULE STREQUAL MODULE_NAME OR INCLUDE MATCHES "${FPRIME_CONFIG_DIR}/.*") continue() # Skip adding to module list endif() diff --git a/cmake/target/fpp_locs.cmake b/cmake/target/fpp_locs.cmake index 753991adc4..81592df4e2 100644 --- a/cmake/target/fpp_locs.cmake +++ b/cmake/target/fpp_locs.cmake @@ -8,8 +8,6 @@ # Static and configuration FPP files set(FPP_CONFIGS - "${FPRIME_CONFIG_DIR}/AcConstants.fpp" - "${FPRIME_CONFIG_DIR}/FpConfig.fpp" "${FPRIME_FRAMEWORK_PATH}/Fpp/ToCpp.fpp" ) set(FPP_LOCATE_DEFS_HELPER "${FPRIME_FRAMEWORK_PATH}/cmake/autocoder/fpp-wrapper/fpp-redirect-helper") diff --git a/config/CMakeLists.txt b/config/CMakeLists.txt new file mode 100644 index 0000000000..643fd4f29a --- /dev/null +++ b/config/CMakeLists.txt @@ -0,0 +1,10 @@ +#### +# config/CMakeLists.txt: +# +# Sets a list of source files for cmake to process as part of autocoding. +#### +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/FpConfig.fpp" + "${CMAKE_CURRENT_LIST_DIR}/AcConstants.fpp" +) +register_fprime_module(config) From e596a2bcff8d954d540454ce5ccf523279be61b6 Mon Sep 17 00:00:00 2001 From: M Starch Date: Wed, 21 Dec 2022 09:39:04 -0800 Subject: [PATCH 117/169] auto-generate connect ports option. Fixes #934 (#1786) * auto-generate connect ports option. Fixes #934 * updating math tutorial * making unit tests settings from #defines to constants * fixing missing properties in signal gen --- Autocoders/Python/bin/codegen.py | 4 + .../src/fprime_ac/generators/GenFactory.py | 3 + .../generators/templates/test/CMakeLists.txt | 1 + .../templates/test/test_helpers.tmpl | 127 ++++++++++++++++++ .../generators/templates/test_impl/cpp.tmpl | 114 +--------------- .../generators/templates/test_impl/hpp.tmpl | 8 ++ .../visitors/TestImplCppHelpersVisitor.py | 47 +++++++ Ref/SignalGen/CMakeLists.txt | 1 + Ref/SignalGen/test/ut/Tester.cpp | 75 ----------- Ref/SignalGen/test/ut/Tester.hpp | 7 +- cmake/API.cmake | 7 +- cmake/autocoder/ai_ut.cmake | 19 ++- cmake/autocoder/ai_ut_impl.cmake | 18 ++- cmake/target/ut.cmake | 29 +++- .../MathReceiver/test/ut/Tester.cpp | 90 ------------- .../MathReceiver/test/ut/Tester.hpp | 7 + .../MathSender/test/ut/Tester.cpp | 70 ---------- .../MathSender/test/ut/Tester.hpp | 6 + docs/Tutorials/MathComponent/Tutorial.md | 4 +- 19 files changed, 275 insertions(+), 362 deletions(-) create mode 100644 Autocoders/Python/src/fprime_ac/generators/templates/test/test_helpers.tmpl create mode 100644 Autocoders/Python/src/fprime_ac/generators/visitors/TestImplCppHelpersVisitor.py diff --git a/Autocoders/Python/bin/codegen.py b/Autocoders/Python/bin/codegen.py index ac36897c5e..e426cc235c 100755 --- a/Autocoders/Python/bin/codegen.py +++ b/Autocoders/Python/bin/codegen.py @@ -725,6 +725,7 @@ def generate_component( cpp_instance_gtest_name = base + "_GTest_Cpp" h_instance_test_impl_name = base + "_TestImpl_H" cpp_instance_test_impl_name = base + "_TestImpl_Cpp" + cpp_instance_test_impl_helpers_name = base + "_TestImplHelpers_Cpp" test_main_name = base + "_TestMain_Cpp" else: PRINT.info("Missing Ai at end of file name...") @@ -753,6 +754,9 @@ def generate_component( generator.configureVisitor( cpp_instance_test_impl_name, "TestImplCppVisitor", True, True ) + generator.configureVisitor( + cpp_instance_test_impl_helpers_name, "TestImplCppHelpersVisitor", True, True + ) generator.configureVisitor(test_main_name, "TestMainVisitor", True, True) else: generator.configureVisitor(h_instance_name, "ComponentHVisitor", True, True) diff --git a/Autocoders/Python/src/fprime_ac/generators/GenFactory.py b/Autocoders/Python/src/fprime_ac/generators/GenFactory.py index 96213e0d35..6aaab7ef9c 100644 --- a/Autocoders/Python/src/fprime_ac/generators/GenFactory.py +++ b/Autocoders/Python/src/fprime_ac/generators/GenFactory.py @@ -71,6 +71,7 @@ SerialHVisitor, SerializableVisitor, TestImplCppVisitor, + TestImplCppHelpersVisitor, TestImplHVisitor, TestMainVisitor, TopologyCppVisitor, @@ -147,6 +148,8 @@ def Instance(self): inst = ImplHVisitor.ImplHVisitor() elif self.__type == "TestImplCppVisitor": inst = TestImplCppVisitor.TestImplCppVisitor() + elif self.__type == "TestImplCppHelpersVisitor": + inst = TestImplCppHelpersVisitor.TestImplCppHelpersVisitor() elif self.__type == "TestImplHVisitor": inst = TestImplHVisitor.TestImplHVisitor() elif self.__type == "TestMainVisitor": diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test/CMakeLists.txt b/Autocoders/Python/src/fprime_ac/generators/templates/test/CMakeLists.txt index 437a242f2e..3994e67161 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test/CMakeLists.txt +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test/CMakeLists.txt @@ -3,6 +3,7 @@ include(autocoder/ai-shared) set(CHEETAH_TEMPLATES "${CMAKE_CURRENT_LIST_DIR}/cpp.tmpl" "${CMAKE_CURRENT_LIST_DIR}/hpp.tmpl" + "${CMAKE_CURRENT_LIST_DIR}/test_helpers.tmpl" "${CMAKE_CURRENT_LIST_DIR}/test_main.tmpl" ) diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test/test_helpers.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test/test_helpers.tmpl new file mode 100644 index 0000000000..034b5cc15e --- /dev/null +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test/test_helpers.tmpl @@ -0,0 +1,127 @@ +// ====================================================================== +// \title $name/test/ut/TesterHelpers.cpp +// \author Auto-generated +// \brief cpp file for ${name} component test harness base class +// +// NOTE: this file was automatically generated +// +// ====================================================================== +\#include "Tester.hpp" + +#if $namespace_list != None + #for $namespace in $namespace_list +namespace ${namespace} { + #end for +#end if + // ---------------------------------------------------------------------- + // Helper methods + // ---------------------------------------------------------------------- + + void Tester :: + connectPorts() + { + +#for $instance, $type, $sync, $priority, $full, $role, $max_num in $typed_input_ports: + // $instance + #if $max_num == 1 or $max_num == "1": + this->connect_to_${instance}( + 0, + this->component.get_${instance}_InputPort(0) + ); + #else + #set LT = "<" + for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { + this->connect_to_${instance}( + i, + this->component.get_${instance}_InputPort(i) + ); + } + #end if + +#end for +#for $instance, $type, $sync, $priority, $role, $max_num in $typed_output_ports: + // $instance + #if $max_num == 1 or $max_num == "1": + this->component.set_${instance}_OutputPort( + 0, + this->get_from_${instance}(0) + ); + #else + #set LT = "<" + for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { + this->component.set_${instance}_OutputPort( + i, + this->get_from_${instance}(i) + ); + } + #end if + +#end for + +#if len($serial_output_ports) > 0: + // ---------------------------------------------------------------------- + // Connect serial output ports + // ---------------------------------------------------------------------- +#for $instance, $sync, $priority, $max_num in $serial_output_ports: + #if $max_num == 1 or $max_num == "1": + this->component.set_${instance}_OutputPort( + 0, + this->get_from_${instance}(0) + ); + #else + #set LT = "<" + for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { + this->component.set_${instance}_OutputPort( + i, + this->get_from_${instance}(i) + ); + } + #end if + +#end for +#end if + +#if len($serial_input_ports) > 0: + // ---------------------------------------------------------------------- + // Connect serial input ports + // ---------------------------------------------------------------------- +#for $instance, $sync, $priority, $full, $max_num in $serial_input_ports: + // $instance + #if $max_num == 1 or $max_num == "1": + this->connect_to_${instance}( + 0, + this->component.get_${instance}_InputPort(0) + ); + #else + #set LT = "<" + for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { + this->connect_to_${instance}( + i, + this->component.get_${instance}_InputPort(i) + ); + } + #end if + +#end for +#end if + + } + + void Tester :: + initComponents() + { + this->init(); + this->component.init( +#if $kind == "passive" + Tester::TEST_INSTANCE_ID +#else + Tester::TEST_INSTANCE_QUEUE_DEPTH, Tester::TEST_INSTANCE_ID +#end if + ); + } + +#if $namespace_list != None + #for $namespace in $reversed($namespace_list) +} // end namespace $namespace + #end for +#end if diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/cpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/cpp.tmpl index 9cb8634b6a..959cb39386 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/cpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/cpp.tmpl @@ -6,12 +6,6 @@ \#include "Tester.hpp" -\#define INSTANCE 0 -\#define MAX_HISTORY_SIZE 10 -#if $kind != "passive": -\#define QUEUE_DEPTH 10 -#end if - #if $namespace_list != None #for $namespace in $namespace_list namespace ${namespace} { @@ -24,7 +18,7 @@ namespace ${namespace} { Tester :: Tester() : - ${gtest_base}("Tester", MAX_HISTORY_SIZE), + ${gtest_base}("Tester", Tester::MAX_HISTORY_SIZE), component("${name}") { this->initComponents(); @@ -85,112 +79,6 @@ $emit_port_params([ $param_portNum ] + $port_params[$instance]) #end for #end if - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - void Tester :: - connectPorts() - { - -#for $instance, $type, $sync, $priority, $full, $role, $max_num in $typed_input_ports: - // $instance - #if $max_num == 1 or $max_num == "1": - this->connect_to_${instance}( - 0, - this->component.get_${instance}_InputPort(0) - ); - #else - #set LT = "<" - for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { - this->connect_to_${instance}( - i, - this->component.get_${instance}_InputPort(i) - ); - } - #end if - -#end for -#for $instance, $type, $sync, $priority, $role, $max_num in $typed_output_ports: - // $instance - #if $max_num == 1 or $max_num == "1": - this->component.set_${instance}_OutputPort( - 0, - this->get_from_${instance}(0) - ); - #else - #set LT = "<" - for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { - this->component.set_${instance}_OutputPort( - i, - this->get_from_${instance}(i) - ); - } - #end if - -#end for - -#if len($serial_output_ports) > 0: - // ---------------------------------------------------------------------- - // Connect serial output ports - // ---------------------------------------------------------------------- -#for $instance, $sync, $priority, $max_num in $serial_output_ports: - #if $max_num == 1 or $max_num == "1": - this->component.set_${instance}_OutputPort( - 0, - this->get_from_${instance}(0) - ); - #else - #set LT = "<" - for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { - this->component.set_${instance}_OutputPort( - i, - this->get_from_${instance}(i) - ); - } - #end if - -#end for -#end if - -#if len($serial_input_ports) > 0: - // ---------------------------------------------------------------------- - // Connect serial input ports - // ---------------------------------------------------------------------- -#for $instance, $sync, $priority, $full, $max_num in $serial_input_ports: - // $instance - #if $max_num == 1 or $max_num == "1": - this->connect_to_${instance}( - 0, - this->component.get_${instance}_InputPort(0) - ); - #else - #set LT = "<" - for (NATIVE_INT_TYPE i = 0; i $LT $max_num; ++i) { - this->connect_to_${instance}( - i, - this->component.get_${instance}_InputPort(i) - ); - } - #end if - -#end for -#end if - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init( -#if $kind == "passive" - INSTANCE -#else - QUEUE_DEPTH, INSTANCE -#end if - ); - } #if $namespace_list != None #for $namespace in $reversed($namespace_list) diff --git a/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/hpp.tmpl b/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/hpp.tmpl index 6f36bc8516..1230577320 100644 --- a/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/hpp.tmpl +++ b/Autocoders/Python/src/fprime_ac/generators/templates/test_impl/hpp.tmpl @@ -25,6 +25,14 @@ namespace ${namespace} { // ---------------------------------------------------------------------- public: + // Maximum size of histories storing events, telemetry, and port outputs + static const NATIVE_INT_TYPE MAX_HISTORY_SIZE = 10; + // Instance ID supplied to the component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_ID = 0; + #if $kind != "passive": + // Queue depth supplied to component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_QUEUE_DEPTH = 10; + #end if //! Construct object Tester //! diff --git a/Autocoders/Python/src/fprime_ac/generators/visitors/TestImplCppHelpersVisitor.py b/Autocoders/Python/src/fprime_ac/generators/visitors/TestImplCppHelpersVisitor.py new file mode 100644 index 0000000000..f4fdcfbd77 --- /dev/null +++ b/Autocoders/Python/src/fprime_ac/generators/visitors/TestImplCppHelpersVisitor.py @@ -0,0 +1,47 @@ +# =============================================================================== +# NAME: TestImplCppHelpersVisitor.py +# +# DESCRIPTION: A visitor class for generating test implementation cpp files. +# +# AUTHOR: lestarch +# DATE CREATED: November 28, 2022 +# +# Copyright 2015, California Institute of Technology. +# ALL RIGHTS RESERVED. U.S. Government Sponsorship acknowledged. +# =============================================================================== +import sys + +from fprime_ac.generators.visitors import TestImplVisitorBase + +try: + from fprime_ac.generators.templates.test import test_helpers +except ImportError: + print("ERROR: must generate python templates first.") + sys.exit(-1) + + +class TestImplCppHelpersVisitor(TestImplVisitorBase.TestImplVisitorBase): + """ + A visitor class for generating test implementation cpp files. + """ + + def __init__(self): + super().__init__() + self.initBase("TestImplCpp") + + def emitPortParams(self, params): + return self.emitPortParamsCpp(8, params) + + def emitNonPortParams(self, params): + return self.emitNonPortParamsCpp(8, params) + + def initFilesVisit(self, obj): + self.openFile("TesterHelpers.cpp") + + def startSourceFilesVisit(self, obj): + c = test_helpers.test_helpers() + self.init(obj, c) + self.initTestImpl(obj, c) + c.emit_port_params = self.emitPortParams + c.emit_non_port_params = self.emitNonPortParams + self._writeTmpl(c, "startSourceFilesVisit") diff --git a/Ref/SignalGen/CMakeLists.txt b/Ref/SignalGen/CMakeLists.txt index b382b9477c..142e35fc8a 100644 --- a/Ref/SignalGen/CMakeLists.txt +++ b/Ref/SignalGen/CMakeLists.txt @@ -17,4 +17,5 @@ set(UT_SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" "${CMAKE_CURRENT_LIST_DIR}/test/ut/TestMain.cpp" ) +set(UT_AUTO_HELPERS ON) register_fprime_ut() diff --git a/Ref/SignalGen/test/ut/Tester.cpp b/Ref/SignalGen/test/ut/Tester.cpp index 21db548ede..e7fa38f730 100644 --- a/Ref/SignalGen/test/ut/Tester.cpp +++ b/Ref/SignalGen/test/ut/Tester.cpp @@ -12,10 +12,6 @@ #include "Tester.hpp" -#define INSTANCE 0 -#define MAX_HISTORY_SIZE 10 -#define QUEUE_DEPTH 10 - namespace Ref { // ---------------------------------------------------------------------- @@ -51,75 +47,4 @@ namespace Ref { component.doDispatch(); ASSERT_TLM_Output_SIZE(1); } - - // ---------------------------------------------------------------------- - // Helper methods - // ---------------------------------------------------------------------- - - void Tester :: - connectPorts() - { - - // cmdIn - this->connect_to_cmdIn( - 0, - this->component.get_cmdIn_InputPort(0) - ); - - // schedIn - this->connect_to_schedIn( - 0, - this->component.get_schedIn_InputPort(0) - ); - - // timeCaller - this->component.set_timeCaller_OutputPort( - 0, - this->get_from_timeCaller(0) - ); - - // cmdRegOut - this->component.set_cmdRegOut_OutputPort( - 0, - this->get_from_cmdRegOut(0) - ); - - // logTextOut - this->component.set_logTextOut_OutputPort( - 0, - this->get_from_logTextOut(0) - ); - - // logOut - this->component.set_logOut_OutputPort( - 0, - this->get_from_logOut(0) - ); - - // cmdResponseOut - this->component.set_cmdResponseOut_OutputPort( - 0, - this->get_from_cmdResponseOut(0) - ); - - // tlmOut - this->component.set_tlmOut_OutputPort( - 0, - this->get_from_tlmOut(0) - ); - - - - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init( - QUEUE_DEPTH, INSTANCE - ); - } - } // end namespace Ref diff --git a/Ref/SignalGen/test/ut/Tester.hpp b/Ref/SignalGen/test/ut/Tester.hpp index 17ff6e52b2..c52c2a6808 100644 --- a/Ref/SignalGen/test/ut/Tester.hpp +++ b/Ref/SignalGen/test/ut/Tester.hpp @@ -21,12 +21,17 @@ namespace Ref { class Tester : public SignalGenGTestBase { - // ---------------------------------------------------------------------- // Construction and destruction // ---------------------------------------------------------------------- public: + // Maximum size of histories storing events, telemetry, and port outputs + static const NATIVE_INT_TYPE MAX_HISTORY_SIZE = 10; + // Instance ID supplied to the component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_ID = 0; + // Queue depth supplied to component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_QUEUE_DEPTH = 10; //! Construct object Tester //! diff --git a/cmake/API.cmake b/cmake/API.cmake index 9621bf807d..fb94f9f081 100644 --- a/cmake/API.cmake +++ b/cmake/API.cmake @@ -326,7 +326,7 @@ endfunction(register_fprime_deployment) # unit test name, autocoding and source inputs for the unit test, and (optionally) any # non-standard link dependencies. # -# **Note:** This is ONLY run when the build type is TESTING. Unit testing is restricted to this build type as fprime +# **Note:** This is ONLY run when the BUILD_TESTING is enabled. Unit testing is restricted to this build type as fprime # sets additional flags when building for unit tests. # # Required variables (defined in calling scope): @@ -361,6 +361,11 @@ endfunction(register_fprime_deployment) # ``` # **Note:** this is typically called after any other register calls in the module. # +# - **UT_AUTO_HELPERS:** (optional) When set ON, a test helper file will be generated that auto-codes the connect ports +# and init components methods. This removes the maintenance overhead for these functions. ON additionally adds test +# source directories to the include path for the unit test target. When set to OFF, this helper file will be created +# when generating implementation templates allowing users to modify these files. Default: OFF +# # ### Unit-Test Example ### # # A standard unit test defines only UT_SOURCES. These sources have the test cpp files and the module diff --git a/cmake/autocoder/ai_ut.cmake b/cmake/autocoder/ai_ut.cmake index 9765432698..98d8f2d651 100644 --- a/cmake/autocoder/ai_ut.cmake +++ b/cmake/autocoder/ai_ut.cmake @@ -31,13 +31,24 @@ endfunction (ai_ut_is_supported) # Required function, sets up a custom command to produce TesterBase and GTestBase files. #### function(ai_ut_setup_autocode AC_INPUT_FILE) - set(REMOVAL_LIST "${CMAKE_CURRENT_BINARY_DIR}/Tester.hpp ${CMAKE_CURRENT_BINARY_DIR}/Tester.cpp ${CMAKE_CURRENT_BINARY_DIR}/TestMain.cpp") - set(AUTOCODER_GENERATED "${CMAKE_CURRENT_BINARY_DIR}/TesterBase.cpp" "${CMAKE_CURRENT_BINARY_DIR}/TesterBase.hpp") + set(REMOVALS "${CMAKE_CURRENT_BINARY_DIR}/Tester.hpp" + "${CMAKE_CURRENT_BINARY_DIR}/Tester.cpp" + "${CMAKE_CURRENT_BINARY_DIR}/TestMain.cpp") + set(AUTOCODER_GENERATED + "${CMAKE_CURRENT_BINARY_DIR}/TesterBase.cpp" + "${CMAKE_CURRENT_BINARY_DIR}/TesterBase.hpp") + # GTest flag handling if (INCLUDE_GTEST) list(APPEND AUTOCODER_GENERATED "${CMAKE_CURRENT_BINARY_DIR}/GTestBase.cpp" "${CMAKE_CURRENT_BINARY_DIR}/GTestBase.hpp") else() - set(REMOVAL_LIST "${REMOVAL_LIST} ${CMAKE_CURRENT_BINARY_DIR}/GTestBase.cpp ${CMAKE_CURRENT_BINARY_DIR}/GTestBase.hpp") + list(APPEND REMOVALS "${CMAKE_CURRENT_BINARY_DIR}/GTestBase.cpp" "${CMAKE_CURRENT_BINARY_DIR}/GTestBase.hpp") + endif() + # Extra test helpers file + if (DEFINED UT_AUTO_HELPERS AND UT_AUTO_HELPERS) + list(APPEND AUTOCODER_GENERATED "${CMAKE_CURRENT_BINARY_DIR}/TesterHelpers.cpp") + else() + list(APPEND REMOVALS "${CMAKE_CURRENT_BINARY_DIR}/TesterHelpers.cpp") endif() # Get the shared setup for all AI autocoders @@ -46,7 +57,7 @@ function(ai_ut_setup_autocode AC_INPUT_FILE) add_custom_command( OUTPUT ${AUTOCODER_GENERATED} COMMAND ${AI_BASE_SCRIPT} -u "${AC_INPUT_FILE}" - COMMAND ${CMAKE_COMMAND} -E remove ${REMOVAL_LIST} + COMMAND ${CMAKE_COMMAND} -E remove ${REMOVALS} DEPENDS "${AC_INPUT_FILE}" "${CODEGEN_TARGET}" ) set(AUTOCODER_GENERATED "${AUTOCODER_GENERATED}" PARENT_SCOPE) diff --git a/cmake/autocoder/ai_ut_impl.cmake b/cmake/autocoder/ai_ut_impl.cmake index a058f03803..af06d1d73f 100644 --- a/cmake/autocoder/ai_ut_impl.cmake +++ b/cmake/autocoder/ai_ut_impl.cmake @@ -36,17 +36,25 @@ function(ai_ut_impl_setup_autocode AC_INPUT_FILE) ${CMAKE_CURRENT_SOURCE_DIR}/Tester.hpp ${CMAKE_CURRENT_SOURCE_DIR}/TestMain.cpp ) + set(REMOVALS + "${CMAKE_CURRENT_SOURCE_DIR}/TesterBase.hpp" + "${CMAKE_CURRENT_SOURCE_DIR}/TesterBase.cpp" + "${CMAKE_CURRENT_SOURCE_DIR}/GTestBase.hpp" + "${CMAKE_CURRENT_SOURCE_DIR}/GTestBase.cpp") + # Extra test helpers file + if (NOT DEFINED UT_AUTO_HELPERS OR NOT UT_AUTO_HELPERS) + list(APPEND AUTOCODER_GENERATED "${CMAKE_CURRENT_SOURCE_DIR}/TesterHelpers.cpp") + else() + list(APPEND REMOVALS "${CMAKE_CURRENT_SOURCE_DIR}/TesterHelpers.cpp") + endif() + # Get the shared setup for all AI autocoders ai_shared_setup("${CMAKE_CURRENT_SOURCE_DIR}") # Specifically setup the `add_custom_command` call as the requires extra commands to run add_custom_command( OUTPUT ${AUTOCODER_GENERATED} COMMAND ${AI_BASE_SCRIPT} -u "${AC_INPUT_FILE}" - COMMAND ${CMAKE_COMMAND} -E remove - ${CMAKE_CURRENT_SOURCE_DIR}/TesterBase.hpp - ${CMAKE_CURRENT_SOURCE_DIR}/TesterBase.cpp - ${CMAKE_CURRENT_SOURCE_DIR}/GTestBase.hpp - ${CMAKE_CURRENT_SOURCE_DIR}/GTestBase.cpp + COMMAND ${CMAKE_COMMAND} -E remove ${REMOVALS} DEPENDS "${AC_INPUT_FILE}" "${CODEGEN_TARGET}" ) set(AUTOCODER_GENERATED "${AUTOCODER_GENERATED}" PARENT_SCOPE) diff --git a/cmake/target/ut.cmake b/cmake/target/ut.cmake index 0446af0e53..ab0fe13648 100644 --- a/cmake/target/ut.cmake +++ b/cmake/target/ut.cmake @@ -40,9 +40,34 @@ function(ut_add_deployment_target MODULE TARGET SOURCES DEPENDENCIES FULL_DEPEND endforeach() endfunction(ut_add_deployment_target) +#### +# Function `ut_setup_unit_test_include_directories`: +# +# Adds the include directories needed to make a unit test executable compile correctly. These directories are: +# 1. Current CMake binary directory for autogenerated headers +# 2. (If UT_AUTO_HELPERS) Containing folder for each .hpp for includes of the for '#include "Tester.hpp"' +# +# - **UT_EXE_NAME:** unit test executable name +# - **SOURCE_FILES:** list of source file inputs +#### +function(ut_setup_unit_test_include_directories UT_EXE_NAME SOURCE_FILES) + set(UT_INCLUDE_DIRECTORIES "${CMAKE_CURRENT_BINARY_DIR}") + # When running with auto-helpers, we need to include the .hpp directories as things are imported without path + # e.g. "#include " and there is no guarantee for the location of these files + if (DEFINED UT_AUTO_HELPERS AND UT_AUTO_HELPERS) + foreach(SOURCE_FILE IN LISTS SOURCE_FILES) + get_filename_component(SOURCE_EXT "${SOURCE_FILE}" LAST_EXT) + get_filename_component(SOURCE_DIR "${SOURCE_FILE}" DIRECTORY) + if (SOURCE_EXT STREQUAL ".cpp" AND NOT SOURCE_DIR IN_LIST UT_INCLUDE_DIRECTORIES) + list(APPEND UT_INCLUDE_DIRECTORIES "${SOURCE_DIR}") + endif() + endforeach() + endif() + target_include_directories("${UT_EXE_NAME}" PRIVATE ${UT_INCLUDE_DIRECTORIES}) +endfunction(ut_setup_unit_test_include_directories) #### -# Dict function `ut_add_module_target`: +# Function `ut_add_module_target`: # # Creates each module's coverage targets. Note: only run for "BUILD_TESTING=ON" builds. # @@ -61,7 +86,7 @@ function(ut_add_module_target MODULE_NAME TARGET_NAME SOURCE_FILES DEPENDENCIES) resolve_dependencies(RESOLVED gtest_main ${DEPENDENCIES} ${AC_DEPENDENCIES}) build_setup_build_module("${UT_EXE_NAME}" "${SOURCE_FILES}" "${AC_GENERATED}" "${AC_SOURCES}" "${RESOLVED}") - target_include_directories("${UT_EXE_NAME}" PRIVATE "${CMAKE_CURRENT_BINARY_DIR}") + ut_setup_unit_test_include_directories("${UT_EXE_NAME}" "${SOURCE_FILES}") add_test(NAME ${UT_EXE_NAME} COMMAND ${UT_EXE_NAME}) # Create a module-level target if not already done diff --git a/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.cpp b/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.cpp index 31b34023ed..1f3de5edb3 100644 --- a/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.cpp +++ b/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.cpp @@ -13,10 +13,6 @@ #include "STest/Pick/Pick.hpp" #include "Tester.hpp" -#define INSTANCE 0 -#define MAX_HISTORY_SIZE 10 -#define QUEUE_DEPTH 10 - namespace Ref { // ---------------------------------------------------------------------- @@ -243,90 +239,4 @@ namespace Ref { ASSERT_TLM_OPERATION(0, op); } - - void Tester :: - connectPorts() - { - - // mathOpIn - this->connect_to_mathOpIn( - 0, - this->component.get_mathOpIn_InputPort(0) - ); - - // schedIn - this->connect_to_schedIn( - 0, - this->component.get_schedIn_InputPort(0) - ); - - // cmdIn - this->connect_to_cmdIn( - 0, - this->component.get_cmdIn_InputPort(0) - ); - - // mathResultOut - this->component.set_mathResultOut_OutputPort( - 0, - this->get_from_mathResultOut(0) - ); - - // cmdResponseOut - this->component.set_cmdResponseOut_OutputPort( - 0, - this->get_from_cmdResponseOut(0) - ); - - // cmdRegOut - this->component.set_cmdRegOut_OutputPort( - 0, - this->get_from_cmdRegOut(0) - ); - - // prmGetOut - this->component.set_prmGetOut_OutputPort( - 0, - this->get_from_prmGetOut(0) - ); - - // prmSetOut - this->component.set_prmSetOut_OutputPort( - 0, - this->get_from_prmSetOut(0) - ); - - // tlmOut - this->component.set_tlmOut_OutputPort( - 0, - this->get_from_tlmOut(0) - ); - - // timeGetOut - this->component.set_timeGetOut_OutputPort( - 0, - this->get_from_timeGetOut(0) - ); - - // eventOut - this->component.set_eventOut_OutputPort( - 0, - this->get_from_eventOut(0) - ); - - // textEventOut - this->component.set_textEventOut_OutputPort( - 0, - this->get_from_textEventOut(0) - ); - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init(QUEUE_DEPTH, INSTANCE); - } - } // end namespace Ref diff --git a/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.hpp b/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.hpp index 1e18417ae0..04b70f36b3 100644 --- a/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.hpp +++ b/docs/Tutorials/MathComponent/MathReceiver/test/ut/Tester.hpp @@ -21,6 +21,13 @@ namespace Ref { class Tester : public MathReceiverGTestBase { + public: + // Maximum size of histories storing events, telemetry, and port outputs + static const NATIVE_INT_TYPE MAX_HISTORY_SIZE = 10; + // Instance ID supplied to the component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_ID = 0; + // Queue depth supplied to component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_QUEUE_DEPTH = 10; private: diff --git a/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp b/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp index 77f9279520..be15213201 100644 --- a/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp +++ b/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.cpp @@ -174,74 +174,4 @@ namespace Ref { ASSERT_EVENTS_COMMAND_RECV(0, val1, op, val2); } - - void Tester :: - connectPorts() - { - - // mathResultIn - this->connect_to_mathResultIn( - 0, - this->component.get_mathResultIn_InputPort(0) - ); - - // cmdIn - this->connect_to_cmdIn( - 0, - this->component.get_cmdIn_InputPort(0) - ); - - // mathOpOut - this->component.set_mathOpOut_OutputPort( - 0, - this->get_from_mathOpOut(0) - ); - - // cmdResponseOut - this->component.set_cmdResponseOut_OutputPort( - 0, - this->get_from_cmdResponseOut(0) - ); - - // cmdRegOut - this->component.set_cmdRegOut_OutputPort( - 0, - this->get_from_cmdRegOut(0) - ); - - // tlmOut - this->component.set_tlmOut_OutputPort( - 0, - this->get_from_tlmOut(0) - ); - - // timeGetOut - this->component.set_timeGetOut_OutputPort( - 0, - this->get_from_timeGetOut(0) - ); - - // eventOut - this->component.set_eventOut_OutputPort( - 0, - this->get_from_eventOut(0) - ); - - // textEventOut - this->component.set_textEventOut_OutputPort( - 0, - this->get_from_textEventOut(0) - ); - - } - - void Tester :: - initComponents() - { - this->init(); - this->component.init( - QUEUE_DEPTH, INSTANCE - ); - } - } // end namespace Ref diff --git a/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.hpp b/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.hpp index fbe94c5604..93bf2fd724 100644 --- a/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.hpp +++ b/docs/Tutorials/MathComponent/MathSender/test/ut/Tester.hpp @@ -27,6 +27,12 @@ namespace Ref { // ---------------------------------------------------------------------- public: + // Maximum size of histories storing events, telemetry, and port outputs + static const NATIVE_INT_TYPE MAX_HISTORY_SIZE = 10; + // Instance ID supplied to the component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_ID = 0; + // Queue depth supplied to component instance under test + static const NATIVE_INT_TYPE TEST_INSTANCE_QUEUE_DEPTH = 10; //! Construct object Tester //! diff --git a/docs/Tutorials/MathComponent/Tutorial.md b/docs/Tutorials/MathComponent/Tutorial.md index cf735ac809..98e63d6458 100644 --- a/docs/Tutorials/MathComponent/Tutorial.md +++ b/docs/Tutorials/MathComponent/Tutorial.md @@ -764,6 +764,7 @@ Add the following lines to `CMakeLists.txt`: set(UT_SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/MathSender.fpp" ) +set(UT_AUTO_HELPERS ON) register_fprime_ut() ``` @@ -797,6 +798,7 @@ set(UT_SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/test/ut/Tester.cpp" "${CMAKE_CURRENT_LIST_DIR}/test/ut/main.cpp" ) +set(UT_AUTO_HELPERS ON) register_fprime_ut() ``` @@ -1833,7 +1835,7 @@ void Tester :: this->setFactor(factor, ThrottleState::THROTTLED); // send the command to clear the throttle - this->sendCmd_CLEAR_EVENT_THROTTLE(INSTANCE, CMD_SEQ); + this->sendCmd_CLEAR_EVENT_THROTTLE(TEST_INSTANCE_ID, CMD_SEQ); // invoke scheduler port to dispatch message const U32 context = STest::Pick::any(); this->invoke_to_schedIn(0, context); From 2340b231c584b5dc2a47973c256745014635ef15 Mon Sep 17 00:00:00 2001 From: M Starch Date: Wed, 21 Dec 2022 14:36:14 -0800 Subject: [PATCH 118/169] Update/baremetal os fixes (#1823) * fixing baremetal os for missing files * fixing com stub to function w/o com queue and com queue to drop on overflow --- Os/Baremetal/FileSystem.cpp | 6 ++++++ Svc/ComQueue/ComQueue.fpp | 6 +++--- Svc/ComStub/ComStub.cpp | 2 +- 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/Os/Baremetal/FileSystem.cpp b/Os/Baremetal/FileSystem.cpp index 00ba4b9a83..a458e98015 100644 --- a/Os/Baremetal/FileSystem.cpp +++ b/Os/Baremetal/FileSystem.cpp @@ -47,5 +47,11 @@ namespace Os { Status getFileCount (const char* directory, U32& fileCount) { return OTHER_ERROR; } //end getFileCount + Status appendFile(const char* originPath, const char* destPath, bool createMissingDest) { + return OTHER_ERROR; + } + Status getFreeSpace(const char* path, U64& totalBytes, U64& freeBytes) { + return OTHER_ERROR; + } } // end FileSystem namespace } // end Os namespace diff --git a/Svc/ComQueue/ComQueue.fpp b/Svc/ComQueue/ComQueue.fpp index 2c500a003e..43cda64368 100644 --- a/Svc/ComQueue/ComQueue.fpp +++ b/Svc/ComQueue/ComQueue.fpp @@ -26,13 +26,13 @@ module Svc { async input port comStatusIn: Fw.SuccessCondition @ Port array for receiving Fw::ComBuffers - async input port comQueueIn: [ComQueueComPorts] Fw.Com + async input port comQueueIn: [ComQueueComPorts] Fw.Com drop @ Port array for receiving Fw::Buffers - async input port buffQueueIn: [ComQueueBufferPorts] Fw.BufferSend + async input port buffQueueIn: [ComQueueBufferPorts] Fw.BufferSend drop @ Port for scheduling telemetry output - async input port run: Svc.Sched + async input port run: Svc.Sched drop # ---------------------------------------------------------------------- # Special ports diff --git a/Svc/ComStub/ComStub.cpp b/Svc/ComStub/ComStub.cpp index 2ba5d670e4..1cf361fcba 100644 --- a/Svc/ComStub/ComStub.cpp +++ b/Svc/ComStub/ComStub.cpp @@ -27,7 +27,7 @@ ComStub::~ComStub() {} // ---------------------------------------------------------------------- Drv::SendStatus ComStub::comDataIn_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& sendBuffer) { - FW_ASSERT(!this->m_reinitialize); // A message should never get here if we need to reinitialize is needed + FW_ASSERT(!this->m_reinitialize || !this->isConnected_comStatus_OutputPort(0)); // A message should never get here if we need to reinitialize is needed Drv::SendStatus driverStatus = Drv::SendStatus::SEND_RETRY; for (NATIVE_UINT_TYPE i = 0; driverStatus == Drv::SendStatus::SEND_RETRY && i < RETRY_LIMIT; i++) { driverStatus = this->drvDataOut_out(0, sendBuffer); From d8d4273b4b29ba6a308f6c1007cb72fe64c0f469 Mon Sep 17 00:00:00 2001 From: M Starch Date: Wed, 21 Dec 2022 14:38:03 -0800 Subject: [PATCH 119/169] fixing sprintf deprecation on macOs (#1824) --- Svc/ActiveTextLogger/test/ut/Tester.cpp | 12 ++++++------ Svc/Health/test/ut/Tester.cpp | 18 +++++++++--------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Svc/ActiveTextLogger/test/ut/Tester.cpp b/Svc/ActiveTextLogger/test/ut/Tester.cpp index 9826e20682..36ebf598c3 100644 --- a/Svc/ActiveTextLogger/test/ut/Tester.cpp +++ b/Svc/ActiveTextLogger/test/ut/Tester.cpp @@ -103,7 +103,7 @@ namespace Svc { if (stream1) { std::cout << "readLine: " << buf << std::endl; char textStr[512]; - sprintf(textStr, + snprintf(textStr, sizeof(textStr), "EVENT: (%d) (%d:%d,%d) %s: %s", id,timeTag.getTimeBase(),timeTag.getSeconds(),timeTag.getUSeconds(),severityString,text.toChar()); ASSERT_EQ(0,strcmp(textStr,buf)); @@ -144,7 +144,7 @@ namespace Svc { // Verify new printed line else { char textStr[512]; - sprintf(textStr, + snprintf(textStr, sizeof(textStr), "EVENT: (%d) (%d:%d,%d) %s: %s", id,timeTag.getTimeBase(),timeTag.getSeconds(),timeTag.getUSeconds(),severityString,text.toChar()); ASSERT_EQ(0,strcmp(textStr,buf)); @@ -206,7 +206,7 @@ namespace Svc { if (stream1) { std::cout << "readLine: " << buf << std::endl; char textStr[512]; - sprintf(textStr, + snprintf(textStr, sizeof(textStr), "EVENT: (%d) (%d:%d,%d) %s: %s", id,timeTag.getTimeBase(),timeTag.getSeconds(),timeTag.getUSeconds(),severityString,text.toChar()); ASSERT_EQ(0,strcmp(textStr,buf)); @@ -316,7 +316,7 @@ namespace Svc { stat = this->component.set_log_file(baseName,50); - sprintf(baseNameWithSuffix,"%s%d",baseName,i); + snprintf(baseNameWithSuffix, sizeof(baseNameWithSuffix), "%s%d",baseName,i); ASSERT_TRUE(stat); ASSERT_TRUE(this->component.m_log_file.m_openFile); ASSERT_EQ(0,strcmp(baseNameWithSuffix,this->component.m_log_file.m_fileName.toChar())); @@ -327,7 +327,7 @@ namespace Svc { // Create 11th which will fail and re-use the original: stat = this->component.set_log_file(baseName,50); - sprintf(baseNameWithSuffix,"%s%d",baseName,i); + snprintf(baseNameWithSuffix, sizeof(baseNameWithSuffix), "%s%d",baseName,i); ASSERT_TRUE(stat); ASSERT_TRUE(this->component.m_log_file.m_openFile); printf("<< %s %s\n",baseName,this->component.m_log_file.m_fileName.toChar()); @@ -341,7 +341,7 @@ namespace Svc { remove(longFileNameDup); remove(baseName); for (i = 0; i < 10; ++i) { - sprintf(baseNameWithSuffix,"%s%d",baseName,i); + snprintf(baseNameWithSuffix, sizeof(baseNameWithSuffix), "%s%d",baseName,i); remove(baseNameWithSuffix); } diff --git a/Svc/Health/test/ut/Tester.cpp b/Svc/Health/test/ut/Tester.cpp index 6b3e17ed0b..f7006db7c9 100644 --- a/Svc/Health/test/ut/Tester.cpp +++ b/Svc/Health/test/ut/Tester.cpp @@ -260,7 +260,7 @@ namespace Svc { for (NATIVE_UINT_TYPE port = 0; port < Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS; port++) { char name[80]; - sprintf(name,"task%d",port); + snprintf(name, sizeof(name), "task%d",port); ASSERT_EVENTS_HLTH_PING_WARN(port,name); } @@ -294,7 +294,7 @@ namespace Svc { for (NATIVE_UINT_TYPE port = 0; port < Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS; port++) { char name[80]; - sprintf(name,"task%d",port); + snprintf(name, sizeof(name), "task%d",port); ASSERT_EVENTS_HLTH_PING_WARN(port,name); } @@ -316,7 +316,7 @@ namespace Svc { for (NATIVE_UINT_TYPE port = 0; port < Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS; port++) { char name[80]; - sprintf(name,"task%d",port); + snprintf(name, sizeof(name), "task%d",port); ASSERT_EVENTS_HLTH_PING_LATE(port,name); } @@ -346,7 +346,7 @@ namespace Svc { ASSERT_EVENTS_HLTH_PING_WARN_SIZE(Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS); for (NATIVE_INT_TYPE entry = 0; entry < Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS; entry++) { char name[80]; - sprintf(name,"task%d",entry); + snprintf(name, sizeof(name), "task%d",entry); ASSERT_EVENTS_HLTH_PING_WARN(entry, name); } @@ -406,7 +406,7 @@ namespace Svc { ASSERT_EVENTS_HLTH_PING_LATE_SIZE(Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS); for (NATIVE_INT_TYPE entry = 0; entry < Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS; entry++) { char name[80]; - sprintf(name,"task%d",entry); + snprintf(name,sizeof(name), "task%d",entry); ASSERT_EVENTS_HLTH_PING_LATE(entry,name); } @@ -435,7 +435,7 @@ namespace Svc { } // disable entry char name[80]; - sprintf(name,"task%d",entry); + snprintf(name, sizeof(name), "task%d",entry); Fw::CmdStringArg task(name); this->sendCmd_HLTH_PING_ENABLE(0,10,name,Fw::Enabled::DISABLED); this->dispatchAll(); @@ -495,7 +495,7 @@ namespace Svc { ASSERT_EQ(this->pingEntries[entry].warnCycles,Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS+entry); ASSERT_EQ(this->pingEntries[entry].fatalCycles,Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS*2+entry+1); char name[80]; - sprintf(name,"task%d",entry); + snprintf(name, sizeof(name), "task%d",entry); Fw::CmdStringArg task(name); this->sendCmd_HLTH_CHNG_PING(0,10,task, Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS*4+entry, @@ -656,7 +656,7 @@ namespace Svc { ASSERT_EVENTS_HLTH_PING_WRONG_KEY_SIZE(Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS); for (NATIVE_INT_TYPE port = 0; port < Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS; port++) { char name[80]; - sprintf(name,"task%d",port); + snprintf(name, sizeof(name), "task%d",port); ASSERT_EVENTS_HLTH_PING_WRONG_KEY(port,name,FLAG_KEY_VALUE); } @@ -748,7 +748,7 @@ namespace Svc { ASSERT_EVENTS_SIZE(1); ASSERT_EVENTS_HLTH_PING_WARN_SIZE(1); char name[80]; - sprintf(name,"task%d",Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS-1); + snprintf(name, sizeof(name), "task%d",Svc::HealthComponentBase::NUM_PINGSEND_OUTPUT_PORTS-1); ASSERT_EVENTS_HLTH_PING_WARN(0,name); ASSERT_TLM_SIZE(1); ASSERT_TLM_PingLateWarnings_SIZE(1); From 7bf55edb34cf8284919cf54a39f670e1d272a58b Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Thu, 22 Dec 2022 01:25:02 +0100 Subject: [PATCH 120/169] Fill in the `projects.md` file (#1815) * Populate `projects.md` * Change the location of the table header * Remove typo in projects table * Fix spellchecking * Resolve `Unrecognized words (2)` from SpellCheck * Replace `?` w/ empty cells * Remove `SW Class (A to F)` column * Rework `NASA Center / Company` colum content/fmt * Rework `Project/Program` column w/ hyperlnk on mission title * Add OS/HW information in some projects * Add link to ASTERIA publication * Add link to FlashLight & NEAScout publication * Fix Spellcheck `Unrecognized words (3)` --- .github/actions/spelling/expect.txt | 12 ++++++++++++ docs/projects.md | 14 +++++++++++++- 2 files changed, 25 insertions(+), 1 deletion(-) diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 7bd0eb1a42..4e9696d7bd 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -46,6 +46,7 @@ aps apxs AQuat AQueued +arcsecond arduino argc argcomplete @@ -198,6 +199,7 @@ cobj CODEFILE codegen codeql +coldarm colno COLORSTYLE colorwheel @@ -325,6 +327,7 @@ dicts dictvalue difflib diffs +digitalcommons diles dinkel dirent @@ -452,6 +455,7 @@ EXAMPLECOMPONENTIMPL excinfo executables exitcode +Exoplanets expandtabs expr exprtokens @@ -713,6 +717,7 @@ isnan isoschematron isr ISREG +iss isspace isupper ITAR @@ -901,6 +906,7 @@ nbits ncsl NDELAY ndiffs +neascout Netscape newloc newroot @@ -1113,12 +1119,14 @@ QNX qsf qtest qthelpproject +Qualcomm quatchan RAbrack radd RAII Ramanan randtbl +rapidscat raspberrypi raspi RATEGROUPDRIVER @@ -1201,6 +1209,7 @@ sbin SBINDIR sbt scanf +scatterometer sched schem schematron @@ -1269,6 +1278,7 @@ SIZ sizeof sloc Smath +smallsat SNDTIMEO snprintf sockaddr @@ -1289,6 +1299,7 @@ SOURCEDIR sourceforge Sourcetrail sourcing +spacetech sparc SPHINXBUILD SPHINXOPTS @@ -1569,6 +1580,7 @@ vfs vhd vhdl VID +viewcontent viewforum virt virtualbox diff --git a/docs/projects.md b/docs/projects.md index bde0d68031..05f8a88ca0 100644 --- a/docs/projects.md +++ b/docs/projects.md @@ -3,4 +3,16 @@ title: "F´ Projects" layout: default --- -F´ has been used in many space applications. This information is **coming soon**. +Here are the projects and programs identified applying the F´ code: + + +|**_Project/Program_**| **_Type_** | **_NASA Center / Company_** | **_OS_** | **_HW Platform_** | **_Launch Date_**| **_End of Mission_** | **_Note_**| +|:---|:---|:---|:---|:---|:---|:---|:---| +| [ISS-RapidScat (International Space Station Rapid Scatterometer)]((https://www.jpl.nasa.gov/missions/international-space-station-rapid-scatterometer-iss-rapidscat)) | Instrument | [NASA's JPL](https://www.jpl.nasa.gov/) | | | Sep. 21, 2014 | Nov. 18, 2018 | Target: Earth | +| [ASTERIA (Arcsecond Space Telescope Enabling Research in Astrophysics)](https://www.jpl.nasa.gov/missions/arcsecond-space-telescope-enabling-research-in-astrophysics-asteria) | Technology Demonstration, CubeSat/SmallSat | [NASA's JPL](https://www.jpl.nasa.gov/) | Linux | PowerPC | Aug. 14, 2017 | End of Feb. 2020 | [Publication](https://digitalcommons.usu.edu/cgi/viewcontent.cgi?article=4067&context=smallsat) - Target: Exoplanets | +| [Mars Helicopter (Ingenuity)](https://mars.nasa.gov/technology/helicopter/) | Airborne | [NASA's JPL](https://www.jpl.nasa.gov/) | Linux | Qualcomm’s Snapdragon 801 | Jul. 30, 2020 | Ongoing | Target: Mars | +| [Lunar Flashlight CubeSat](https://www.jpl.nasa.gov/missions/lunar-flashlight) | Technology Demonstration, CubeSat/SmallSat | [NASA's JPL](https://www.jpl.nasa.gov/) | VxWorks | Sphinx (GR712 - LEON3FT SPARC) | Dec. 11, 2022 |Ongoing | [Publication](https://digitalcommons.usu.edu/cgi/viewcontent.cgi?article=5263&context=smallsat) - Target: Moon | +| [Near Earth Asteroid Scout CubeSat](https://www.jpl.nasa.gov/missions/near-earth-asteroid-scout-neascout) | Technology Demonstration, CubeSat/SmallSat | [NASA's JPL](https://www.jpl.nasa.gov/) | VxWorks | Sphinx (GR712 - LEON3FT SPARC) | Nov. 16, 2022 | Ongoing | [Publication](https://digitalcommons.usu.edu/cgi/viewcontent.cgi?article=5263&context=smallsat) - Target: Asteroids and Comets | +| [OWLS (Ocean Worlds Life Surveyor instrument)](https://ml.jpl.nasa.gov/projects/owls/owls.html) | Instrument | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | +| [CADRE (Cooperative Autonomous Distributed Robotic Explorers)](https://www.nasa.gov/directorates/spacetech/game_changing_development/projects/CADRE) | Robot | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | +| [COLDArm (Cold Operable Lunar Deployable Arm)]((https://www.nasa.gov/feature/cold-operable-lunar-deployable-arm-coldarm/)) | Robotic arm | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | From c7009350bc489010489211f74b1e26b15dbc6df0 Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Fri, 23 Dec 2022 00:40:22 +0100 Subject: [PATCH 121/169] Fix RapidScat & COLDArm link redirection (#1825) --- docs/projects.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/projects.md b/docs/projects.md index 05f8a88ca0..e1585f91c8 100644 --- a/docs/projects.md +++ b/docs/projects.md @@ -8,11 +8,11 @@ Here are the projects and programs identified applying the F´ code: |**_Project/Program_**| **_Type_** | **_NASA Center / Company_** | **_OS_** | **_HW Platform_** | **_Launch Date_**| **_End of Mission_** | **_Note_**| |:---|:---|:---|:---|:---|:---|:---|:---| -| [ISS-RapidScat (International Space Station Rapid Scatterometer)]((https://www.jpl.nasa.gov/missions/international-space-station-rapid-scatterometer-iss-rapidscat)) | Instrument | [NASA's JPL](https://www.jpl.nasa.gov/) | | | Sep. 21, 2014 | Nov. 18, 2018 | Target: Earth | +| [ISS-RapidScat (International Space Station Rapid Scatterometer)](https://www.jpl.nasa.gov/missions/international-space-station-rapid-scatterometer-iss-rapidscat) | Instrument | [NASA's JPL](https://www.jpl.nasa.gov/) | | | Sep. 21, 2014 | Nov. 18, 2018 | Target: Earth | | [ASTERIA (Arcsecond Space Telescope Enabling Research in Astrophysics)](https://www.jpl.nasa.gov/missions/arcsecond-space-telescope-enabling-research-in-astrophysics-asteria) | Technology Demonstration, CubeSat/SmallSat | [NASA's JPL](https://www.jpl.nasa.gov/) | Linux | PowerPC | Aug. 14, 2017 | End of Feb. 2020 | [Publication](https://digitalcommons.usu.edu/cgi/viewcontent.cgi?article=4067&context=smallsat) - Target: Exoplanets | | [Mars Helicopter (Ingenuity)](https://mars.nasa.gov/technology/helicopter/) | Airborne | [NASA's JPL](https://www.jpl.nasa.gov/) | Linux | Qualcomm’s Snapdragon 801 | Jul. 30, 2020 | Ongoing | Target: Mars | | [Lunar Flashlight CubeSat](https://www.jpl.nasa.gov/missions/lunar-flashlight) | Technology Demonstration, CubeSat/SmallSat | [NASA's JPL](https://www.jpl.nasa.gov/) | VxWorks | Sphinx (GR712 - LEON3FT SPARC) | Dec. 11, 2022 |Ongoing | [Publication](https://digitalcommons.usu.edu/cgi/viewcontent.cgi?article=5263&context=smallsat) - Target: Moon | | [Near Earth Asteroid Scout CubeSat](https://www.jpl.nasa.gov/missions/near-earth-asteroid-scout-neascout) | Technology Demonstration, CubeSat/SmallSat | [NASA's JPL](https://www.jpl.nasa.gov/) | VxWorks | Sphinx (GR712 - LEON3FT SPARC) | Nov. 16, 2022 | Ongoing | [Publication](https://digitalcommons.usu.edu/cgi/viewcontent.cgi?article=5263&context=smallsat) - Target: Asteroids and Comets | | [OWLS (Ocean Worlds Life Surveyor instrument)](https://ml.jpl.nasa.gov/projects/owls/owls.html) | Instrument | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | | [CADRE (Cooperative Autonomous Distributed Robotic Explorers)](https://www.nasa.gov/directorates/spacetech/game_changing_development/projects/CADRE) | Robot | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | -| [COLDArm (Cold Operable Lunar Deployable Arm)]((https://www.nasa.gov/feature/cold-operable-lunar-deployable-arm-coldarm/)) | Robotic arm | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | +| [COLDArm (Cold Operable Lunar Deployable Arm)](https://www.nasa.gov/feature/cold-operable-lunar-deployable-arm-coldarm/) | Robotic arm | [NASA's JPL](https://www.jpl.nasa.gov/) | | | | | | From d177bb7ef91f0b00ac805a0414e793bcfa053da2 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 22 Dec 2022 18:00:24 -0800 Subject: [PATCH 122/169] lestarch: update for small platform support (no U64) (#1721) * lestarch: update for small platform support (no U64) * first-pass at fixing types interface * fixing U64s in merged commit * fixing improper loop limit * fixing FwSizeType redefinition * fixing review comments * formatting Linux/FileSystem * fixing static analysis errors * fixing UTs when file system or memory to large * disabling broken ut and fixing spelling * cleaning up unused variable * adding more comments to explain casting checks --- .github/actions/spelling/expect.txt | 1 + Fw/Test/UnitTestAssert.hpp | 2 +- Fw/Types/BasicTypes.hpp | 6 + Fw/Types/Serializable.cpp | 2 +- Os/Baremetal/FileSystem.cpp | 103 +- Os/FileSystem.hpp | 5 +- Os/Linux/FileSystem.cpp | 1135 ++++++++++---------- Os/Linux/SystemResources.cpp | 26 +- Os/MacOs/SystemResources.cpp | 4 +- Os/SystemResources.hpp | 8 +- Os/TaskCommon.cpp | 7 +- Os/ValidateFileCommon.cpp | 5 +- Os/test/ut/OsFileSystemTest.cpp | 2 +- Os/test/ut/OsSystemResourcesTest.cpp | 4 - Os/test/ut/OsValidateFileTest.cpp | 2 +- Svc/ActiveTextLogger/LogFile.cpp | 2 +- Svc/ActiveTextLogger/test/ut/Tester.cpp | 4 +- Svc/BufferLogger/test/ut/Tester.cpp | 2 +- Svc/CmdSequencer/formats/AMPCSSequence.cpp | 9 +- Svc/ComLogger/test/ut/Tester.cpp | 4 +- Svc/FileDownlink/File.cpp | 12 +- Svc/FileDownlink/docs/sdd.md | 3 + Svc/FramingProtocol/FprimeProtocol.cpp | 6 +- Svc/SystemResources/SystemResources.cpp | 4 +- Svc/SystemResources/docs/sdd.md | 12 + Svc/SystemResources/test/ut/Tester.cpp | 27 +- Utils/CRCChecker.cpp | 8 +- Utils/Types/Queue.hpp | 2 - 28 files changed, 734 insertions(+), 673 deletions(-) create mode 100644 Svc/SystemResources/docs/sdd.md diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 4e9696d7bd..220aa08466 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -529,6 +529,7 @@ frox frsize fsanitize fsanitizers +fsblkcnt fscanf fstream fstrength diff --git a/Fw/Test/UnitTestAssert.hpp b/Fw/Test/UnitTestAssert.hpp index 4aed203847..8e1b5059e3 100644 --- a/Fw/Test/UnitTestAssert.hpp +++ b/Fw/Test/UnitTestAssert.hpp @@ -18,7 +18,7 @@ namespace Test { class UnitTestAssert: public Fw::AssertHook { public: #if FW_ASSERT_LEVEL == FW_FILEID_ASSERT - typedef NATIVE_UINT_TYPE File; + typedef U32 File; #else typedef String File; #endif diff --git a/Fw/Types/BasicTypes.hpp b/Fw/Types/BasicTypes.hpp index a1a8cba72c..dd867d45f8 100644 --- a/Fw/Types/BasicTypes.hpp +++ b/Fw/Types/BasicTypes.hpp @@ -101,20 +101,26 @@ struct BasicLimits : PlatformLimits { static const uint8_t U8_MIN = 0; static const uint8_t U8_MAX = UINT8_MAX; +#if FW_HAS_16_BIT static const I16 I16_MIN = INT16_MIN; static const I16 I16_MAX = INT16_MAX; static const U16 U16_MIN = 0; static const U16 U16_MAX = UINT16_MAX; +#endif +#if FW_HAS_32_BIT static const I32 I32_MIN = INT32_MIN; static const I32 I32_MAX = INT32_MAX; static const U32 U32_MIN = 0; static const U32 U32_MAX = UINT32_MAX; +#endif +#if FW_HAS_64_BIT static const I64 I64_MIN = INT64_MIN; static const I64 I64_MAX = INT64_MAX; static const U64 U64_MIN = 0; static const U64 U64_MAX = UINT64_MAX; +#endif }; #endif diff --git a/Fw/Types/Serializable.cpp b/Fw/Types/Serializable.cpp index ac0087fc9b..9eaa7ee5dc 100644 --- a/Fw/Types/Serializable.cpp +++ b/Fw/Types/Serializable.cpp @@ -186,7 +186,7 @@ namespace Fw { } #endif -#if FW_HAS_F64 +#if FW_HAS_F64 && FW_HAS_64_BIT SerializeStatus SerializeBufferBase::serialize(F64 val) { // floating point values need to be byte-swapped as well, so copy to U64 and use that routine diff --git a/Os/Baremetal/FileSystem.cpp b/Os/Baremetal/FileSystem.cpp index a458e98015..61a6d44614 100644 --- a/Os/Baremetal/FileSystem.cpp +++ b/Os/Baremetal/FileSystem.cpp @@ -1,57 +1,54 @@ #include -#include -#include #include +#include +#include namespace Os { - namespace FileSystem { - Status createDirectory(const char* path) { - return NO_SPACE; - } // end createDirectory - - Status removeDirectory(const char* path) { - return INVALID_PATH; - } // end removeDirectory - - Status readDirectory(const char* path, const U32 maxNum, - Fw::String fileArray[]) - { - return OTHER_ERROR; - } - Status removeFile(const char* path) { - - return OTHER_ERROR; - } // end removeFile - - Status moveFile(const char* originPath, const char* destPath) { - return OTHER_ERROR; - - } // end moveFile - - Status handleFileError(File::Status fileStatus) { - return OTHER_ERROR; - } // end handleFileError - - Status copyFile(const char* originPath, const char* destPath) { - return OTHER_ERROR; - } // end copyFile - - Status getFileSize(const char* path, U64& size) { - return OTHER_ERROR; - } // end getFileSize - - Status changeWorkingDirectory(const char* path) { - return OTHER_ERROR; - } // end changeWorkingDirectory - // Public function to get the file count for a given directory. - Status getFileCount (const char* directory, U32& fileCount) { - return OTHER_ERROR; - } //end getFileCount - Status appendFile(const char* originPath, const char* destPath, bool createMissingDest) { - return OTHER_ERROR; - } - Status getFreeSpace(const char* path, U64& totalBytes, U64& freeBytes) { - return OTHER_ERROR; - } - } // end FileSystem namespace -} // end Os namespace +namespace FileSystem { +Status createDirectory(const char* path) { + return NO_SPACE; +} // end createDirectory + +Status removeDirectory(const char* path) { + return INVALID_PATH; +} // end removeDirectory + +Status readDirectory(const char* path, const U32 maxNum, Fw::String fileArray[]) { + return OTHER_ERROR; +} +Status removeFile(const char* path) { + return OTHER_ERROR; +} // end removeFile + +Status moveFile(const char* originPath, const char* destPath) { + return OTHER_ERROR; + +} // end moveFile + +Status handleFileError(File::Status fileStatus) { + return OTHER_ERROR; +} // end handleFileError + +Status copyFile(const char* originPath, const char* destPath) { + return OTHER_ERROR; +} // end copyFile + +Status getFileSize(const char* path, FwSizeType& size) { + return OTHER_ERROR; +} // end getFileSize + +Status changeWorkingDirectory(const char* path) { + return OTHER_ERROR; +} // end changeWorkingDirectory +// Public function to get the file count for a given directory. +Status getFileCount(const char* directory, U32& fileCount) { + return OTHER_ERROR; +} // end getFileCount +Status appendFile(const char* originPath, const char* destPath, bool createMissingDest) { + return OTHER_ERROR; +} +Status getFreeSpace(const char* path, FwSizeType& totalBytes, FwSizeType& freeBytes) { + return OTHER_ERROR; +} +} // namespace FileSystem +} // namespace Os diff --git a/Os/FileSystem.hpp b/Os/FileSystem.hpp index d6b6473359..e6b0e2e5f3 100644 --- a/Os/FileSystem.hpp +++ b/Os/FileSystem.hpp @@ -32,11 +32,10 @@ namespace Os { Status moveFile(const char* originPath, const char* destPath); //! moves a file from origin to destination Status copyFile(const char* originPath, const char* destPath); //! copies a file from origin to destination Status appendFile(const char* originPath, const char* destPath, bool createMissingDest=false); //! append file origin to destination file. If boolean true, creates a brand new file if the destination doesn't exist. - Status getFileSize(const char* path, U64& size); //!< gets the size of the file (in bytes) at location path + Status getFileSize(const char* path, FwSizeType& size); //!< gets the size of the file (in bytes) at location path Status getFileCount(const char* directory, U32& fileCount); //!< counts the number of files in the given directory Status changeWorkingDirectory(const char* path); //!< move current directory to path - - Status getFreeSpace(const char* path, U64& totalBytes, U64& freeBytes); //!< get FS free and total space in bytes on filesystem containing path + Status getFreeSpace(const char* path, FwSizeType& totalBytes, FwSizeType& freeBytes); //!< get FS free and total space in bytes on filesystem containing path } } diff --git a/Os/Linux/FileSystem.cpp b/Os/Linux/FileSystem.cpp index df72e226a7..e96599744a 100644 --- a/Os/Linux/FileSystem.cpp +++ b/Os/Linux/FileSystem.cpp @@ -1,581 +1,586 @@ #include -#include -#include #include +#include +#include -#include +#include #include +#include #include -#include -#include // Needed for rename +#include +#include // Needed for rename #include #include -#include namespace Os { - namespace FileSystem { - - Status createDirectory(const char* path) { +namespace FileSystem { - Status stat = OP_OK; +Status createDirectory(const char* path) { + Status stat = OP_OK; #ifdef __VXWORKS__ - int mkStat = ::mkdir(path); + int mkStat = ::mkdir(path); #else - int mkStat = ::mkdir(path,S_IRWXU); + int mkStat = ::mkdir(path, S_IRWXU); #endif - if (-1 == mkStat) { - switch (errno) { - case EACCES: - case EPERM: - case EROFS: - case EFAULT: - stat = NO_PERMISSION; - break; - case EEXIST: - stat = ALREADY_EXISTS; - break; - case ELOOP: - case ENOENT: - case ENAMETOOLONG: - stat = INVALID_PATH; - break; - case ENOTDIR: - stat = NOT_DIR; - break; - case ENOSPC: - case EDQUOT: - stat = NO_SPACE; - break; - case EMLINK: - stat = FILE_LIMIT; - break; - default: - stat = OTHER_ERROR; - break; - } - } - - return stat; - } // end createDirectory - - Status removeDirectory(const char* path) { - - Status stat = OP_OK; - - if (::rmdir(path) == -1) { - switch (errno) { - case EACCES: - case EPERM: - case EROFS: - case EFAULT: - stat = NO_PERMISSION; - break; - case ENOTEMPTY: - case EEXIST: - stat = NOT_EMPTY; - break; - case EINVAL: - case ELOOP: - case ENOENT: - case ENAMETOOLONG: - stat = INVALID_PATH; - break; - case ENOTDIR: - stat = NOT_DIR; - break; - case EBUSY: - stat = BUSY; - break; - default: - stat = OTHER_ERROR; - break; - } - } - - return stat; - } // end removeDirectory - - Status readDirectory(const char* path, const U32 maxNum, - Fw::String fileArray[], - U32& numFiles) - { - Status dirStat = OP_OK; - DIR * dirPtr = nullptr; - struct dirent *direntData = nullptr; - - FW_ASSERT(fileArray != nullptr); - FW_ASSERT(path != nullptr); - - // Open directory failed: - if((dirPtr = ::opendir(path)) == nullptr) { - - switch (errno) { - case EACCES: - dirStat = NO_PERMISSION; - break; - case ENOENT: - dirStat = INVALID_PATH; - break; - case ENOTDIR: - dirStat = NOT_DIR; - break; - default: - dirStat = OTHER_ERROR; - break; - } - return dirStat; - } - - // Set errno to 0 so we know why we exited readdir - errno = 0; - U32 arrayIdx = 0; - U32 limitCount = 0; - const U32 loopLimit = std::numeric_limits::max(); - - // Read the directory contents and store in passed in array: - while(arrayIdx < maxNum && limitCount < loopLimit) { - - ++limitCount; - - if((direntData = ::readdir(dirPtr)) != nullptr) { - // We are only care about regular files - if(direntData->d_type == DT_REG) { - - FW_ASSERT(arrayIdx < maxNum, - static_cast(arrayIdx), - static_cast(maxNum)); - - Fw::String str(direntData->d_name); - fileArray[arrayIdx++] = str; - } - } - else { - // readdir failed, did it error or did we run out of files? - if(errno != 0) { - // Only error from readdir is EBADF - dirStat = OTHER_ERROR; - } - break; - } - } - - if(limitCount == loopLimit) { - dirStat = FILE_LIMIT; - } - - if(::closedir(dirPtr) == -1) { - // Only error from closedir is EBADF - dirStat = OTHER_ERROR; - } - - numFiles = arrayIdx; - - return dirStat; - } - - Status removeFile(const char* path) { - - Status stat = OP_OK; - - if(::unlink(path) == -1) { - switch (errno) { - case EACCES: - case EPERM: - case EROFS: - stat = NO_PERMISSION; - break; - case EISDIR: - stat = IS_DIR; - break; - case ELOOP: - case ENOENT: - case ENAMETOOLONG: - stat = INVALID_PATH; - break; - case ENOTDIR: - stat = NOT_DIR; - break; - case EBUSY: - stat = BUSY; - break; - default: - stat = OTHER_ERROR; - break; - } - } - - return stat; - } // end removeFile - - Status moveFile(const char* originPath, const char* destPath) { - - Status stat = OP_OK; - - if(::rename(originPath, destPath) == -1) { - switch (errno) { - case EACCES: - case EPERM: - case EROFS: - case EFAULT: - stat = NO_PERMISSION; - break; - case EDQUOT: - case ENOSPC: - stat = NO_SPACE; - break; - case ELOOP: - case ENAMETOOLONG: - case ENOENT: - case EINVAL: - stat = INVALID_PATH; - break; - case ENOTDIR: - case EISDIR: // Old path is not a dir - stat = NOT_DIR; - break; - case ENOTEMPTY: - case EEXIST: - stat = NOT_EMPTY; - break; - case EMLINK: - stat = FILE_LIMIT; - break; - case EBUSY: - stat = BUSY; - break; - default: - stat = OTHER_ERROR; - break; - } - } - return stat; - - } // end moveFile - - Status handleFileError(File::Status fileStatus) { - Status fileSystemStatus = OTHER_ERROR; - - switch(fileStatus) { - case File::NO_SPACE: - fileSystemStatus = NO_SPACE; - break; - case File::NO_PERMISSION: - fileSystemStatus = NO_PERMISSION; - break; - case File::DOESNT_EXIST: - fileSystemStatus = INVALID_PATH; - break; - default: - fileSystemStatus = OTHER_ERROR; - } - return fileSystemStatus; - } // end handleFileError - - /** - * A helper function that returns an "OP_OK" status if the given file - * exists and can be read from, otherwise returns an error status. - * - * If provided, will also initialize the given stat struct with file - * information. - */ - Status initAndCheckFileStats(const char* filePath, - struct stat* fileInfo=nullptr) { - FileSystem::Status fs_status; - struct stat local_info; - if(!fileInfo) { - // No external struct given, so use the local one - fileInfo = &local_info; - } - - if(::stat(filePath, fileInfo) == -1) { - switch (errno) { - case EACCES: - fs_status = NO_PERMISSION; - break; - case ELOOP: - case ENOENT: - case ENAMETOOLONG: - fs_status = INVALID_PATH; - break; - case ENOTDIR: - fs_status = NOT_DIR; - break; - default: - fs_status = OTHER_ERROR; - break; - } - return fs_status; - } - - // Make sure the origin is a regular file - if(!S_ISREG(fileInfo->st_mode)) { - return INVALID_PATH; - } - - return OP_OK; - } - - /** - * A helper function that writes all the file information in the source - * file to the destination file (replaces/appends to end/etc. depending - * on destination file mode). - * - * Files must already be open and will remain open after this function - * completes. - * - * @param source File to copy data from - * @param destination File to copy data to - * @param size The number of bytes to copy - */ - Status copyFileData(File source, File destination, U64 size) { - U8 fileBuffer[FILE_SYSTEM_CHUNK_SIZE]; - File::Status file_status; - - // Set loop limit - const U64 copyLoopLimit = (size/FILE_SYSTEM_CHUNK_SIZE) + 2; - - U64 loopCounter = 0; - NATIVE_INT_TYPE chunkSize; - while(loopCounter < copyLoopLimit) { - chunkSize = FILE_SYSTEM_CHUNK_SIZE; - file_status = source.read(&fileBuffer, chunkSize, false); - if(file_status != File::OP_OK) { - return handleFileError(file_status); - } - - if(chunkSize == 0) { - //file has been successfully copied - break; - } - - file_status = destination.write(fileBuffer, chunkSize, true); - if(file_status != File::OP_OK) { - return handleFileError(file_status); - } - loopCounter++; - } - FW_ASSERT(loopCounter < copyLoopLimit); - - return FileSystem::OP_OK; - } // end copyFileData - - Status copyFile(const char* originPath, const char* destPath) { - FileSystem::Status fs_status; - File::Status file_status; - - U64 fileSize = 0; - - File source; - File destination; - - fs_status = initAndCheckFileStats(originPath); - if(FileSystem::OP_OK != fs_status) { - return fs_status; - } - - // Get the file size: - fs_status = FileSystem::getFileSize(originPath, fileSize); //!< gets the size of the file (in bytes) at location path - if(FileSystem::OP_OK != fs_status) { - return fs_status; - } - - file_status = source.open(originPath, File::OPEN_READ); - if(file_status != File::OP_OK) { - return handleFileError(file_status); - } - - file_status = destination.open(destPath, File::OPEN_WRITE); - if(file_status != File::OP_OK) { - return handleFileError(file_status); - } - - fs_status = copyFileData(source, destination, fileSize); - - (void) source.close(); - (void) destination.close(); - - return fs_status; - } // end copyFile - - Status appendFile(const char* originPath, const char* destPath, bool createMissingDest) { - FileSystem::Status fs_status; - File::Status file_status; - U64 fileSize = 0; - - File source; - File destination; - - fs_status = initAndCheckFileStats(originPath); - if(FileSystem::OP_OK != fs_status) { - return fs_status; - } - - // Get the file size: - fs_status = FileSystem::getFileSize(originPath, fileSize); //!< gets the size of the file (in bytes) at location path - if(FileSystem::OP_OK != fs_status) { - return fs_status; - } - - file_status = source.open(originPath, File::OPEN_READ); - if(file_status != File::OP_OK) { - return handleFileError(file_status); - } - - // If needed, check if destination file exists (and exit if not) - if(!createMissingDest) { - fs_status = initAndCheckFileStats(destPath); - if(FileSystem::OP_OK != fs_status) { - return fs_status; - } - } - - file_status = destination.open(destPath, File::OPEN_APPEND); - if(file_status != File::OP_OK) { - return handleFileError(file_status); - } - - fs_status = copyFileData(source, destination, fileSize); - - (void) source.close(); - (void) destination.close(); - - return fs_status; - } // end appendFile - - Status getFileSize(const char* path, U64& size) { - - Status fileStat = OP_OK; - struct stat fileStatStruct; - - fileStat = initAndCheckFileStats(path, &fileStatStruct); - if(FileSystem::OP_OK == fileStat) { - // Only check size if struct was initialized successfully - size = fileStatStruct.st_size; - } - - return fileStat; - } // end getFileSize - - Status changeWorkingDirectory(const char* path) { - - Status stat = OP_OK; - - if (::chdir(path) == -1) { - switch (errno) { - case EACCES: - case EFAULT: - stat = NO_PERMISSION; - break; - case ENOTEMPTY: - stat = NOT_EMPTY; - break; - case ENOENT: - case ELOOP: - case ENAMETOOLONG: - stat = INVALID_PATH; - break; - case ENOTDIR: - stat = NOT_DIR; - break; - default: - stat = OTHER_ERROR; - break; - } - } - - return stat; - } // end changeWorkingDirectory - - Status getFreeSpace(const char* path, U64& totalBytes, U64& freeBytes) { - Status stat = OP_OK; - - struct statvfs fsStat; - int ret = statvfs(path, &fsStat); - if (ret) { - switch (errno) { - case EACCES: - stat = NO_PERMISSION; - break; - case ELOOP: - case ENOENT: - case ENAMETOOLONG: - stat = INVALID_PATH; - break; - case ENOTDIR: - stat = NOT_DIR; - break; - default: - stat = OTHER_ERROR; - break; - } - return stat; - } - - totalBytes = static_cast(fsStat.f_blocks) * static_cast(fsStat.f_frsize); - freeBytes = static_cast(fsStat.f_bfree) * static_cast(fsStat.f_frsize); - return stat; - } - - // Public function to get the file count for a given directory. - Status getFileCount (const char* directory, U32& fileCount) { - Status dirStat = OP_OK; - DIR * dirPtr = nullptr; - struct dirent *direntData = nullptr; - U32 limitCount; - const U64 loopLimit = std::numeric_limits::max(); - - fileCount = 0; - if((dirPtr = ::opendir(directory)) == nullptr) { - switch (errno) { - case EACCES: - dirStat = NO_PERMISSION; - break; - case ENOENT: - dirStat = INVALID_PATH; - break; - case ENOTDIR: - dirStat = NOT_DIR; - break; - default: - dirStat = OTHER_ERROR; - break; - } - return dirStat; - } - - // Set errno to 0 so we know why we exited readdir - errno = 0; - for(limitCount = 0; limitCount < loopLimit; limitCount++) { - if((direntData = ::readdir(dirPtr)) != nullptr) { - // We are only counting regular files - if(direntData->d_type == DT_REG) { - fileCount++; - } - } - else { - // readdir failed, did it error or did we run out of files? - if(errno != 0) { - // Only error from readdir is EBADF - dirStat = OTHER_ERROR; - } - break; - } - } - if(limitCount == loopLimit) { - dirStat = FILE_LIMIT; - } - - if(::closedir(dirPtr) == -1) { - // Only error from closedir is EBADF - dirStat = OTHER_ERROR; - } - - return dirStat; - } //end getFileCount - - } // end FileSystem namespace - -} // end Os namespace + if (-1 == mkStat) { + switch (errno) { + case EACCES: + case EPERM: + case EROFS: + case EFAULT: + stat = NO_PERMISSION; + break; + case EEXIST: + stat = ALREADY_EXISTS; + break; + case ELOOP: + case ENOENT: + case ENAMETOOLONG: + stat = INVALID_PATH; + break; + case ENOTDIR: + stat = NOT_DIR; + break; + case ENOSPC: + case EDQUOT: + stat = NO_SPACE; + break; + case EMLINK: + stat = FILE_LIMIT; + break; + default: + stat = OTHER_ERROR; + break; + } + } + + return stat; +} // end createDirectory + +Status removeDirectory(const char* path) { + Status stat = OP_OK; + + if (::rmdir(path) == -1) { + switch (errno) { + case EACCES: + case EPERM: + case EROFS: + case EFAULT: + stat = NO_PERMISSION; + break; + case ENOTEMPTY: + case EEXIST: + stat = NOT_EMPTY; + break; + case EINVAL: + case ELOOP: + case ENOENT: + case ENAMETOOLONG: + stat = INVALID_PATH; + break; + case ENOTDIR: + stat = NOT_DIR; + break; + case EBUSY: + stat = BUSY; + break; + default: + stat = OTHER_ERROR; + break; + } + } + + return stat; +} // end removeDirectory + +Status readDirectory(const char* path, const U32 maxNum, Fw::String fileArray[], U32& numFiles) { + Status dirStat = OP_OK; + DIR* dirPtr = nullptr; + struct dirent* direntData = nullptr; + + FW_ASSERT(fileArray != nullptr); + FW_ASSERT(path != nullptr); + + // Open directory failed: + if ((dirPtr = ::opendir(path)) == nullptr) { + switch (errno) { + case EACCES: + dirStat = NO_PERMISSION; + break; + case ENOENT: + dirStat = INVALID_PATH; + break; + case ENOTDIR: + dirStat = NOT_DIR; + break; + default: + dirStat = OTHER_ERROR; + break; + } + return dirStat; + } + + // Set errno to 0 so we know why we exited readdir + errno = 0; + U32 arrayIdx = 0; + U32 limitCount = 0; + const U32 loopLimit = std::numeric_limits::max(); + + // Read the directory contents and store in passed in array: + while (arrayIdx < maxNum && limitCount < loopLimit) { + ++limitCount; + + if ((direntData = ::readdir(dirPtr)) != nullptr) { + // We are only care about regular files + if (direntData->d_type == DT_REG) { + FW_ASSERT(arrayIdx < maxNum, static_cast(arrayIdx), + static_cast(maxNum)); + + Fw::String str(direntData->d_name); + fileArray[arrayIdx++] = str; + } + } else { + // readdir failed, did it error or did we run out of files? + if (errno != 0) { + // Only error from readdir is EBADF + dirStat = OTHER_ERROR; + } + break; + } + } + + if (limitCount == loopLimit) { + dirStat = FILE_LIMIT; + } + + if (::closedir(dirPtr) == -1) { + // Only error from closedir is EBADF + dirStat = OTHER_ERROR; + } + + numFiles = arrayIdx; + + return dirStat; +} + +Status removeFile(const char* path) { + Status stat = OP_OK; + + if (::unlink(path) == -1) { + switch (errno) { + case EACCES: + case EPERM: + case EROFS: + stat = NO_PERMISSION; + break; + case EISDIR: + stat = IS_DIR; + break; + case ELOOP: + case ENOENT: + case ENAMETOOLONG: + stat = INVALID_PATH; + break; + case ENOTDIR: + stat = NOT_DIR; + break; + case EBUSY: + stat = BUSY; + break; + default: + stat = OTHER_ERROR; + break; + } + } + + return stat; +} // end removeFile + +Status moveFile(const char* originPath, const char* destPath) { + Status stat = OP_OK; + + if (::rename(originPath, destPath) == -1) { + switch (errno) { + case EACCES: + case EPERM: + case EROFS: + case EFAULT: + stat = NO_PERMISSION; + break; + case EDQUOT: + case ENOSPC: + stat = NO_SPACE; + break; + case ELOOP: + case ENAMETOOLONG: + case ENOENT: + case EINVAL: + stat = INVALID_PATH; + break; + case ENOTDIR: + case EISDIR: // Old path is not a dir + stat = NOT_DIR; + break; + case ENOTEMPTY: + case EEXIST: + stat = NOT_EMPTY; + break; + case EMLINK: + stat = FILE_LIMIT; + break; + case EBUSY: + stat = BUSY; + break; + default: + stat = OTHER_ERROR; + break; + } + } + return stat; + +} // end moveFile + +Status handleFileError(File::Status fileStatus) { + Status fileSystemStatus = OTHER_ERROR; + + switch (fileStatus) { + case File::NO_SPACE: + fileSystemStatus = NO_SPACE; + break; + case File::NO_PERMISSION: + fileSystemStatus = NO_PERMISSION; + break; + case File::DOESNT_EXIST: + fileSystemStatus = INVALID_PATH; + break; + default: + fileSystemStatus = OTHER_ERROR; + } + return fileSystemStatus; +} // end handleFileError + +/** + * A helper function that returns an "OP_OK" status if the given file + * exists and can be read from, otherwise returns an error status. + * + * If provided, will also initialize the given stat struct with file + * information. + */ +Status initAndCheckFileStats(const char* filePath, struct stat* fileInfo = nullptr) { + FileSystem::Status fs_status; + struct stat local_info; + if (!fileInfo) { + // No external struct given, so use the local one + fileInfo = &local_info; + } + + if (::stat(filePath, fileInfo) == -1) { + switch (errno) { + case EACCES: + fs_status = NO_PERMISSION; + break; + case ELOOP: + case ENOENT: + case ENAMETOOLONG: + fs_status = INVALID_PATH; + break; + case ENOTDIR: + fs_status = NOT_DIR; + break; + default: + fs_status = OTHER_ERROR; + break; + } + return fs_status; + } + + // Make sure the origin is a regular file + if (!S_ISREG(fileInfo->st_mode)) { + return INVALID_PATH; + } + + return OP_OK; +} + +/** + * A helper function that writes all the file information in the source + * file to the destination file (replaces/appends to end/etc. depending + * on destination file mode). + * + * Files must already be open and will remain open after this function + * completes. + * + * @param source File to copy data from + * @param destination File to copy data to + * @param size The number of bytes to copy + */ +Status copyFileData(File source, File destination, FwSizeType size) { + static_assert(FILE_SYSTEM_CHUNK_SIZE != 0, "FILE_SYSTEM_CHUNK_SIZE must be >0"); + U8 fileBuffer[FILE_SYSTEM_CHUNK_SIZE]; + File::Status file_status; + + // Set loop limit + const FwSizeType copyLoopLimit = (size / FILE_SYSTEM_CHUNK_SIZE) + 2; + + FwSizeType loopCounter = 0; + NATIVE_INT_TYPE chunkSize; + while (loopCounter < copyLoopLimit) { + chunkSize = FILE_SYSTEM_CHUNK_SIZE; + file_status = source.read(&fileBuffer, chunkSize, false); + if (file_status != File::OP_OK) { + return handleFileError(file_status); + } + + if (chunkSize == 0) { + // file has been successfully copied + break; + } + + file_status = destination.write(fileBuffer, chunkSize, true); + if (file_status != File::OP_OK) { + return handleFileError(file_status); + } + loopCounter++; + } + FW_ASSERT(loopCounter < copyLoopLimit); + + return FileSystem::OP_OK; +} // end copyFileData + +Status copyFile(const char* originPath, const char* destPath) { + FileSystem::Status fs_status; + File::Status file_status; + + FwSizeType fileSize = 0; + + File source; + File destination; + + fs_status = initAndCheckFileStats(originPath); + if (FileSystem::OP_OK != fs_status) { + return fs_status; + } + + // Get the file size: + fs_status = + FileSystem::getFileSize(originPath, fileSize); //!< gets the size of the file (in bytes) at location path + if (FileSystem::OP_OK != fs_status) { + return fs_status; + } + + file_status = source.open(originPath, File::OPEN_READ); + if (file_status != File::OP_OK) { + return handleFileError(file_status); + } + + file_status = destination.open(destPath, File::OPEN_WRITE); + if (file_status != File::OP_OK) { + return handleFileError(file_status); + } + + fs_status = copyFileData(source, destination, fileSize); + + (void)source.close(); + (void)destination.close(); + + return fs_status; +} // end copyFile + +Status appendFile(const char* originPath, const char* destPath, bool createMissingDest) { + FileSystem::Status fs_status; + File::Status file_status; + FwSizeType fileSize = 0; + + File source; + File destination; + + fs_status = initAndCheckFileStats(originPath); + if (FileSystem::OP_OK != fs_status) { + return fs_status; + } + + // Get the file size: + fs_status = + FileSystem::getFileSize(originPath, fileSize); //!< gets the size of the file (in bytes) at location path + if (FileSystem::OP_OK != fs_status) { + return fs_status; + } + + file_status = source.open(originPath, File::OPEN_READ); + if (file_status != File::OP_OK) { + return handleFileError(file_status); + } + + // If needed, check if destination file exists (and exit if not) + if (!createMissingDest) { + fs_status = initAndCheckFileStats(destPath); + if (FileSystem::OP_OK != fs_status) { + return fs_status; + } + } + + file_status = destination.open(destPath, File::OPEN_APPEND); + if (file_status != File::OP_OK) { + return handleFileError(file_status); + } + + fs_status = copyFileData(source, destination, fileSize); + + (void)source.close(); + (void)destination.close(); + + return fs_status; +} // end appendFile + +Status getFileSize(const char* path, FwSizeType& size) { + Status fileStat = OP_OK; + struct stat fileStatStruct; + + fileStat = initAndCheckFileStats(path, &fileStatStruct); + if (FileSystem::OP_OK == fileStat) { + // Only check size if struct was initialized successfully + size = fileStatStruct.st_size; + if (static_cast(size) != fileStatStruct.st_size) { + return FileSystem::OTHER_ERROR; + } + } + + return fileStat; +} // end getFileSize + +Status changeWorkingDirectory(const char* path) { + Status stat = OP_OK; + + if (::chdir(path) == -1) { + switch (errno) { + case EACCES: + case EFAULT: + stat = NO_PERMISSION; + break; + case ENOTEMPTY: + stat = NOT_EMPTY; + break; + case ENOENT: + case ELOOP: + case ENAMETOOLONG: + stat = INVALID_PATH; + break; + case ENOTDIR: + stat = NOT_DIR; + break; + default: + stat = OTHER_ERROR; + break; + } + } + + return stat; +} // end changeWorkingDirectory + +Status getFreeSpace(const char* path, FwSizeType& totalBytes, FwSizeType& freeBytes) { + Status stat = OP_OK; + + struct statvfs fsStat; + int ret = statvfs(path, &fsStat); + if (ret) { + switch (errno) { + case EACCES: + stat = NO_PERMISSION; + break; + case ELOOP: + case ENOENT: + case ENAMETOOLONG: + stat = INVALID_PATH; + break; + case ENOTDIR: + stat = NOT_DIR; + break; + default: + stat = OTHER_ERROR; + break; + } + return stat; + } + + const FwSizeType block_size = static_cast(fsStat.f_frsize); + const FwSizeType free_blocks = static_cast(fsStat.f_bfree); + const FwSizeType total_blocks = static_cast(fsStat.f_blocks); + + // Check for casting and type error + if (((block_size <= 0) || (static_cast(block_size) != fsStat.f_frsize)) || + ((free_blocks <= 0) || (static_cast(free_blocks) != fsStat.f_bfree)) || + ((total_blocks <= 0) || (static_cast(block_size) != fsStat.f_blocks))) { + return OTHER_ERROR; + } + // Check for overflow in multiplication + if (free_blocks > (FpLimits::FwSizeType_MAX / block_size) || + total_blocks > (FpLimits::FwSizeType_MAX / block_size)) { + return OTHER_ERROR; + } + freeBytes = free_blocks * block_size; + totalBytes = total_blocks * block_size; + return stat; +} + +// Public function to get the file count for a given directory. +Status getFileCount(const char* directory, U32& fileCount) { + Status dirStat = OP_OK; + DIR* dirPtr = nullptr; + struct dirent* direntData = nullptr; + U32 limitCount; + const U32 loopLimit = FpLimits::U32_MAX; + + fileCount = 0; + if ((dirPtr = ::opendir(directory)) == nullptr) { + switch (errno) { + case EACCES: + dirStat = NO_PERMISSION; + break; + case ENOENT: + dirStat = INVALID_PATH; + break; + case ENOTDIR: + dirStat = NOT_DIR; + break; + default: + dirStat = OTHER_ERROR; + break; + } + return dirStat; + } + + // Set errno to 0 so we know why we exited readdir + errno = 0; + for (limitCount = 0; limitCount < loopLimit; limitCount++) { + if ((direntData = ::readdir(dirPtr)) != nullptr) { + // We are only counting regular files + if (direntData->d_type == DT_REG) { + fileCount++; + } + } else { + // readdir failed, did it error or did we run out of files? + if (errno != 0) { + // Only error from readdir is EBADF + dirStat = OTHER_ERROR; + } + break; + } + } + if (limitCount == loopLimit) { + dirStat = FILE_LIMIT; + } + + if (::closedir(dirPtr) == -1) { + // Only error from closedir is EBADF + dirStat = OTHER_ERROR; + } + + return dirStat; +} // end getFileCount + +} // namespace FileSystem + +} // namespace Os diff --git a/Os/Linux/SystemResources.cpp b/Os/Linux/SystemResources.cpp index e4f4c51dfa..00be4ab0df 100644 --- a/Os/Linux/SystemResources.cpp +++ b/Os/Linux/SystemResources.cpp @@ -84,12 +84,32 @@ namespace Os { struct sysinfo memory_info; sysinfo(&memory_info); - if (memory_info.totalram < memory_info.freeram) { + + const FwSizeType total_ram = static_cast(memory_info.totalram); + const FwSizeType free_ram = static_cast(memory_info.freeram); + const FwSizeType memory_unit = static_cast(memory_info.mem_unit); + + // Check for casting and type errors + if (((total_ram <= 0) || (static_cast(total_ram) != memory_info.totalram)) || + ((free_ram <= 0) || (static_cast(free_ram) != memory_info.freeram)) || + ((memory_unit <= 0) || (static_cast(memory_unit) != memory_info.mem_unit)) + ) { + return SYSTEM_RESOURCES_ERROR; + } + + // Check for invalid memory calculations + if (total_ram < free_ram) { + return SYSTEM_RESOURCES_ERROR; + } + + // Check for overflow in multiplication + if (total_ram > (FpLimits::FwSizeType_MAX / memory_unit)) + { return SYSTEM_RESOURCES_ERROR; } - memory_util.total = static_cast(memory_info.totalram * memory_info.mem_unit); - memory_util.used = static_cast((memory_info.totalram - memory_info.freeram) * memory_info.mem_unit); + memory_util.total = total_ram * memory_unit; + memory_util.used = (total_ram - free_ram) * memory_unit; return SYSTEM_RESOURCES_OK; } diff --git a/Os/MacOs/SystemResources.cpp b/Os/MacOs/SystemResources.cpp index ded252b382..500ba129c7 100644 --- a/Os/MacOs/SystemResources.cpp +++ b/Os/MacOs/SystemResources.cpp @@ -30,7 +30,7 @@ namespace Os { * \param total: total memory in bytes * \return: kern_return_t with success/failure straight from the kernel */ -kern_return_t vm_stat_helper(U64& used, U64& total) { +kern_return_t vm_stat_helper(FwSizeType& used, FwSizeType& total) { mach_msg_type_number_t count = HOST_VM_INFO_COUNT; vm_statistics_data_t vmstat; vm_size_t vmsize; @@ -79,7 +79,7 @@ kern_return_t cpu_data_helper(processor_cpu_load_info_t& cpu_load_info, U32& cpu * * \return success/failure using kern_return_t */ -kern_return_t cpu_by_index(U32 cpu_index, U64& used, U64& total) { +kern_return_t cpu_by_index(U32 cpu_index, FwSizeType& used, FwSizeType& total) { processor_cpu_load_info_t cpu_load_info; U32 cpu_count = 0; kern_return_t stat = cpu_data_helper(cpu_load_info, cpu_count); diff --git a/Os/SystemResources.hpp b/Os/SystemResources.hpp index a1825762c6..01a82b5830 100644 --- a/Os/SystemResources.hpp +++ b/Os/SystemResources.hpp @@ -23,13 +23,13 @@ enum SystemResourcesStatus { }; struct CpuTicks { - U64 used; //!< Filled with non-idle (system, user) CPU ticks - U64 total; //!< Filled with total CPU ticks + FwSizeType used; //!< Filled with non-idle (system, user) CPU ticks + FwSizeType total; //!< Filled with total CPU ticks }; struct MemUtil { - U64 used; //!< Filled with used bytes of volatile memory (permanent, paged-in) - U64 total; //!< Filled with total non-volatile memory + FwSizeType used; //!< Filled with used bytes of volatile memory (permanent, paged-in) + FwSizeType total; //!< Filled with total non-volatile memory }; /** diff --git a/Os/TaskCommon.cpp b/Os/TaskCommon.cpp index 57f3aa90c3..11de91cfc3 100644 --- a/Os/TaskCommon.cpp +++ b/Os/TaskCommon.cpp @@ -1,11 +1,10 @@ #include #include -#include -#include -#include +#include + namespace Os { - const NATIVE_UINT_TYPE Task::TASK_DEFAULT = std::numeric_limits::max(); + const NATIVE_UINT_TYPE Task::TASK_DEFAULT = FpLimits::PlatformUIntType_MAX; TaskRegistry* Task::s_taskRegistry = nullptr; NATIVE_INT_TYPE Task::s_numTasks = 0; diff --git a/Os/ValidateFileCommon.cpp b/Os/ValidateFileCommon.cpp index c9c8bf3346..39b69b5325 100644 --- a/Os/ValidateFileCommon.cpp +++ b/Os/ValidateFileCommon.cpp @@ -18,9 +18,10 @@ namespace Os { // Get the file size: FileSystem::Status fs_status; - U64 fileSize = 0; + FwSizeType fileSize = 0; fs_status = FileSystem::getFileSize(fileName, fileSize); //!< gets the size of the file (in bytes) at location path - if( FileSystem::OP_OK != fs_status ) { + // fileSize will be used as a NATIVE_INT_TYPE below and thus must cast cleanly to that type + if( FileSystem::OP_OK != fs_status || static_cast(static_cast(fileSize)) != fileSize) { return File::BAD_SIZE; } const NATIVE_INT_TYPE max_itr = static_cast(fileSize/VFILE_HASH_CHUNK_SIZE + 1); diff --git a/Os/test/ut/OsFileSystemTest.cpp b/Os/test/ut/OsFileSystemTest.cpp index 3ead1c4f3a..54608a4b69 100644 --- a/Os/test/ut/OsFileSystemTest.cpp +++ b/Os/test/ut/OsFileSystemTest.cpp @@ -22,7 +22,7 @@ void testTestFileSystem() { const char up_dir[] = "../"; const char cur_dir[] = "."; struct stat info; - U64 file_size = 42; + FwSizeType file_size = 42; U32 file_count = 0; const char test_string[] = "This is a test file."; NATIVE_INT_TYPE test_string_len = 0; diff --git a/Os/test/ut/OsSystemResourcesTest.cpp b/Os/test/ut/OsSystemResourcesTest.cpp index 1d6219cded..36cb78f2f5 100644 --- a/Os/test/ut/OsSystemResourcesTest.cpp +++ b/Os/test/ut/OsSystemResourcesTest.cpp @@ -7,7 +7,6 @@ void testTestSystemResources() { Os::SystemResources::SystemResourcesStatus sys_res_status; Os::SystemResources::CpuTicks cpuUtil; - Os::SystemResources::MemUtil memUtil; U32 cpuCount; U32 cpuIndex; @@ -22,9 +21,6 @@ void testTestSystemResources() { cpuIndex = 1000; sys_res_status = Os::SystemResources::getCpuTicks(cpuUtil, cpuIndex); ASSERT_EQ(sys_res_status, Os::SystemResources::SystemResourcesStatus::SYSTEM_RESOURCES_ERROR); - - sys_res_status = Os::SystemResources::getMemUtil(memUtil); - ASSERT_EQ(sys_res_status, Os::SystemResources::SystemResourcesStatus::SYSTEM_RESOURCES_OK); } extern "C" { diff --git a/Os/test/ut/OsValidateFileTest.cpp b/Os/test/ut/OsValidateFileTest.cpp index bca810b3b5..db749be20f 100644 --- a/Os/test/ut/OsValidateFileTest.cpp +++ b/Os/test/ut/OsValidateFileTest.cpp @@ -48,7 +48,7 @@ void testValidateFile(const char* fileName) { // Get file size: printf("Checking file size of %s.\n", hashFileName); - U64 fileSize=0; + FwSizeType fileSize=0; fsStatus = Os::FileSystem::getFileSize(hashFileName, fileSize); if( Os::FileSystem::OP_OK != fsStatus ) { printf("\tFailed to get file size of %s\n", hashFileName); diff --git a/Svc/ActiveTextLogger/LogFile.cpp b/Svc/ActiveTextLogger/LogFile.cpp index 38d8e12028..4b95efd00b 100644 --- a/Svc/ActiveTextLogger/LogFile.cpp +++ b/Svc/ActiveTextLogger/LogFile.cpp @@ -95,7 +95,7 @@ namespace Svc { } U32 suffix = 0; - U64 tmp; + FwSizeType tmp; char fileNameFinal[Fw::String::STRING_SIZE]; (void) strncpy(fileNameFinal,fileName, Fw::String::STRING_SIZE); diff --git a/Svc/ActiveTextLogger/test/ut/Tester.cpp b/Svc/ActiveTextLogger/test/ut/Tester.cpp index 36ebf598c3..4c742a9f1b 100644 --- a/Svc/ActiveTextLogger/test/ut/Tester.cpp +++ b/Svc/ActiveTextLogger/test/ut/Tester.cpp @@ -125,7 +125,7 @@ namespace Svc { ASSERT_EQ(512U, this->component.m_log_file.m_maxFileSize); // Test predicted size matches actual: - U64 fileSize = 0; + FwSizeType fileSize = 0; Os::FileSystem::getFileSize("test_file",fileSize); ASSERT_EQ(fileSize,this->component.m_log_file.m_currentFileSize); @@ -164,7 +164,7 @@ namespace Svc { { // TODO file errors- use the Os/Stubs? - U64 tmp; + FwSizeType tmp; printf("Testing writing text that is larger than FW_INTERNAL_INTERFACE_STRING_MAX_SIZE\n"); // Can't test this b/c max size of TextLogString is 256 and diff --git a/Svc/BufferLogger/test/ut/Tester.cpp b/Svc/BufferLogger/test/ut/Tester.cpp index f32c8a749f..548d03a5a9 100644 --- a/Svc/BufferLogger/test/ut/Tester.cpp +++ b/Svc/BufferLogger/test/ut/Tester.cpp @@ -265,7 +265,7 @@ namespace Svc { { // Make sure the file size is within bounds - U64 actualSize = 0; + FwSizeType actualSize = 0; const Os::FileSystem::Status status = Os::FileSystem::getFileSize(fileName, actualSize); ASSERT_EQ(Os::FileSystem::OP_OK, status); diff --git a/Svc/CmdSequencer/formats/AMPCSSequence.cpp b/Svc/CmdSequencer/formats/AMPCSSequence.cpp index 31d9e29f92..5b39715501 100644 --- a/Svc/CmdSequencer/formats/AMPCSSequence.cpp +++ b/Svc/CmdSequencer/formats/AMPCSSequence.cpp @@ -80,20 +80,23 @@ namespace Svc { getFileSize(const Fw::CmdStringArg& seqFileName) { bool status = true; - U64 fileSize; + FwSizeType fileSize; this->setFileName(seqFileName); const Os::FileSystem::Status fileStatus = Os::FileSystem::getFileSize(this->m_fileName.toChar(), fileSize); + // fileSize will be used to set a U32 member below, thus we check overflow first + bool overflow = static_cast(static_cast(fileSize)) != fileSize; if ( fileStatus == Os::FileSystem::OP_OK and - fileSize >= sizeof(this->m_sequenceHeader) + fileSize >= sizeof(this->m_sequenceHeader) and + !overflow ) { this->m_header.m_fileSize = static_cast(fileSize - sizeof(this->m_sequenceHeader)); } else { this->m_events.fileInvalid( CmdSequencer_FileReadStage::READ_HEADER_SIZE, - fileStatus + overflow ? Os::FileSystem::OTHER_ERROR : fileStatus ); status = false; } diff --git a/Svc/ComLogger/test/ut/Tester.cpp b/Svc/ComLogger/test/ut/Tester.cpp index b45a380452..18020874ee 100644 --- a/Svc/ComLogger/test/ut/Tester.cpp +++ b/Svc/ComLogger/test/ut/Tester.cpp @@ -136,7 +136,7 @@ namespace Svc { // Make sure the file size is smaller or equal to the limit: Os::FileSystem::Status fsStat; - U64 fileSize = 0; + FwSizeType fileSize = 0; fsStat = Os::FileSystem::getFileSize(fileName, fileSize); //!< gets the size of the file (in bytes) at location path ASSERT_EQ(fsStat, Os::FileSystem::OP_OK); ASSERT_LE(fileSize, MAX_BYTES_PER_FILE); @@ -259,7 +259,7 @@ namespace Svc { // Make sure the file size is smaller or equal to the limit: Os::FileSystem::Status fsStat; - U64 fileSize = 0; + FwSizeType fileSize = 0; fsStat = Os::FileSystem::getFileSize(fileName, fileSize); //!< gets the size of the file (in bytes) at location path ASSERT_EQ(fsStat, Os::FileSystem::OP_OK); ASSERT_LE(fileSize, MAX_BYTES_PER_FILE); diff --git a/Svc/FileDownlink/File.cpp b/Svc/FileDownlink/File.cpp index 34cead16b6..2b6caa09be 100644 --- a/Svc/FileDownlink/File.cpp +++ b/Svc/FileDownlink/File.cpp @@ -33,11 +33,15 @@ namespace Svc { this->destName = destLogStringArg; // Set size - U64 size; + FwSizeType size; const Os::FileSystem::Status status = Os::FileSystem::getFileSize(sourceFileName, size); if (status != Os::FileSystem::OP_OK) return Os::File::BAD_SIZE; + // If the size does not cast cleanly to the desired U32 type, return size error + if (static_cast(static_cast(size)) != size) { + return Os::File::BAD_SIZE; + } this->size = static_cast(size); // Initialize checksum @@ -66,8 +70,10 @@ namespace Svc { status = this->osFile.read(data, intSize); if (status != Os::File::OP_OK) return status; - FW_ASSERT(static_cast(intSize) == size); - + // Force a bad size error when the U32 carrying size is bad + if (static_cast(intSize) != size) { + return Os::File::BAD_SIZE; + } this->checksum.update(data, byteOffset, size); return Os::File::OP_OK; diff --git a/Svc/FileDownlink/docs/sdd.md b/Svc/FileDownlink/docs/sdd.md index dff4c312d0..0e44c68ea4 100644 --- a/Svc/FileDownlink/docs/sdd.md +++ b/Svc/FileDownlink/docs/sdd.md @@ -12,6 +12,9 @@ has completed. To prevent a continuous stream of file downlink traffic from satu communication link, a cooldown can be configured to add a delay between the completion of a file downlink and starting on the next file in the queue. +**Note:** file downlink is limited to processing files with a maximum file size of 4GiB. Larger files will result in a +bad size error. + ## 2 Requirements Requirement | Description | Rationale | Verification Method diff --git a/Svc/FramingProtocol/FprimeProtocol.cpp b/Svc/FramingProtocol/FprimeProtocol.cpp index 666d48c2b5..dd3873f21f 100644 --- a/Svc/FramingProtocol/FprimeProtocol.cpp +++ b/Svc/FramingProtocol/FprimeProtocol.cpp @@ -9,10 +9,8 @@ // acknowledged. // // ====================================================================== - -#include - #include "FprimeProtocol.hpp" +#include "FpConfig.hpp" #include "Utils/Hash/Hash.hpp" namespace Svc { @@ -102,7 +100,7 @@ DeframingProtocol::DeframingStatus FprimeDeframing::deframe(Types::CircularBuffe // Read size from header status = ring.peek(size, sizeof(FpFrameHeader::TokenType)); FW_ASSERT(status == Fw::FW_SERIALIZE_OK, status); - const U32 maxU32 = std::numeric_limits::max(); + const U32 maxU32 = FpLimits::U32_MAX; if (size > maxU32 - (FpFrameHeader::SIZE + HASH_DIGEST_LENGTH)) { // Size is too large to process: needed would overflow return DeframingProtocol::DEFRAMING_INVALID_SIZE; diff --git a/Svc/SystemResources/SystemResources.cpp b/Svc/SystemResources/SystemResources.cpp index 7f476b1dc1..7de8f3b36f 100644 --- a/Svc/SystemResources/SystemResources.cpp +++ b/Svc/SystemResources/SystemResources.cpp @@ -142,8 +142,8 @@ void SystemResources::Mem() { } void SystemResources::PhysMem() { - U64 total = 0; - U64 free = 0; + FwSizeType total = 0; + FwSizeType free = 0; if (Os::FileSystem::getFreeSpace("/", total, free) == Os::FileSystem::OP_OK) { this->tlmWrite_NON_VOLATILE_FREE(free / 1024); diff --git a/Svc/SystemResources/docs/sdd.md b/Svc/SystemResources/docs/sdd.md new file mode 100644 index 0000000000..c89a5f269d --- /dev/null +++ b/Svc/SystemResources/docs/sdd.md @@ -0,0 +1,12 @@ +# System Resources Component + +The system resources component downlinks information about the running F´ system. This information includes: + +1. System and Software version +2. Free Memory +3. CPU load +4. Disk space + +These items are downlinked as telemetry channels in response to a rate group port invocation. + +**Note:** system resources requires `U64` types to be available on the target architecture. \ No newline at end of file diff --git a/Svc/SystemResources/test/ut/Tester.cpp b/Svc/SystemResources/test/ut/Tester.cpp index 19f5dbbfda..94d32ecdd4 100644 --- a/Svc/SystemResources/test/ut/Tester.cpp +++ b/Svc/SystemResources/test/ut/Tester.cpp @@ -88,19 +88,36 @@ void Tester ::test_tlm(bool enabled) { ASSERT_TLM_CPU_00_SIZE((enabled) ? 1 : 0); // Cascade expected default: + FwSizeType free = 0; + FwSizeType total = 0; + Os::SystemResources::MemUtil memory_info; ASSERT_TLM_CPU_SIZE((enabled) ? 1 : 0); - ASSERT_TLM_MEMORY_USED_SIZE((enabled) ? 1 : 0); - ASSERT_TLM_MEMORY_TOTAL_SIZE((enabled) ? 1 : 0); - ASSERT_TLM_NON_VOLATILE_FREE_SIZE((enabled) ? 1 : 0); - ASSERT_TLM_NON_VOLATILE_TOTAL_SIZE((enabled) ? 1 : 0); + // Check that the filesystem reads well before asserting telemetry + if (enabled && Os::SystemResources::getMemUtil(memory_info) == Os::SystemResources::SYSTEM_RESOURCES_OK) { + ASSERT_TLM_MEMORY_USED_SIZE(1); + ASSERT_TLM_MEMORY_TOTAL_SIZE(1); + count += 2; + } else { + ASSERT_TLM_MEMORY_USED_SIZE(0); + ASSERT_TLM_MEMORY_TOTAL_SIZE(0); + } + // Check that the filesystem reads well before asserting telemetry + if (enabled && Os::FileSystem::getFreeSpace("/", free, total ) == Os::FileSystem::OP_OK) { + ASSERT_TLM_NON_VOLATILE_FREE_SIZE(1); + ASSERT_TLM_NON_VOLATILE_TOTAL_SIZE(1); + count += 2; + } else { + ASSERT_TLM_NON_VOLATILE_FREE_SIZE(0); + ASSERT_TLM_NON_VOLATILE_TOTAL_SIZE(0); + } ASSERT_TLM_FRAMEWORK_VERSION_SIZE((enabled) ? 1 : 0); ASSERT_TLM_PROJECT_VERSION_SIZE((enabled) ? 1 : 0); if (enabled) { ASSERT_TLM_FRAMEWORK_VERSION(0, FRAMEWORK_VERSION); ASSERT_TLM_PROJECT_VERSION(0, PROJECT_VERSION); } - ASSERT_TLM_SIZE((enabled) ? (count + 7) : 0); // CPU count channels + avg + 2 mem + 2 non-volatile + 2 ver + ASSERT_TLM_SIZE((enabled) ? (count + 3) : 0); // CPU count channels + avg + 2 ver break; } } diff --git a/Utils/CRCChecker.cpp b/Utils/CRCChecker.cpp index 3b1bbe92d1..e5ba06e444 100644 --- a/Utils/CRCChecker.cpp +++ b/Utils/CRCChecker.cpp @@ -26,7 +26,7 @@ namespace Utils { NATIVE_INT_TYPE i; NATIVE_INT_TYPE blocks; NATIVE_INT_TYPE remaining_bytes; - U64 filesize; + FwSizeType filesize; Os::File f; Os::FileSystem::Status fs_stat; Os::File::Status stat; @@ -46,7 +46,7 @@ namespace Utils { } int_file_size = static_cast(filesize); - if(static_cast(int_file_size) != filesize) + if(static_cast(int_file_size) != filesize) { return FAILED_FILE_SIZE_CAST; } @@ -154,7 +154,7 @@ namespace Utils { NATIVE_INT_TYPE i; NATIVE_INT_TYPE blocks; NATIVE_INT_TYPE remaining_bytes; - U64 filesize; + FwSizeType filesize; Os::File f; Os::FileSystem::Status fs_stat; Os::File::Status stat; @@ -172,7 +172,7 @@ namespace Utils { } int_file_size = static_cast(filesize); - if(static_cast(int_file_size) != filesize) + if(static_cast(int_file_size) != filesize) { return FAILED_FILE_SIZE_CAST; } diff --git a/Utils/Types/Queue.hpp b/Utils/Types/Queue.hpp index 625c6316cd..157233d8d7 100644 --- a/Utils/Types/Queue.hpp +++ b/Utils/Types/Queue.hpp @@ -17,8 +17,6 @@ #include #include -typedef U32 FwSizeType; // TODO: replace with refactored types when available - namespace Types { class Queue { From 5dca1cd7f1156b9f7c1282a9f656a96e4bcaa4fa Mon Sep 17 00:00:00 2001 From: Ani Date: Thu, 12 Jan 2023 16:11:30 -0700 Subject: [PATCH 123/169] Added information on STest (#1783) * Added information on STest * A few edits to the STest README * A few more edits to the STest README * Revise fonts * More edits * More edits Co-authored-by: Rob Bocchino --- STest/README.md | 62 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 62 insertions(+) diff --git a/STest/README.md b/STest/README.md index e69de29bb2..4d2a03fc0c 100644 --- a/STest/README.md +++ b/STest/README.md @@ -0,0 +1,62 @@ +## STest + +STest is a framework for using **rules** and **scenarios** to construct and run unit tests. +The concepts of "rules" and "scenarios" are described below. +Using rules and scenarios provides structure to unit tests. +By automatically generating tests, scenarios can also provide more coverage than is possible +with manually-written tests. + +- [State](#state) +- [Rule](#rule) +- [Scenario](#scenario) +- [Use in F Prime](#use-in-f-prime) + +


    + +### State + +In rule-based testing, **state** refers to the current state of a running test. It usually includes **concrete state** (the actual state of the system under test) and **test state** or **abstract state** (state that abstracts the state of the system under test, to assist with modeling). + +In the STest implementation of rule-based testing, `State` is a user-defined type. The `Rule` and `Scenario` classes discussed below are templates that are parameterized over this type. + +### Rule + +A **rule** is a unit of test code that specifies and checks some behavior of the system under test. +It has two elements: + +1. A **precondition** that specifies when the rule may be applied. +A precondition is a predicate function (i.e., a read-only function that returns a Boolean value) on +the [system state](#state). +For example, consider a rule that exercises the nominal behavior of a buffer allocator. +The precondition for this rule might specify that a buffer is available for allocation. +On the other hand, the precondition for a rule that exercises the error case "buffer not available" +might specify that all buffers have been allocated. + +2. An **action** that (a) causes the system under test to do something and (b) checks that the resulting +behavior is as expected, given the current system state. +For example, a "nominal" or "OK" rule for a buffer allocator might check that a buffer was allocated. +A "buffer not available" rule might check that the appropriate warning is emitted as an F' event. + +When using STest, you specify rules as derived classes of the abstract class [Rule](./STest/Rule/Rule.hpp). +You specify the precondition and action by overriding pure virtual functions specified in the `Rule` interface. + +### Scenario +A **scenario** is a recipe for using a set of rules to construct one or more tests. Examples of scenarios include the following: +- Applying a set of rules in a sequence which is either fixed ([RuleSequenceScenario](./STest/Scenario/RuleSequenceScenario.hpp)) or randomized ([RandomScenario](./STest/Scenario/RandomScenario.hpp)) +- Repeatedly applying a rule within a scenario ([RepeatedRuleScenario](./STest/Scenario/RepeatedRuleScenario.hpp)) +- Running a scenario while a condition holds ([ConditionalScenario](./STest/Scenario/ConditionalScenario.hpp)) +- Creating a sequence of scenarios ([SequenceScenario](./STest/Scenario/SequenceScenario.hpp)) and randomly selecting one of them to run ([SelectedScenario](./STest/Scenario/SelectedScenario.hpp)) +- Randomly interleaving a set of scenarios ([InterleavedScenario](./STest/Scenario/InterleavedScenario.hpp)) +- Iterating over a collection of scenarios ([IteratedScenario](./STest/Scenario/IteratedScenario.hpp)) or over a particular one till a certain condition holds ([ConditionalIteratedScenario](./STest/Scenario/ConditionalIteratedScenario.hpp)) +- Running an iterated scenario with a specific bound on the number of iterations ([BoundedIteratedScenario](./STest/Scenario/BoundedIteratedScenario.hpp)) +- Running a scenario for a certain bound, with the range being either fixed ([BoundedScenario](./STest/Scenario/BoundedScenario.hpp)) or randomly selected ([RandomlyBoundedScenario](./STest/Scenario/RandomlyBoundedScenario.hpp)) + +The iterated and random scenarios allow you to construct complex tests that explore many behaviors, using relatively simple specifications. Typically the tests constructed with these scenarios are not feasible to write by hand (e.g., because they apply thousands or millions of rules). + +### Use in F Prime + +At present, F Prime uses STest for unit testing of components. Examples include [Svc/GroundInterface](https://github.com/nasa/fprime/blob/master/Svc/GroundInterface/test/ut/GroundInterfaceRules.cpp) and [Fw/Logger](https://github.com/nasa/fprime/blob/master/Fw/Logger/test/ut/LoggerRules.cpp). The main scenarios used here are +as follows: + +* Short sequences of rules that set up the system state and then test a particular rule. +* Random scenarios for automatically generating more complex tests. From 54d89871e275e64d323c748d87cb1d017b4148c9 Mon Sep 17 00:00:00 2001 From: Ani Date: Thu, 12 Jan 2023 16:24:57 -0700 Subject: [PATCH 124/169] Documentation revision (./docs/*.md files) (#1570) * Corrections and edits for *.md files in the root of /docs * Edits on docs/UsersGuide/best/*.md * Edits on docs/UsersGuide/cmake/*.md * Edits on *.md files at the root of docs/UsersGuide/dev/ * Edits on docs/UsersGuide/{dev,gds,user}/*.md * Edits on docs/Tutorials/*.md and a few others after a final read * Revert changes Co-authored-by: M Starch --- docs/INSTALL.md | 17 ++-- docs/Tutorials/CrossCompilation/Tutorial.md | 4 +- docs/Tutorials/GettingStarted/Tutorial.md | 22 ++--- docs/Tutorials/GpsTutorial/Tutorial.md | 81 +++++++++---------- docs/UsersGuide/best/app-man-drv.md | 20 ++--- docs/UsersGuide/best/development-practice.md | 51 ++++++------ docs/UsersGuide/best/documentation.md | 29 ++++--- docs/UsersGuide/best/dynamic-memory.md | 57 ++++++------- docs/UsersGuide/best/ground-interface.md | 24 +++--- docs/UsersGuide/best/hub-pattern.md | 7 +- docs/UsersGuide/best/rate-group.md | 19 ++--- docs/UsersGuide/cmake/Customization.md | 14 ++-- docs/UsersGuide/cmake/Migration.md | 23 +++--- docs/UsersGuide/cmake/Targets.md | 10 +-- docs/UsersGuide/cmake/cmake-advanced.md | 11 ++- docs/UsersGuide/cmake/cmake-api.md | 6 +- docs/UsersGuide/cmake/cmake-intro.md | 25 +++--- docs/UsersGuide/cmake/cmake-platforms.md | 12 +-- docs/UsersGuide/cmake/cmake-toolchains.md | 9 +-- docs/UsersGuide/cmake/cmake-uts.md | 6 +- docs/UsersGuide/dev/assert.md | 2 +- docs/UsersGuide/dev/autocoder-integration.md | 51 +++++------- docs/UsersGuide/dev/baremetal-multicore.md | 40 ++++----- docs/UsersGuide/dev/building-topology.md | 6 +- docs/UsersGuide/dev/code-style.md | 37 +++++---- docs/UsersGuide/dev/configure-ide.md | 16 ++-- docs/UsersGuide/dev/configuring-fprime.md | 36 ++++----- docs/UsersGuide/dev/cookiecutter.md | 4 +- docs/UsersGuide/dev/gds-cli-dev.md | 16 ++-- .../UsersGuide/dev/gds-dashboard-reference.md | 15 ++-- docs/UsersGuide/dev/implementation.md | 12 +-- docs/UsersGuide/dev/os-docs.md | 17 ++-- docs/UsersGuide/dev/porting-guide.md | 8 +- docs/UsersGuide/dev/py-dev.md | 16 ++-- docs/UsersGuide/dev/source-tree.md | 20 +++-- docs/UsersGuide/dev/target-integration.md | 16 ++-- .../dev/testAPI/markdown/test_logger.md | 6 +- docs/UsersGuide/dev/xml-specification.md | 34 ++++---- docs/UsersGuide/gds/gds-cli.md | 18 ++--- docs/UsersGuide/gds/gds-custom-dashboards.md | 12 +-- docs/UsersGuide/gds/gds-introduction.md | 61 +++++++------- docs/UsersGuide/gds/seqgen.md | 22 ++--- docs/UsersGuide/guide.md | 26 +++--- docs/UsersGuide/user/autocomplete.md | 15 ++-- docs/UsersGuide/user/cmd-evt-chn-prm.md | 36 ++++----- docs/UsersGuide/user/enum-arr-ser.md | 10 +-- docs/UsersGuide/user/fprime-util.md | 22 ++--- docs/UsersGuide/user/full-intro.md | 26 +++--- docs/UsersGuide/user/port-comp-top.md | 40 ++++----- docs/UsersGuide/user/proj-dep.md | 11 ++- docs/UsersGuide/user/settings.md | 11 ++- docs/UsersGuide/user/unit-testing.md | 11 ++- docs/UsersGuide/user/v3-migration-guide.md | 16 ++-- docs/features.md | 4 +- docs/index.md | 2 +- 55 files changed, 535 insertions(+), 607 deletions(-) diff --git a/docs/INSTALL.md b/docs/INSTALL.md index a9865639b5..274ff70ad0 100644 --- a/docs/INSTALL.md +++ b/docs/INSTALL.md @@ -8,7 +8,7 @@ title: "F´ Installation Guide" This installation guide is specifically designed to enable individuals and researchers to get up and running with F´ quickly. Larger projects with specific requirements may need to extend this process. -**Note:** see the troubleshooting section at the bottom for help resolving common issues found during F´ installs. +**Note:** See the troubleshooting section at the bottom for help resolving common issues found during F´ installs. ## Requirements @@ -25,7 +25,7 @@ Requirements: 4. CLang or GNU C and C++ compilers (e.g. gcc and g++) 5. [Python 3.7+](https://www.python.org/downloads/), virtual environments, and PIP -**Note:** operating system specific notes are in the [Troubleshooting](#Troubleshooting) section below. +**Note:** OS-specific notes are in the [Troubleshooting](#Troubleshooting) section below. ### Setting Up F´ Environment @@ -50,7 +50,7 @@ pip install -U setuptools setuptools_scm wheel pip ### Cloning the F´ Repository and Installing F´ Tools -Installation of F´ requires cloning of the F´ core repository. This uses Git. This will bring down the core framework and C++ files. +Installation of F´ requires cloning of the F´ core repository via Git. This will bring down the core framework and C++ files. F´ ships with a `requirements.txt` file enumerating the tools F´ uses and their specific tested versions. **Clone F´ and Install Tools** @@ -90,7 +90,7 @@ installation). ## Advanced There are several advanced options users can consider while installing F´. However, users should be warned that some -knowledge of our tools and versions are often required. +knowledge of our tools and versions is often required. ### Installing Tab Completion @@ -140,7 +140,7 @@ install things more effectively. ### fprime-util: command not found -If the user is using a virtual environment and receives the command not found, the problem is likely caused by the +If the user is using a virtual environment and receives the 'command not found', the problem is likely caused by the environment not being sourced in a new terminal. Make sure to source the environment before running: ``` @@ -153,8 +153,7 @@ Users running without virtual environments should add this directory to the path ### Ubuntu, Debian, Java and Python PIP -Ubuntu and possibly other Debian variants don't include the pip packages in the default python 3 installation. To get a -fully functional, use these commands on Ubuntu and Debian based systems: +Ubuntu and possibly other Debian variants don't include the pip packages in the default Python 3 installation. To get fully functional, use these commands on Ubuntu and Debian based systems: ``` sudo apt install git cmake default-jre python3 python3-pip python3-venv @@ -176,9 +175,7 @@ More information can be found [here](https://stackoverflow.com/questions/3066860 ### System Python, Packages, and Python3 Many operating systems offer python PIP packages through their package manager (apt, yum, etc). Most python projects -recommend avoiding those packages, but rather installing from PIP in a virtual environment. The reason for this is that -the version of the python package from the OS may not be the required version that the python project depends on. Thus, -users may choose to install F´ into a virtual environment. This is outside the scope of this document. +recommend avoiding those packages and instead installing them from PIP in a virtual environment. The reason for this is that the version of the python package from the OS may not be the required version that the python project depends on. Thus, users may choose to install F´ into a virtual environment. This is outside the scope of this document. ### SSL Error with Python 3.6+ on macOS diff --git a/docs/Tutorials/CrossCompilation/Tutorial.md b/docs/Tutorials/CrossCompilation/Tutorial.md index 4898f9ea30..75890b32b8 100644 --- a/docs/Tutorials/CrossCompilation/Tutorial.md +++ b/docs/Tutorials/CrossCompilation/Tutorial.md @@ -11,7 +11,7 @@ ## 1. Introduction -In this section we will take our Ref topology and cross-compile it for the +In this section, we will take our Ref topology and cross-compile it for the Raspberry Pi. In order to fully benefit from this tutorial, the user should acquire a Raspberry Pi and have the cross-compilation toolchain as described in [RPI](https://github.com/nasa/fprime/blob/master/RPI/README.md). @@ -70,7 +70,7 @@ You can log into the Raspberry Pi via SSH by running: ssh pi@ ``` -Finally you can run the Ref deployment on the Raspberry Pi as follows: +Finally, you can run the Ref deployment on the Raspberry Pi as follows: ```sh ./Ref -a -p 50000 ``` diff --git a/docs/Tutorials/GettingStarted/Tutorial.md b/docs/Tutorials/GettingStarted/Tutorial.md index 5d26ee81b2..b9cef55ff6 100644 --- a/docs/Tutorials/GettingStarted/Tutorial.md +++ b/docs/Tutorials/GettingStarted/Tutorial.md @@ -38,9 +38,9 @@ An event is composed of a name, format string, and set of arguments that describ history of the system. Events are defined per-*component*. **Channel:** a channel, also known as a telemetry item, is a single value read and downlinked. Channels consist of -a type, a format specifier, and a value. Channels represent current system state. Channels are defined per-*component*. +a type, a format specifier, and a value. Channels represent the current system state. Channels are defined per-*component*. -**Command:** a command is uplinked data items that instructs the system to perform an action. *Commands* consist of an +**Command:** a command is uplinked data items that instruct the system to perform an action. *Commands* consist of an opcode, a mnemonic, and a list of arguments to the command. Commands are defined per-*component*. **Deployment:** a deployment is a single instance of F´. Although a single F´ project can use/define multiple @@ -72,14 +72,14 @@ the design is already in-place. Users can see the design by inspecting Componen new components from design through test is demonstrated in the [Math Component Tutorial](../MathComponent/Tutorial.md). The next step for developing a Component is to implement the code. To do this, one can generate template stubs to fill -with the developer's stubs. To do this, a user runs the F´ tool suite to generate these stubs. Then implements, builds, -and tests from there. Unit tests template stubs are generated in the same way, and should test-driven development be -preferred, these tests stubs could be generated and implemented before the Component's code. +with the developer's stubs. To do this, a user runs the F´ tool suite to generate these stubs. Then implements, builds, +and tests from there. Unit test template stubs are generated in the same way and should test-driven development be +preferred, these test stubs could be generated and implemented before the Component's code. Finally, the Component is integrated into the deployment and the entire deployment may be built and installed. This tutorial will walk developers through generating the templates, building example Components, and -building/installing the full deployment. It will use the `Ref` application as an example for this. +building/installing the full deployment. It will use the `Ref` application as an example for this. ## Working the F´ Development Process with `fprime-util` @@ -94,8 +94,8 @@ to compile against. It is usually done right after F´ is checked-out and repeat is a setup step and isn't formally part of the F´ development process. To run this tool, the developer will use the `generate` subcommand. It takes one optional argument: the toolchain file -used in CMake to compile for a specific platform. If not supplied, the `native` toolchain will be used and F´ will be -setup to run on the current platform (typically Mac OS, or Linux depending on the developer's chosen OS). +used in CMake to compile for a specific platform. If not supplied, the `native` toolchain will be used and F´ will be +set up to run on the current platform (typically Mac OS, or Linux depending on the developer's chosen OS). **Generate the Ref Application for Native Compilation** @@ -154,7 +154,7 @@ cd fprime/Ref/SignalGen fprime-util impl --ut ``` -This creates the following files, that are typically moved to a sub folder called `test/ut`. The files created are +This creates the following files, which are typically moved to a subfolder called `test/ut`. The files created are placed in the current directory and named: ``` Tester.cpp @@ -169,7 +169,7 @@ TestMain.cpp ### Building Components and Deployments Once a developer has implemented a component, it is time to build that component and test that component. In order to build -a component the `build` subcommand needs to be run. This will build the "current directory" that the developer is in. +a component, the `build` subcommand needs to be run. This will build the "current directory" that the developer is in. That means that should the user change into a deployment directory then the build command will build the full deployment. Should the user desire to build a component, navigate into the Component's directory and run the build command. @@ -259,4 +259,4 @@ applications. The next step is to follow the full `MathComponent` tutorial to cr *Topologies*. This will walk the user through the entire development process, using the tool commands we learned here. **Next:** [Math Component Tutorial](../MathComponent/Tutorial.md) -**Also See:** [GPS Component Tutorial](../GpsTutorial/Tutorial.md) for a cross-compiling tutorial. +**Also See:** [GPS Component Tutorial](../GpsTutorial/Tutorial.md) for a cross-compiling tutorial. \ No newline at end of file diff --git a/docs/Tutorials/GpsTutorial/Tutorial.md b/docs/Tutorials/GpsTutorial/Tutorial.md index 210746a3a9..ff434a0eb9 100644 --- a/docs/Tutorials/GpsTutorial/Tutorial.md +++ b/docs/Tutorials/GpsTutorial/Tutorial.md @@ -1,10 +1,9 @@ # F´ GPS Tutorial -**WARNING:** this tutorial is under revision for use with F´ 2.0.0. +**WARNING:** This tutorial is under revision for use with F´ 2.0.0. In this guide, we will cover the basics of working with F´ by attaching a GPS receiver to a serial driver and running -the application on a Raspberry PI. In order to fully benefit from this tutorial, the user should acquire any NMEA -compatible UART GPS receiver and a raspberry pi. In this tutorial, we use a NMEA GPS receiver with micro-USB such that +the application on a Raspberry PI. In order to fully benefit from this tutorial, the user should acquire any NMEA-compatible UART GPS receiver and a raspberry pi. In this tutorial, we use a NMEA GPS receiver with micro-USB such that the code may be run on both the laptop and the Raspberry PI. In the DIY electronics community there is an abundance of cheap GPS receivers based around the NMEA protocol. These @@ -15,7 +14,7 @@ receivers send are NMEA formatted ASCII text. This tutorial will show how to integrate one of these GPS receivers with the F´ framework by wrapping it in a Component and defining commands, telemetry, and log events. We will create a GpsApp deployment for the Component where it will -be wired to a standard UART driver in order to receive messages. Then we can cross compile it for the Raspberry PI and +be wired to a standard UART driver in order to receive messages. Then we can cross-compile it for the Raspberry PI and run the application against the F´ ground system. **Note:** A completed version of this tutorial app is available [here](https://github.com/fprime-community/gps-tutorial) @@ -35,13 +34,13 @@ understand this tutorial are as follows: 4. An understanding of the raspberry pi, specifically SSHing into the pi and running applications Installation can be done by following the installation guide found at: [INSTALL.md](../../INSTALL.md). This guide -will walk the user through the installation process and verifying the installation. In addition, users may wish to +will walk the user through the installation process and verify the installation. In addition, users may wish to follow the [Getting Started Tutorial](../GettingStarted/Tutorial.md) in order to get a feel for the F´ environment and tools. ## Creating a Custom F´ Component -In this next section we will create a custom F´ component for reading GPS data off a UART based GPS module. It will +In this next section, we will create a custom F´ component for reading GPS data off a UART-based GPS module. It will receive data from a UART read port, process the data, and report telemetry from that data. We will then finish up by adding an event to report GPS lock status when it changes and a command to report lock status on demand. @@ -49,7 +48,7 @@ Our custom component has the following functional block diagram: ![GPS Component Diagram](img/gps-comp.png) -**Note:** there are a few other ports our component will need to wire to other components in the system, the above +**Note:** There are a few other ports our component will need to wire to other components in the system, the above diagram captures the ports needed for our desired functionality. ### Designing the GPS Component @@ -60,8 +59,7 @@ and Telemetry Channel specifications are also written in XML. Further informati [User Guide](../../UsersGuide/FprimeUserGuide.pdf). This application does not need any custom ports, as we are using the standard ports to create our GPS handler. Custom ports can be seen in the [Math Component Tutorial](../MathComponent/Tutorial.md). -In this section we will create a directory for our GPS component, and design the component through XML. The first step -to making the component is to make a project directory to hold our project, and a component subdirectory for our GPS. +In this section, we will create a directory for our GPS component, and design the component through XML. The first step in making the component is to make a project directory to hold our project, and a component subdirectory for our GPS. ```shell cd fprime @@ -76,7 +74,7 @@ specify commands, telemetry, and events. As can be seen, we are creating our com ports defined above, and 4 additional ports described below: 1. **cmdIn**: an input port of *Fw::Cmd* type used to process commands sent to this component. -2. **cmdRegOut**: an output port of *Fw::CmdReg* type used to register this component's with the command dispatcher +2. **cmdRegOut**: an output port of *Fw::CmdReg* type used to register this component with the command dispatcher 3. **cmdResponseOut**: an output port of *Fw::CmdResponse* type used respond to dispatched commands 4. **eventOut**: an output port of *Fw::Log* type used to send events out 5. **textEventOut**: an output port of *Fw::LogText* type used to send events in a text form @@ -94,9 +92,9 @@ The `GpsComponentAi.xml` file in the `Gps` subdirectory should look like: diff --git a/Ref/Top/instances.fpp b/Ref/Top/instances.fpp index 86d2490e81..56edd8ad86 100644 --- a/Ref/Top/instances.fpp +++ b/Ref/Top/instances.fpp @@ -87,6 +87,8 @@ module Ref { stack size Default.STACK_SIZE \ priority 96 + instance typeDemo: Ref.TypeDemo base id 0x0E00 + # ---------------------------------------------------------------------- # Queued component instances # ---------------------------------------------------------------------- diff --git a/Ref/Top/topology.fpp b/Ref/Top/topology.fpp index 66b226b5db..6da5dccd55 100644 --- a/Ref/Top/topology.fpp +++ b/Ref/Top/topology.fpp @@ -51,6 +51,7 @@ module Ref { instance sendBuffComp instance staticMemory instance textLogger + instance typeDemo instance uplink instance systemResources diff --git a/Ref/TypeDemo/CMakeLists.txt b/Ref/TypeDemo/CMakeLists.txt new file mode 100644 index 0000000000..9a80610286 --- /dev/null +++ b/Ref/TypeDemo/CMakeLists.txt @@ -0,0 +1,13 @@ +#### +# F prime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoding files +# MOD_DEPS: (optional) module dependencies +# +#### +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/TypeDemo.fpp" + "${CMAKE_CURRENT_LIST_DIR}/TypeDemo.cpp" +) + +register_fprime_module() diff --git a/Ref/TypeDemo/TypeDemo.cpp b/Ref/TypeDemo/TypeDemo.cpp new file mode 100644 index 0000000000..3362a6f58b --- /dev/null +++ b/Ref/TypeDemo/TypeDemo.cpp @@ -0,0 +1,126 @@ +// ====================================================================== +// \title TypeDemo.cpp +// \author mstarch +// \brief cpp file for TypeDemo component implementation class +// ====================================================================== + +#include +#include +#include + +namespace Ref { + +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +TypeDemo ::TypeDemo(const char* const compName) : TypeDemoComponentBase(compName) {} + +void TypeDemo ::init(const NATIVE_INT_TYPE instance) { + TypeDemoComponentBase::init(instance); +} + +// ---------------------------------------------------------------------- +// Command handler implementations +// ---------------------------------------------------------------------- + +void TypeDemo ::CHOICE_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, Ref::Choice choice) { + this->tlmWrite_ChoiceCh(choice); + this->log_ACTIVITY_HI_ChoiceEv(choice); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::CHOICES_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, Ref::ManyChoices choices) { + this->tlmWrite_ChoicesCh(choices); + this->log_ACTIVITY_HI_ChoicesEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::CHOICES_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, + const U32 cmdSeq, + U8 repeat, + Ref::ManyChoices choices, + U8 repeat_max) { + for (U32 i = 0; (i < repeat) && (i < std::numeric_limits::max()) && (i < repeat_max); i++) { + this->tlmWrite_ChoicesCh(choices); + } + this->log_ACTIVITY_HI_ChoicesEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::EXTRA_CHOICES_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, Ref::TooManyChoices choices) { + this->tlmWrite_ExtraChoicesCh(choices); + this->log_ACTIVITY_HI_ExtraChoicesEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::EXTRA_CHOICES_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, + const U32 cmdSeq, + U8 repeat, + Ref::TooManyChoices choices, + U8 repeat_max) { + for (U32 i = 0; (i < repeat) && (i < std::numeric_limits::max()) && (i < repeat_max); i++) { + this->tlmWrite_ExtraChoicesCh(choices); + } + this->log_ACTIVITY_HI_ExtraChoicesEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::CHOICE_PAIR_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, Ref::ChoicePair choices) { + this->tlmWrite_ChoicePairCh(choices); + this->log_ACTIVITY_HI_ChoicePairEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::CHOICE_PAIR_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, + const U32 cmdSeq, + U8 repeat, + Ref::ChoicePair choices, + U8 repeat_max) { + for (U32 i = 0; (i < repeat) && (i < std::numeric_limits::max()) && (i < repeat_max); i++) { + this->tlmWrite_ChoicePairCh(choices); + } + this->log_ACTIVITY_HI_ChoicePairEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::GLUTTON_OF_CHOICE_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq, Ref::ChoiceSlurry choices) { + this->tlmWrite_ChoiceSlurryCh(choices); + this->log_ACTIVITY_HI_ChoiceSlurryEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::GLUTTON_OF_CHOICE_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, + const U32 cmdSeq, + U8 repeat, + Ref::ChoiceSlurry choices, + U8 repeat_max) { + for (U32 i = 0; (i < repeat) && (i < std::numeric_limits::max()) && (i < repeat_max); i++) { + this->tlmWrite_ChoiceSlurryCh(choices); + } + this->log_ACTIVITY_HI_ChoiceSlurryEv(choices); + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +void TypeDemo ::DUMP_TYPED_PARAMETERS_cmdHandler(const FwOpcodeType opCode, const U32 cmdSeq) { + Fw::ParamValid validity; + + Ref::Choice choice = this->paramGet_CHOICE_PRM(validity); + this->log_ACTIVITY_HI_ChoicePrmEv(choice, validity); + + Ref::ManyChoices choices = this->paramGet_CHOICES_PRM(validity); + this->log_ACTIVITY_HI_ChoicesPrmEv(choices, validity); + + Ref::TooManyChoices tooManyChoices = this->paramGet_EXTRA_CHOICES_PRM(validity); + this->log_ACTIVITY_HI_ExtraChoicesPrmEv(tooManyChoices, validity); + + Ref::ChoicePair choicePair = this->paramGet_CHOICE_PAIR_PRM(validity); + this->log_ACTIVITY_HI_ChoicePairPrmEv(choicePair, validity); + + Ref::ChoiceSlurry choiceSlurry = this->paramGet_GLUTTON_OF_CHOICE_PRM(validity); + this->log_ACTIVITY_HI_ChoiceSlurryPrmEv(choiceSlurry, validity); + + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} + +} // end namespace Ref diff --git a/Ref/TypeDemo/TypeDemo.fpp b/Ref/TypeDemo/TypeDemo.fpp new file mode 100644 index 0000000000..2c5a6b0c93 --- /dev/null +++ b/Ref/TypeDemo/TypeDemo.fpp @@ -0,0 +1,225 @@ +module Ref { + constant dimension = 2 + + @ Enumeration type for use later + enum Choice { + ONE + TWO + RED + BLUE + } + + @ Enumeration array + array ManyChoices = [dimension] Choice + + @ Array of array + array TooManyChoices = [dimension] ManyChoices + + @ Structure of enums + struct ChoicePair { + @ The first choice to make + firstChoice: Choice, + @ The second choice to make + secondChoice: Choice + } + + @ Structure of enums (with an multi-dimensional array and structure) + struct ChoiceSlurry { + @ A large set of disorganized choices + tooManyChoices: TooManyChoices, + @ A singular choice + separateChoice: Choice + @ A pair of choices + choicePair: ChoicePair + } + + @ Component to demonstrate multiple type configurations + passive component TypeDemo { + ##### + # Variations on a single enumeration input + ##### + @ Single choice command + sync command CHOICE( + @ A single choice + choice: Choice + ) + + @ Single choice channel + telemetry ChoiceCh: Choice + + @ Single choice event + event ChoiceEv(choice: Choice) severity activity high format "Choice: {}" + + @ Single enumeration parameter + param CHOICE_PRM: Choice + + ##### + # Variations on a one-dimensional array of enumeration input + ##### + @ Multiple choice command via Array + sync command CHOICES( + @ A set of choices + choices: ManyChoices + ) + + @ Multiple choice command via Array with a preceding and following argument + sync command CHOICES_WITH_FRIENDS( + @ Number of times to repeat the choices + repeat: U8, + @ A set of choices + choices: ManyChoices, + @ Limit to the number of repetitions + repeat_max: U8 + ) + + @ Multiple choice channel via Array + telemetry ChoicesCh: ManyChoices + + @ Multiple choice event via Array + event ChoicesEv(choices: ManyChoices) severity activity high format "Choices: {}" + + @ Multiple enumeration parameter via Array + param CHOICES_PRM: ManyChoices + + ##### + # Variations on a multi-dimensional array of enumeration input + ##### + @ Too many choice command via Array + sync command EXTRA_CHOICES( + @ Way to many choices to make + choices: TooManyChoices + ) + + @ Too many choices command via Array with a preceding and following argument + sync command EXTRA_CHOICES_WITH_FRIENDS( + @ Number of times to repeat the choices + repeat: U8, + @ Way to many choices to make + choices: TooManyChoices, + @ Limit to the number of repetitions + repeat_max: U8 + ) + + @ Too many choice channel via Array + telemetry ExtraChoicesCh: TooManyChoices + + @ Too many choice event via Array + event ExtraChoicesEv(choices: TooManyChoices) severity activity high format "Choices: {}" + + @ Too many enumeration parameter via Array + param EXTRA_CHOICES_PRM: ManyChoices + + ##### + # Variations on a basic structure + ##### + @ Multiple choice command via Structure + sync command CHOICE_PAIR( + @ A pair of choices + choices: ChoicePair + ) + + @ Multiple choices command via Structure with a preceding and following argument + sync command CHOICE_PAIR_WITH_FRIENDS( + @ Number of times to repeat the choices + repeat: U8, + @ A pair of choices + choices: ChoicePair, + @ Limit to the number of repetitions + repeat_max: U8 + ) + + @ Multiple choice channel via Structure + telemetry ChoicePairCh: ChoicePair + + @ Multiple choice event via Structure + event ChoicePairEv(choices: ChoicePair) severity activity high format "Choices: {}" + + @ Multiple enumeration parameter via Structure + param CHOICE_PAIR_PRM: ChoicePair + + ##### + # Variations on a complex structure + ##### + @ Multiple choice command via Complex Structure + sync command GLUTTON_OF_CHOICE( + @ A phenomenal amount of choice + choices: ChoiceSlurry + ) + + @ Multiple choices command via Complex Structure with a preceding and following argument + sync command GLUTTON_OF_CHOICE_WITH_FRIENDS( + @ Number of times to repeat the choices + repeat: U8, + @ A phenomenal amount of choice + choices: ChoiceSlurry, + @ Limit to the number of repetitions + repeat_max: U8 + ) + + @ Multiple choice channel via Complex Structure + telemetry ChoiceSlurryCh: ChoiceSlurry + + @ Multiple choice event via Complex Structure + event ChoiceSlurryEv(choices: ChoiceSlurry) severity activity high format "Choices: {}" + + @ Multiple enumeration parameter via Complex Structure + param GLUTTON_OF_CHOICE_PRM: ChoiceSlurry + + ##### + # Parameter control: events and a dump command + ##### + + @ Single choice parameter event + event ChoicePrmEv(choice: Choice, validity: Fw.ParamValid) severity activity high \ + format "CHOICE_PRM: {} with validity: {}" + + @ Multiple choice parameter event via Array + event ChoicesPrmEv(choices: ManyChoices, validity: Fw.ParamValid) severity activity high \ + format "CHOICES_PRM: {} with validity: {}" + + @ Too many choice parameter event via Array + event ExtraChoicesPrmEv(choices: TooManyChoices, validity: Fw.ParamValid) severity activity high \ + format "EXTRA_CHOICES_PRM: {} with validity: {}" + + @ Multiple choice parameter event via Structure + event ChoicePairPrmEv(choices: ChoicePair, validity: Fw.ParamValid) severity activity high \ + format "CHOICE_PAIR_PRM: {} with validity: {}" + + @ Multiple choice parameter event via Complex Structure + event ChoiceSlurryPrmEv(choices: ChoiceSlurry, validity: Fw.ParamValid) severity activity high \ + format "GLUTTON_OF_CHOICE_PRM: {} with validity: {}" + + @ Dump the typed parameters + sync command DUMP_TYPED_PARAMETERS() + + # ---------------------------------------------------------------------- + # Special ports + # ---------------------------------------------------------------------- + @ Time get port + time get port timeCaller + + @ Command registration port + command reg port cmdRegOut + + @ Command received port + command recv port cmdIn + + @ Command response port + command resp port cmdResponseOut + + @ Text event port + text event port logTextOut + + @ Event port + event port logOut + + @ Telemetry port + telemetry port tlmOut + + @ Parameter get + param get port prmGetOut + + @ Parameter set + param set port prmSetOut + } +} diff --git a/Ref/TypeDemo/TypeDemo.hpp b/Ref/TypeDemo/TypeDemo.hpp new file mode 100644 index 0000000000..23c251fde3 --- /dev/null +++ b/Ref/TypeDemo/TypeDemo.hpp @@ -0,0 +1,118 @@ +// ====================================================================== +// \title TypeDemo.hpp +// \author mstarch +// \brief hpp file for TypeDemo component implementation class +// ====================================================================== + +#ifndef TypeDemo_HPP +#define TypeDemo_HPP + +#include "Ref/TypeDemo/TypeDemoComponentAc.hpp" + +namespace Ref { + +class TypeDemo : public TypeDemoComponentBase { + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object TypeDemo + //! + TypeDemo(const char* const compName /*!< The component name*/ + ); + + //! Initialize object TypeDemo + //! + void init(const NATIVE_INT_TYPE instance = 0 /*!< The instance number*/ + ); + + //! Destroy object TypeDemo + //! + ~TypeDemo() = default; + + PRIVATE: + // ---------------------------------------------------------------------- + // Command handler implementations + // ---------------------------------------------------------------------- + + //! Implementation for CHOICE command handler + //! Single choice command + void CHOICE_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + Ref::Choice choice); + + //! Implementation for CHOICES command handler + //! Multiple choice command via Array + void CHOICES_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + Ref::ManyChoices choices); + + //! Implementation for CHOICES_WITH_FRIENDS command handler + //! Multiple choice command via Array with a preceding and following argument + void CHOICES_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + U8 repeat, + Ref::ManyChoices choices, + U8 repeat_max); + + //! Implementation for EXTRA_CHOICES command handler + //! Multiple choice command via Array + void EXTRA_CHOICES_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + Ref::TooManyChoices choices); + + //! Implementation for EXTRA_CHOICES_WITH_FRIENDS command handler + //! Too many choices command via Array with a preceding and following argument + void EXTRA_CHOICES_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + U8 repeat, + Ref::TooManyChoices choices, + U8 repeat_max); + //! Implementation for CHOICE_PAIR command handler + //! Multiple choice command via Structure + void CHOICE_PAIR_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + Ref::ChoicePair choices); + + //! Implementation for CHOICE_PAIR_WITH_FRIENDS command handler + //! Multiple choices command via Structure with a preceding and following argument + void CHOICE_PAIR_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + U8 repeat, + Ref::ChoicePair choices, + U8 repeat_max); + //! Implementation for GLUTTON_OF_CHOICE command handler + //! Multiple choice command via Complex Structure + void GLUTTON_OF_CHOICE_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + Ref::ChoiceSlurry choices /*!< + A phenomenal amount of choice + */ + ); + + //! Implementation for GLUTTON_OF_CHOICE_WITH_FRIENDS command handler + //! Multiple choices command via Complex Structure with a preceding and following argument + void GLUTTON_OF_CHOICE_WITH_FRIENDS_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq, /*!< The command sequence number*/ + U8 repeat, /*!< + Number of times to repeat the choices + */ + Ref::ChoiceSlurry choices, /*!< + A phenomenal amount of choice + */ + U8 repeat_max /*!< + Limit to the number of repetitions + */ + ); + + //! Implementation for DUMP_TYPED_PARAMETERS command handler + //! Dump the typed parameters + void DUMP_TYPED_PARAMETERS_cmdHandler(const FwOpcodeType opCode, /*!< The opcode*/ + const U32 cmdSeq /*!< The command sequence number*/ + ); +}; + +} // end namespace Ref + +#endif From 087bfb5673d0bd006940704288b0aa234446066e Mon Sep 17 00:00:00 2001 From: Andrei Tumbar Date: Fri, 31 Mar 2023 17:25:09 -0400 Subject: [PATCH 162/169] Recursively check for type imports (#1948) * Recursively check for type imports * Fix some Python formating * Make prm type checks for lax * More formatting --- Autocoders/Python/bin/codegen.py | 15 ----- .../fprime_ac/parsers/XmlComponentParser.py | 57 ++++++++++++++----- 2 files changed, 43 insertions(+), 29 deletions(-) diff --git a/Autocoders/Python/bin/codegen.py b/Autocoders/Python/bin/codegen.py index e426cc235c..1d24a95a98 100755 --- a/Autocoders/Python/bin/codegen.py +++ b/Autocoders/Python/bin/codegen.py @@ -502,13 +502,6 @@ def generate_component_instance_dictionary( xml_parser_obj = XmlSerializeParser.XmlSerializeParser( serializable_file ) # Telemetry/Params can only use generated serializable types - # check to make sure that the serializables don't have things that channels and parameters can't have - # can't have external non-xml members - if len(xml_parser_obj.get_include_header_files()): - PRINT.info( - f"ERROR: Component include serializables cannot use user-defined types. file: {serializable_file}" - ) - sys.exit(-1) # print xml_parser_obj.get_args() parsed_serializable_xml_list.append(xml_parser_obj) @@ -674,14 +667,6 @@ def generate_component( xml_parser_obj = XmlSerializeParser.XmlSerializeParser( serializable_file ) # Telemetry/Params can only use generated serializable types - # check to make sure that the serializables don't have things that channels and parameters can't have - # can't have external non-xml members - if len(xml_parser_obj.get_include_header_files()): - PRINT.info( - f"ERROR: Component include serializables cannot use user-defined types. file: {serializable_file}" - ) - sys.exit(-1) - # print xml_parser_obj.get_args() parsed_serializable_xml_list.append(xml_parser_obj) del xml_parser_obj diff --git a/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py b/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py index 66fcb1215e..f2b92d5ff5 100644 --- a/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py +++ b/Autocoders/Python/src/fprime_ac/parsers/XmlComponentParser.py @@ -95,8 +95,8 @@ def __init__(self, xml_file=None): else: self.__const_parser = None - xml_parser = etree.XMLParser(remove_comments=True) - element_tree = etree.parse(fd, parser=xml_parser) + self.__xml_parser = etree.XMLParser(remove_comments=True) + element_tree = etree.parse(fd, parser=self.__xml_parser) fd.close() # Close the file, which is only used for the parsing above # Validate against current schema. if more are imported later in the process, they will be reevaluated @@ -159,16 +159,14 @@ def __init__(self, xml_file=None): for comp_tag in component: if comp_tag.tag == "comment": self.__component.set_comment(comp_tag.text.strip()) - elif comp_tag.tag == "include_header": - self.__include_header_files.append(comp_tag.text) - elif comp_tag.tag == "import_port_type": - self.__import_port_type_files.append(comp_tag.text) - elif comp_tag.tag == "import_serializable_type": - self.__import_serializable_type_files.append(comp_tag.text) - elif comp_tag.tag == "import_enum_type": - self.__import_enum_type_files.append(comp_tag.text) - elif comp_tag.tag == "import_array_type": - self.__import_array_type_files.append(comp_tag.text) + elif comp_tag.tag in ( + "include_header", + "import_port_type", + "import_serializable_type", + "import_enum_type", + "import_array_type", + ): + self.__process_import_tag(comp_tag) elif comp_tag.tag == "import_dictionary": try: dict_file = locate_build_root(comp_tag.text) @@ -180,7 +178,7 @@ def __init__(self, xml_file=None): PRINT.info("Reading external dictionary %s" % dict_file) dict_fd = open(dict_file) _ = etree.XMLParser(remove_comments=True) - dict_element_tree = etree.parse(dict_fd, parser=xml_parser) + dict_element_tree = etree.parse(dict_fd, parser=self.__xml_parser) component.append(dict_element_tree.getroot()) @@ -848,7 +846,7 @@ def __init__(self, xml_file=None): else: PRINT.info( "%s: Invalid tag %s in parameter %s" - % (xml_file, comment.tag, n) + % (xml_file, parameter_tag.tag, n) ) sys.exit(-1) self.__parameters.append(parameter_obj) @@ -1129,6 +1127,37 @@ def __init__(self, xml_file=None): # PRINT.info("WARNING: Found namespace qualifier in port type definition (name=%s, type=%s) using namespace specified in XXXPortAi.xml file." % (n,t)) p.set_type(t.split("::")[-1]) + def __recursive_import_process(self, comp_tag): + try: + f = locate_build_root(comp_tag.text) + except (BuildRootMissingException, BuildRootCollisionException) as bre: + stri = "ERROR: Could not find specified dictionary XML file. {}. Error: {}".format( + comp_tag.text, str(bre) + ) + raise OSError(stri) + + fd = open(f) + _ = etree.XMLParser(remove_comments=True) + element_tree = etree.parse(fd, parser=self.__xml_parser) + + for child_tag in element_tree.getroot(): + self.__process_import_tag(child_tag) + + def __process_import_tag(self, comp_tag): + if comp_tag.tag == "include_header": + self.__include_header_files.append(comp_tag.text) + elif comp_tag.tag == "import_port_type": + self.__import_port_type_files.append(comp_tag.text) + self.__recursive_import_process(comp_tag) + elif comp_tag.tag == "import_serializable_type": + self.__import_serializable_type_files.append(comp_tag.text) + self.__recursive_import_process(comp_tag) + elif comp_tag.tag == "import_enum_type": + self.__import_enum_type_files.append(comp_tag.text) + elif comp_tag.tag == "import_array_type": + self.__import_array_type_files.append(comp_tag.text) + self.__recursive_import_process(comp_tag) + def __generate_port_from_role(self, role): special_ports = self.Config._ConfigManager__prop["special_ports"] From 1a7b1125d0ef9128f9f3926e0890993ad2ec32c9 Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 3 Apr 2023 09:30:30 -0700 Subject: [PATCH 163/169] Updating GDS version to include complex commanding (#1951) --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index f1e15f5102..6760075434 100644 --- a/requirements.txt +++ b/requirements.txt @@ -16,7 +16,7 @@ Flask==2.2.2 Flask-Compress==1.13 Flask-RESTful==0.3.9 fprime-fpp==1.2.0 -fprime-gds==3.1.5a3 +fprime-gds==3.1.5a4 fprime-tools==3.1.2a2 gcovr==5.2 idna==3.4 From fc19fc648578a3663b4c81fe9c07301560300f45 Mon Sep 17 00:00:00 2001 From: Rob Bocchino Date: Mon, 3 Apr 2023 09:33:24 -0700 Subject: [PATCH 164/169] Modernize C code in bsd_random (#1952) --- STest/STest/Random/bsd_random.c | 24 +++++++++++------------- STest/STest/Random/bsd_random.h | 2 +- 2 files changed, 12 insertions(+), 14 deletions(-) diff --git a/STest/STest/Random/bsd_random.c b/STest/STest/Random/bsd_random.c index 36add5f392..cdc15cafa6 100644 --- a/STest/STest/Random/bsd_random.c +++ b/STest/STest/Random/bsd_random.c @@ -190,8 +190,7 @@ static uint32_t *end_ptr = &randtbl[DEG_3 + 1]; static inline uint32_t good_rand(int32_t) __attribute__((always_inline)); -static inline uint32_t good_rand (x) - int32_t x; +static inline uint32_t good_rand (int32_t x) { /* * Compute x = (7^5 * x) mod (2^31 - 1) @@ -227,8 +226,7 @@ static inline uint32_t good_rand (x) * for default usage relies on values produced by this routine. */ void -bsd_srandom(x) - unsigned x; +bsd_srandom(unsigned x) { int i, lim; @@ -270,11 +268,11 @@ bsd_srandom(x) * complain about mis-alignment, but you should disregard these messages. */ char * -bsd_initstate(seed, arg_state, n) - unsigned seed; /* seed for R.N.G. */ - char *arg_state; /* pointer to state array */ - size_t n; /* # bytes of state info */ -{ +bsd_initstate( + unsigned seed, /* seed for R.N.G. */ + char *arg_state, /* pointer to state array */ + size_t n /* # bytes of state info */ +) { char *ostate = (char *)(&state[-1]); uint32_t *int_arg_state = (uint32_t *)arg_state; @@ -338,9 +336,9 @@ bsd_initstate(seed, arg_state, n) * complain about mis-alignment, but you should disregard these messages. */ char * -bsd_setstate(arg_state) - const char *arg_state; /* pointer to state array */ -{ +bsd_setstate( + const char *arg_state /* pointer to state array */ +) { uint32_t *new_state = (uint32_t *)arg_state; uint32_t type = new_state[0] % MAX_TYPES; uint32_t rear = new_state[0] / MAX_TYPES; @@ -391,7 +389,7 @@ bsd_setstate(arg_state) * Returns a 31-bit random number. */ long -bsd_random() +bsd_random(void) { uint32_t i; uint32_t *f, *r; diff --git a/STest/STest/Random/bsd_random.h b/STest/STest/Random/bsd_random.h index 1e72d82ece..f776aa5d09 100644 --- a/STest/STest/Random/bsd_random.h +++ b/STest/STest/Random/bsd_random.h @@ -21,4 +21,4 @@ char *bsd_initstate(unsigned seed, char *arg_state, size_t n); char *bsd_setstate(const char *arg_state); -long bsd_random(); +long bsd_random(void); From 7366c534474d743bdb865bbf0880ebb74474ce43 Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 3 Apr 2023 14:27:42 -0700 Subject: [PATCH 165/169] Add platform guard to CMake API (#1954) --- Drv/LinuxGpioDriver/CMakeLists.txt | 6 ++++-- Drv/LinuxI2cDriver/CMakeLists.txt | 6 ++++-- Drv/LinuxSpiDriver/CMakeLists.txt | 5 +++-- Drv/LinuxUartDriver/CMakeLists.txt | 17 +++++++---------- cmake/API.cmake | 22 ++++++++++++++++++++++ 5 files changed, 40 insertions(+), 16 deletions(-) diff --git a/Drv/LinuxGpioDriver/CMakeLists.txt b/Drv/LinuxGpioDriver/CMakeLists.txt index b20d3ed98d..d8d5692db5 100644 --- a/Drv/LinuxGpioDriver/CMakeLists.txt +++ b/Drv/LinuxGpioDriver/CMakeLists.txt @@ -5,6 +5,10 @@ # MOD_DEPS: (optional) module dependencies # #### +if (NOT FPRIME_USE_STUBBED_DRIVERS) + restrict_platforms(Linux) +endif() + if(FPRIME_USE_STUBBED_DRIVERS) set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/LinuxGpioDriver.fpp" @@ -19,8 +23,6 @@ elseif(${CMAKE_SYSTEM_NAME} STREQUAL "Linux") "${CMAKE_CURRENT_LIST_DIR}/LinuxGpioDriverComponentImpl.cpp" ) register_fprime_module() -else() - message(STATUS "Cannot use ${CMAKE_CURRENT_LIST_DIR} with platform ${CMAKE_SYSTEM_NAME}. Skipping.") endif() diff --git a/Drv/LinuxI2cDriver/CMakeLists.txt b/Drv/LinuxI2cDriver/CMakeLists.txt index eabb7ac694..43a4fff46f 100644 --- a/Drv/LinuxI2cDriver/CMakeLists.txt +++ b/Drv/LinuxI2cDriver/CMakeLists.txt @@ -5,6 +5,10 @@ # MOD_DEPS: (optional) module dependencies # #### +if (NOT FPRIME_USE_STUBBED_DRIVERS) + restrict_platforms(Linux) +endif() + if(FPRIME_USE_STUBBED_DRIVERS) add_definitions(-DSTUBBED_LINUX_I2C_DRIVER) set(SOURCE_FILES @@ -18,8 +22,6 @@ elseif(${CMAKE_SYSTEM_NAME} STREQUAL "Linux") "${CMAKE_CURRENT_LIST_DIR}/LinuxI2cDriver.cpp" ) register_fprime_module() -else() - message(STATUS "Cannot use ${CMAKE_CURRENT_LIST_DIR} with platform ${CMAKE_SYSTEM_NAME}. Skipping.") endif() diff --git a/Drv/LinuxSpiDriver/CMakeLists.txt b/Drv/LinuxSpiDriver/CMakeLists.txt index 10419ba038..8de2c478bf 100644 --- a/Drv/LinuxSpiDriver/CMakeLists.txt +++ b/Drv/LinuxSpiDriver/CMakeLists.txt @@ -5,6 +5,9 @@ # MOD_DEPS: (optional) module dependencies # #### +if (NOT FPRIME_USE_STUBBED_DRIVERS) + restrict_platforms(Linux) +endif() if(FPRIME_USE_STUBBED_DRIVERS) set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/LinuxSpiDriver.fpp" @@ -19,7 +22,5 @@ elseif(${CMAKE_SYSTEM_NAME} STREQUAL "Linux") "${CMAKE_CURRENT_LIST_DIR}/LinuxSpiDriverComponentImpl.cpp" ) register_fprime_module() -else() - message(STATUS "Cannot use ${CMAKE_CURRENT_LIST_DIR} with platform ${CMAKE_SYSTEM_NAME}. Skipping.") endif() diff --git a/Drv/LinuxUartDriver/CMakeLists.txt b/Drv/LinuxUartDriver/CMakeLists.txt index 0bc47509cc..8212f62a5a 100644 --- a/Drv/LinuxUartDriver/CMakeLists.txt +++ b/Drv/LinuxUartDriver/CMakeLists.txt @@ -5,14 +5,11 @@ # MOD_DEPS: (optional) module dependencies # #### -set(MOD_DEPS Os) +restrict_platforms(Linux Darwin) -if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux" OR ${CMAKE_SYSTEM_NAME} STREQUAL "Darwin") - set(SOURCE_FILES - "${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver.fpp" - "${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver.cpp" - ) - register_fprime_module() -else() - message(STATUS "Cannot use ${CMAKE_CURRENT_LIST_DIR} with platform ${CMAKE_SYSTEM_NAME}. Skipping.") -endif() +set(MOD_DEPS Os) +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver.fpp" + "${CMAKE_CURRENT_LIST_DIR}/LinuxUartDriver.cpp" +) +register_fprime_module() diff --git a/cmake/API.cmake b/cmake/API.cmake index fb94f9f081..9bf7a33d25 100644 --- a/cmake/API.cmake +++ b/cmake/API.cmake @@ -14,6 +14,28 @@ set(FPRIME_TARGET_LIST "" CACHE INTERNAL "FPRIME_TARGET_LIST: custom fprime targets" FORCE) set(FPRIME_UT_TARGET_LIST "" CACHE INTERNAL "FPRIME_UT_TARGET_LIST: custom fprime targets" FORCE) set(FPRIME_AUTOCODER_TARGET_LIST "" CACHE INTERNAL "FPRIME_AUTOCODER_TARGET_LIST: custom fprime targets" FORCE) + +#### +# Macro `restrict_platforms`: +# +# Restricts a CMakeLists.txt file to a given list of platforms. This prevents usage on platforms for which the module +# is incapable of being used and replaces the historical pattern of an if-tree detecting unsupported platforms. +# +# Usage: +# restrict_platforms(Linux Darwin) # Restricts to Linux and Darwin platforms +# +# Args: +# ARGN: list of platforms that are supported +##### +macro(restrict_platforms) + set(__CHECKER ${ARGN}) + if (NOT CMAKE_SYSTEM_NAME IN_LIST __CHECKER) + get_module_name("${CMAKE_CURRENT_LIST_DIR}") + message(STATUS "Platform ${CMAKE_SYSTEM_NAME} not supported for module ${MODULE_NAME}") + return() + endif() +endmacro() + #### # Function `add_fprime_subdirectory`: # From 124b6e817083fdfb765b1af266fcc0a9503f489f Mon Sep 17 00:00:00 2001 From: M Starch Date: Tue, 18 Apr 2023 17:37:41 -0700 Subject: [PATCH 166/169] Tutorial/getting started (#1968) * Revising the getting started tutorial to cover getting started * Adding a generate step * Additional generate note * Clarifying the directory for running commands * Adding actual output to New Project * Updating HelloWorld.md with tool output * Toushing up Deployments.md * sp * Fixing spacing * Removing prereqs * Update Tutorial.md to move next link --- RPI/README.md | 2 +- Ref/README.md | 2 +- docs/Tutorials/GettingStarted/Tutorial.md | 260 ---------------------- docs/Tutorials/GpsTutorial/Tutorial.md | 4 +- docs/Tutorials/HelloWorld/Deployments.md | 179 +++++++++++++++ docs/Tutorials/HelloWorld/HelloWorld.md | 189 ++++++++++++++++ docs/Tutorials/HelloWorld/NewProject.md | 77 +++++++ docs/Tutorials/HelloWorld/Tutorial.md | 78 +++++++ docs/Tutorials/README.md | 20 +- 9 files changed, 539 insertions(+), 272 deletions(-) delete mode 100644 docs/Tutorials/GettingStarted/Tutorial.md create mode 100644 docs/Tutorials/HelloWorld/Deployments.md create mode 100644 docs/Tutorials/HelloWorld/HelloWorld.md create mode 100644 docs/Tutorials/HelloWorld/NewProject.md create mode 100644 docs/Tutorials/HelloWorld/Tutorial.md diff --git a/RPI/README.md b/RPI/README.md index 69053f62f4..48fdac77f0 100644 --- a/RPI/README.md +++ b/RPI/README.md @@ -52,7 +52,7 @@ sudo apt update && sudo apt install -y gcc-arm-linux-gnueabihf g++-arm-linux-gnu **Crosscompiling using CMake:** -The following commands are described at length in the getting started [tutorial](../docs/Tutorials/GettingStarted/Tutorial.md). These commands will +The following commands are described at length in the getting started [tutorial](../docs/Tutorials/HelloWorld/Tutorial.md). These commands will go to the RPI directory and generate a build directory for the RPI example. This step generates a CMake Cache, sets the toolchain use to build the code and does an initial scan of the source tree. Since the RPI example sets a default F´ toolchain file in its CMakeLists.txt, we do not need to supply one on the command line when generating the build. This only needs to be done once to prepare for the build because CMake will detect diff --git a/Ref/README.md b/Ref/README.md index e7b04ccc39..3760603d1e 100644 --- a/Ref/README.md +++ b/Ref/README.md @@ -63,7 +63,7 @@ cd fprime/Ref/build-artifacts//bin/ - The F´ utility's build command can build individual components too. - The 'generate' command can take a toolchain argument for quickly generating a cross-compile `fprime-util generate raspberrypi` for example. -Further work with the F´ utility can be found in the [Getting Started](../docs/Tutorials/GettingStarted/Tutorial.md) tutorial. Other tutorials +Further work with the F´ utility can be found in the [Getting Started](../docs/Tutorials/HelloWorld/Tutorial.md) tutorial. Other tutorials for many aspects of F´ are available [here](../docs/Tutorials/README.md). diff --git a/docs/Tutorials/GettingStarted/Tutorial.md b/docs/Tutorials/GettingStarted/Tutorial.md deleted file mode 100644 index 7712b1db39..0000000000 --- a/docs/Tutorials/GettingStarted/Tutorial.md +++ /dev/null @@ -1,260 +0,0 @@ -# Getting Started with F´ - -Prerequisites: [INSTALL.md](../../INSTALL.md) - -This tutorial will walk the user through the basic usage of the F´ development suite. This assumes that the user has run -through the above installation guide, and has a working F´ installation. - -The goal of this Tutorial is to build familiarity with the F´environment and tools. It does not walk the user through -creation of new F´ items, but rather use the existing F´ `Ref` example as a place to operate the tools, learn the -environment, and learn F´. - -The full development process is covered in the [Math Component Tutorial](../MathComponent/Tutorial.md), which will build -on the knowledge learned here. - -## Tutorial Goals - -The goal of this tutorial is to demonstrate the F´ tool suite as it applies to the F´ development process. Users will -first gain some understanding of F´ terminology followed by the F´ development process. Then they will use the tools to -walk the F´ development process steps against existing reference goals. - -## F´ Terminology - -This section will cover basic terminology used in this and other tutorials with respect to F´. It may be used as a -reference for keywords that have specific meaning in an F´ project. - -**Port:** a port represents a connection between *Components*. These act as communication channels in F´. This allows -*Components* to interact with each other. A set of *Ports* acts as a defined interface to a *Component*. - -**Component:** the location of program behavior. Components execute the software logic of the system and typically -define an interface of *Ports* that act allow them to interact with other *Components*. Components additionally -may define *Commands*, *Events*, *Channels*, and *Parameters*, which define standard data patterns in F´. - -**Topology**: a topology represents the full F´ system. It is a set of *Components* and the connections between those -*Components*. The *Topology* specifies the full system and all the communication channels. - -**Event:** an event, also known as an EVR, is a type of downlinked data that represents a single event in the system. -An event is composed of a name, format string, and set of arguments that described what happened. Events represent a -history of the system. Events are defined per-*component*. - -**Channel:** a channel, also known as a telemetry item, is a single value read and downlinked. Channels consist of -a type, a format specifier, and a value. Channels represent the current system state. Channels are defined per-*component*. - -**Command:** a command is uplinked data items that instruct the system to perform an action. *Commands* consist of an -opcode, a mnemonic, and a list of arguments to the command. Commands are defined per-*component*. - -**Deployment:** a deployment is a single instance of F´. Although a single F´ project can use/define multiple -deployments, a deployment represents one build/executable. - -**Build Directory/Build Cache:** this directory, created by the `fprime-util` described below, is required to build -CMake projects. It stores all by-products, generated code, and build products from an F´ build. - -**Ground System:** the computer system running to collect the data from the running F´ deployment. There is a basic -ground system supplied with F´ for development purposes. - -**Toolchain:** a set of build tools to build for a specific architecture. i.e. the "raspberrypi" toolchain will build F´ -deployments for the arm/Linux architecture of the raspberry pi. - -## F´ Development Process - -F´ development typically starts with creating new Ports and Components as these can be built and tested as units and -then the full F´ system deployment topology can be assembled for integrated systems testing and release/operations. This -can be done iteratively by creating a few Components then integrating them into the system topology and then repeating -with the next most critical components. - -F´ development is a design-first approach. To start, a developer should design any unique ports that the Component will -need. If desired, the port can be built and compiled to ensure that the design is correct. Since the port will be -entirely auto-generated, developers usually refrain from unit testing the port and defer unit testing to the Component. - -Next, developers design components. Components are designed by specifying the ports that represent the Component's -interface and the Commands, Events and Channels that the Component handles. This tutorial focuses on the tool suite, so -the design is already in-place. Users can see the design by inspecting Components in the `Ref` directory. Creation of -new components from design through test is demonstrated in the [Math Component Tutorial](../MathComponent/Tutorial.md). - -The next step for developing a Component is to implement the code. To do this, one can generate template stubs to fill -with the developer's stubs. To do this, a user runs the F´ tool suite to generate these stubs. Then implements, builds, -and tests from there. Unit test template stubs are generated in the same way and should test-driven development be -preferred, these test stubs could be generated and implemented before the Component's code. - -Finally, the Component is integrated into the deployment and the entire deployment may be built and installed. - -This tutorial will walk developers through generating the templates, building example Components, and -building/installing the full deployment. It will use the `Ref` application as an example for this. - -## Working the F´ Development Process with `fprime-util` - -In order to ease in development, the F´ team has created a small wrapper for the CMake build system. This will recover the -advantages of previous F´ development patterns, while allowing for the power and configurability of CMake as an underlying -build tool. - -### Build Cache Generation - -In order to run CMake, a build cache needs to be generated. This is typically done once for each platform the user wishes -to compile against. It is usually done right after F´ is checked-out and repeated for each platform as they are added. It -is a setup step and isn't formally part of the F´ development process. - -To run this tool, the developer will use the `generate` subcommand. It takes one optional argument: the toolchain file -used in CMake to compile for a specific platform. If not supplied, the `native` toolchain will be used and F´ will be -set up to run on the current platform (typically Mac OS, or Linux depending on the developer's chosen OS). - -**Generate the Ref Application for Native Compilation** - -To generate a native build, follow the commands shown below. It is assumed that the user has checked out the fprime repository -and is performing commands relative to the location of that checkout. - -``` -cd fprime/Ref -fprime-util generate -``` - -Here the utility will create two standard builds: one for the standard build, and one for the unit test build. This will enable -the user to take advantage of all parts of F´ without generating their own CMake build caches. **Note:** should a developer -be developing or improving F´ provided infrastructure components, then the `generate` command should be run in the F´ -root directory. However, most developers do not need this functionality. - -**Generate Cross-Compile of the Ref Application for Raspberry PI Platform** - -Most developers wish to run F´ on embedded hardware. This is done by generating a cross-compile using a different CMake -toolchain by providing the toolchain argument. The above invocations assume the default "native" toolchain. - -Here, the "raspberrypi" toolchain supplied by F´ is used. This will generate a cross-compile for the raspberry pi -architecture. The user should ensure to follow the Raspberry PI setup steps found at: [RPI](https://github.com/nasa/fprime/blob/master/RPI/README.md) -``` -cd fprime/Ref -fprime-util generate raspberrypi -``` - -## Creating Implementation Stubs - -Once the build system cache is generated, developers will need to generate the stubbed implementations of a Component's C++ -files. This can be done using the `impl` command of the F´ utility. These commands assume a default build has been generated. -Typically passing in a toolchain is unnecessary as these templates are platform agnostic. - -**Generating Implementation Stubs of SignalGen** -``` -cd fprime/Ref/SignalGen -fprime-util impl -``` - -This creates two files for the component. These are `Impl.cpp-template` and `Impl.hpp-template`. -The user can then rename these files to remove `-template`. The file is then ready for C++ development. By generating -`-template` files, we won't accidentally overwrite any existing implementation should the developer need to repeat this -step. - -## Creating Unit Test Implementations - -Once the build system cache is generated, developers will need to generate the stubbed implementations for creating -unit tests for a Component's C++. This can be done using the `impl --ut` command of the F´ utility. These commands -assume a default build has been generated. They can be run passing in a toolchain, but this is typically not done because -they are toolchain agnostic. - -**Generating Unit Test Stubs of SignalGen** -``` -cd fprime/Ref/SignalGen -fprime-util impl --ut -``` - -This creates the following files, which are typically moved to a subfolder called `test/ut`. The files created are -placed in the current directory and named: -``` -Tester.cpp -Tester.hpp -GTestBase.cpp -GTestBase.hpp -TesterBase.cpp -TesterBase.hpp -TestMain.cpp -``` - -### Building Components and Deployments - -Once a developer has implemented a component, it is time to build that component and test that component. In order to build -a component, the `build` subcommand needs to be run. This will build the "current directory" that the developer is in. -That means that should the user change into a deployment directory then the build command will build the full deployment. -Should the user desire to build a component, navigate into the Component's directory and run the build command. - -**Build SignalGen Component** -``` -cd fprime/Ref/SignalGen -fprime-util build -``` - -The user can also build a deployment by navigating to the deployment directory and running the `build` command. The build -command also copies the binary to the deployments "bin" directory, i.e. `fprime/Ref/bin`. This is shown below: - -**Build Ref Deployment** -``` -cd fprime/Ref -fprime-util build -``` - -This process also built the Dictionaries for the project and places the dictionary in the "Top" folder of the deployment. -This happens any time the "build" command is run on a deployment. - -The user can also build a component or deployment for a cross-compile by specifying the toolchain. A previous generate -for that toolchain should have been run. These steps require the setup described here: -[RPI](https://github.com/nasa/fprime/blob/master/RPI/README.md) - -``` -cd fprime/Ref/SignalGen -fprime-util build raspberrypi -cd fprime/Ref -fprime-util build raspberrypi -``` - -**Running the Binary Assuming Linux** -``` -cd fprime/Ref -fprime-util build -./build-artifacts/Linux/bin/Ref # Run the deployment -CTRL-C # Exit the application -``` -Running the application as part of the development ground data system is shown below. - -The user can also install a cross-compile. -``` -cd fprime/Ref -fprime-util build raspberrypi -``` - -## Building and Running Unit Tests - -Unit tests can be built using the `build --ut` command of the `fprime-util`. This will allow us to build the unit tests -in preparation to run them. The user can also just run `check` to build and run the unit tests. - -Before building unit tests, the unit test build cache must be generated: - -``` -cd fprime/Ref -fprime-util generate --ut -``` - -**Building Unit Test of SignalGen** -``` -cd fprime/Ref/SignalGen -fprime-util build --ut -``` - -Once built, the unit test can be run using the following command. **Note: this will produce a message warning of no -tests run because SigGen has no unit tests defined.** -``` -cd fprime/Ref/SignalGen -fprime-util check -``` -The user can also build the unit test, but must copy it to the hardware and run it here. This can be done with a cross- -compile by running the following commands. - -**Cross-Compile Unit Test of SignalGen** -``` -cd fprime/Ref/SignalGen -fprime-util build raspberrypi --ut -``` - -## Conclusion - -The user should now be familiar with F´ terminology and with the `fprime-util` tool used to build and develop F´ -applications. The next step is to follow the full `MathComponent` tutorial to create new *Ports*, *Components*, and -*Topologies*. This will walk the user through the entire development process, using the tool commands we learned here. - -**Next:** [Math Component Tutorial](../MathComponent/Tutorial.md) -**Also See:** [GPS Component Tutorial](../GpsTutorial/Tutorial.md) for a cross-compiling tutorial. \ No newline at end of file diff --git a/docs/Tutorials/GpsTutorial/Tutorial.md b/docs/Tutorials/GpsTutorial/Tutorial.md index ff434a0eb9..efd50bdf52 100644 --- a/docs/Tutorials/GpsTutorial/Tutorial.md +++ b/docs/Tutorials/GpsTutorial/Tutorial.md @@ -22,7 +22,7 @@ for use as a demo or to help debug issues that come up when going through the tu ## Prerequisites -This tutorial assumes the user has gone through and understood [Getting Started Tutorial](../GettingStarted/Tutorial.md) +This tutorial assumes the user has gone through and understood [Getting Started Tutorial](../HelloWorld/Tutorial.md) and [MathComponent Tutorial](../MathComponent/Tutorial.md) This tutorial requires the user to have some basic software skills and have installed F´. The prerequisite skills to @@ -35,7 +35,7 @@ understand this tutorial are as follows: Installation can be done by following the installation guide found at: [INSTALL.md](../../INSTALL.md). This guide will walk the user through the installation process and verify the installation. In addition, users may wish to -follow the [Getting Started Tutorial](../GettingStarted/Tutorial.md) in order to get a feel for the F´ environment and +follow the [Getting Started Tutorial](../HelloWorld/Tutorial.md) in order to get a feel for the F´ environment and tools. ## Creating a Custom F´ Component diff --git a/docs/Tutorials/HelloWorld/Deployments.md b/docs/Tutorials/HelloWorld/Deployments.md new file mode 100644 index 0000000000..b3193d53e7 --- /dev/null +++ b/docs/Tutorials/HelloWorld/Deployments.md @@ -0,0 +1,179 @@ +# Getting Started: Integration and Testing With F´ Deployments + +This section will walk new users through creating a new F´ [deployment](./Tutorial.md#deployment). This deployment will +build a [topology](./Tutorial.md#topology) containing the standard F´ stack of components and a single `HelloWorld` +component instance. The `HelloWorld` was created in the [last section](./HelloWorld.md). The tutorial will close by +testing the deployment and `HelloWorld` component through the `fprime-gds`. + +### Prerequisites: +- [Getting Started: F´ Hello World Component](./HelloWorld.md) + +### Tutorial Steps: +- [Creating A New Deployment](#creating-a-new-deployment) +- [Adding The Hello World Component](#adding-the-hello-world-component) +- [Testing With `fprime-gds`](#testing-with-fprime-gds) +- [Conclusion](#conclusion) + +## Creating A New Deployment + +F´ deployments represent one flight software executable. All the components we develop for F´ run within a deployment. +The deployment created here will contain the standard command and data handling stack. This stack enables +ground control and data collection of the deployment. + +To create a deployment, run the following commands: +```bash +cd MyProject +fprime-util new --deployment +``` +This command will ask for some input. Respond with the following answers: + +``` +deployment_name [MyDeployment]: MyDeployment +path_to_fprime [./fprime]: +author_name []: LeStarch +``` + +> For any other questions, select the default response. + +At this point, the `MyDeployment` has been created, but our `HelloWorld` component has not been added. + +## Adding The Hello World Component + +First, the project's components should be added to this deployment's build. This can be done by adding the following +to `MyDeployment/CMakeLists.txt`. + +```cmake +... +### +# Components and Topology +### +include("${FPRIME_PROJECT_ROOT}/project.cmake") +... +``` + +In this section the `HelloWorld` component will be added to the `MyDeployment` deployment. This can be done by adding +the component to the topology defined in `MyDeployment/Top`. + +Topologies instantiate all the components in a running system and link them together. For some port types, like the +commanding, event, and telemetry ports used by `HelloWorld`, the connections are made automatically. In addition, the +topology specifies how to construct the component instance. This is also done automatically unless the component has +specific configuration. + +In order to add a component to the topology, it must be added to the topology model. An instance definition and an +instance initializer must both be added. + +To add an instance definition, add `instance helloWorld` to the instance definition list in the `topology Ref` section +of `MyDeployment/Top/topology.fpp`. This is shown below. + +``` +... + topology Ref { + # ---------------------------------------------------------------------- + # Instances used in the topology + # ---------------------------------------------------------------------- + + instance ... + instance ... + instance helloWorld +``` +> Be careful to not remove any other instances from the list. + +`helloWorld` is the name of the component instance. Like variable names, component instance names should be descriptive +and are typically named in camel or snake case. + +Next, an instance initializer must be added to topology instances defined in `MyDeploymment/Top/instances.fpp` file. +Since the `HelloWorld` component is an `active` component it should be added to the active components section and should +define a priority and queue depth options. This is shown below. + +``` +... + # ---------------------------------------------------------------------- + # Active component instances + # ---------------------------------------------------------------------- + instance ... + ... + ... + ... + + instance ... + + instance helloWorld: MyComponents.HelloWorld base id 0x0F00 \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ + priority 50 +``` +> The user must ensure that the base id (0x0F00) does not conflict with any other base ids in the topology. 0x0F00 +> should be safe for deployments created with `fprime-util new --deployment`. + +> Make sure to use the same instance name (i.e. helloWorld) as defined in the instance definition just added to +> `topology.fpp`. + +Finally, our new telemetry channel should be added to our telemetry packet specification. For this tutorial the +channel can be ignored as the deployment will not use the telemetry packetizer. Add the following to the `ignore` +section of `MyDeployment/Top/MyDeploymentPackets.xml`. + +``` + + ... + + +``` + +Since this component has no custom ports nor does it require special configuration, our addition to the topology is +completed. The deployment can now be set up and built using the following commands: + +``` +cd MyDeployment +fprime-util generate +fprime-util build -j4 +``` +Resolve any errors that occur before continuing to the testing section. + +> Notice `fprime-util generate` was used again. This is because this new deployment builds in a separate environment. + +## Testing With `fprime-gds` + +It is now time to test the `HelloWorld` component by running the deployment created in this section. This can be +accomplished by running the `fprime-gds` command in the deployment, verifying connection, sending the new SEND_HELLO +command and verifying that the `Hello` event and `GreetingCount` channel appears. + +To start the deployment with default settings, run: +```bash +fprime-gds +``` + +The F´ GDS control page should open up in your web browser. If it does not open up, navigate to `http://127.0.0.1:5000`. + +Once the F´ GDS page is visible, look for a green circle icon in the upper right corner. This shows that the flight +software deployment has connected to the GDS system. If a red X appears instead, navigate to the Logs tab and look for +errors in the various logs. + +Now that communication is verified, navigate to the "Commanding" tab and select `helloWorld.SAY_HELLO` from the +dropdown list. Type a greeting into the argument input box and click the button "Send Command". If the argument has +validated successfully the command will send. Resolve all errors and ensure the command has sent. + +> Notice commands are instance specific. Had several HelloWorld component instances been used, there would be multiple +> `SAY_HELLO` listings, one for each component instance. + +Now that the command has sent, navigate to the "Events" tab. Ensure that the event list contains the Hello event with +the text entered when sending the command. + +Lastly, navigate to the "Channels" tab. Look for "helloWorld.GreetingCount" in the channel list. Ensure it has recorded +the number of times a `helloWorld.SAY_HELLO` was sent. + +Congratulations, you have now set up a project, component, and deployment in F´. + +## Conclusion + +This concludes both the adding deployment section of the Getting Started tutorial and the tutorial itself. The user has +been able to perform the following actions: + +1. Create a new blank F´ projects +2. Create a new F´ components +3. Create a new F´ deployments and add components it + +To explore components more in-depth and see how components communicate with one another, see the +[Math Component Tutorial](../MathComponent/Tutorial.md). + +**Next:** [Math Component Tutorial](../MathComponent/Tutorial.md) + diff --git a/docs/Tutorials/HelloWorld/HelloWorld.md b/docs/Tutorials/HelloWorld/HelloWorld.md new file mode 100644 index 0000000000..527d08413e --- /dev/null +++ b/docs/Tutorials/HelloWorld/HelloWorld.md @@ -0,0 +1,189 @@ +# Getting Started: Creating an F´ Hello World Component + +This tutorial will walk new users through creating a basic F´ component. Users should have completed the new project +tutorial and have the tools sourced as shown in the [conclusion](./NewProject.md#conclusion) portion of that tutorial. + +F´ components encapsulate the various parts of system behavior. These components can interact with the ground system +through [commands](Tutorial.md#command), [events](./Tutorial.md#event), and +[telemetry channels](./Tutorial.md#telemetry-channel). Components communicate with other components through +[ports](./Tutorial.md#port), which covered in-depth in [another tutorial](../MathComponent/Tutorial.md). + +### Prerequisites: +- [Getting Started: Creating an F´ Project](./NewProject.md) + +### Tutorial Steps: +- [Hello World Component](#hello-world-component-requirements) +- [Creating the Hello World Component](#creating-the-hello-world-component) +- [Editing the Component Model](#editing-the-component-model) +- [Implementing Component Behavior](#implementing-component-behavior) +- [Conclusion](#conclusion) + +## Hello World Component Requirements + +The first step for creating a new component is understanding what it is that we wish to implement. This is called +defining requirements. In the spirit of "Hello World" this component will encapsulate greeting behavior. The component +will define three items to implement greeting behaviour: + +1. A [command](./Tutorial.md#command) called `SAY_HELLO` that will command the component to send a greeting +2. An [event](./Tutorial.md#event) called `Hello` that is the greeting sent in response to the `SAY_HELLO` command +3. A [telemetry channel](./Tutorial.md#telemetry-channel) called `GreetingCount` that will count each `Hello` event sent + +These are a simple set of requirements for this component. + +## Creating the Hello World Component + +The next step is to create the new component. First, create a directory called `MyComponents` to contain this project's +components and change into that directory. + +```bash +mkdir MyComponents +cd MyComponents +``` + +Creating a new component is accomplished with the following command: + +```bash +fprime-util new --component +``` +This command will ask for some input. You should respond with the following answers: + +``` +[INFO] Cookiecutter source: using builtin +component_name [MyComponent]: HelloWorld +component_short_description [Example Component for F Prime FSW framework.]: Hello World Tutorial Component +component_namespace [HelloWorld]: MyComponents +Select component_kind: +1 - active +2 - passive +3 - queued +Choose from 1, 2, 3 [1]: 1 +Select enable_commands: +1 - yes +2 - no +Choose from 1, 2 [1]: 1 +Select enable_telemetry: +1 - yes +2 - no +Choose from 1, 2 [1]: 1 +Select enable_events: +1 - yes +2 - no +Choose from 1, 2 [1]: 1 +Select enable_parameters: +1 - yes +2 - no +Choose from 1, 2 [1]: 2 +[INFO] Found CMake file at 'MyProject/project.cmake' +Add component MyComponents/HelloWorld to MyProject/project.cmake at end of file (yes/no)? yes +Generate implementation files (yes/no)? no +``` + +> For any other questions, select the default response. + +This will create a new component called "HelloWorld" in the "MyProject" namespace. This new component will be able to +define commands, events, and telemetry channels. + +We should navigate to the component's directory and look around: + +```bash +cd HelloWorld +ls +``` +This will show the following files: +1. `HelloWorld.fpp`: design model for the component +2. `HelloWorld.hpp` and `HelloWorld.cpp`: C++ implementation files for the component, currently empty. +3. `CMakeList.txt`: build definitions for the component. +4. `docs` folder to place component documentation + +To build this component run `fprime-util build` in the current folder. + +> Any component in F´ can be built by navigating to the component's folder and running `fprime-util build`. + +## Editing the Component Model + +A component model defines the interface of the component with the rest of the F´ system and with the ground system F´ +communicates with. In this case we intend to define a command, an event, and a telemetry channel as specified above. + +Open the model file `HelloWorld.fpp` and add replace the line + +`async command TODO opcode 0` + +with the following: + +``` +@ Command to issue greeting with maximum length of 20 characters +async command SAY_HELLO( + greeting: string size 20 @ Greeting to repeat in the Hello event +) + +@ Greeting event with maximum greeting length of 20 characters +event Hello( + greeting: string size 20 @ Greeting supplied from the SAY_HELLO command +) severity activity high format "I say: {}" + +@ A count of the number of greetings issued +telemetry GreetingCount: U32 +``` +> You should ensure to replace any existing command, event, and channel definitions with those supplied above but leave +> the 'Standard AC Ports' section untouched. + +With this step completed you can generate a basic implementation with the following command: + +```bash +fprime-util impl +``` + +This creates `HelloWorld.hpp-template` and `HelloWorld.cpp-template` files that contain our new fill-in template. While +normally one would merge new templates with the existing code, we will instead overwrite the existing implementations as +we have not edited those files yet. To do this: + +```bash +mv HelloWorld.hpp-template HelloWorld.hpp +mv HelloWorld.cpp-template HelloWorld.cpp +``` +We are now ready for implementing component behavior. + +## Implementing Component Behavior + +F´ behavior is implemented in two types of methods command handler functions to implement command behavior and handler +functions to implement port behavior (as described in the next tutorial). For this tutorial we need to implement the +`SAY_HELLO` command, so we need to edit the `SAY_HELLO_cmdHandler` function in the `HelloWorld.cpp` file. Ensure its +contents look like: + +```c++ +void HelloWorld:: SAY_HELLO_cmdHandler(FwOpcodeType opCode, U32 cmdSeq, const Fw::CmdStringArg& greeting) { + // Copy the command string input into an event string for the Hello event + Fw::LogStringArg eventGreeting(greeting.toChar()); + // Emit the Hello event with the copied string + this->log_ACTIVITY_HI_Hello(eventGreeting); + + this->tlmWrite_GreetingCount(++this->m_greetingCount); + + // Tell the fprime command system that we have completed the processing of the supplied command with OK status + this->cmdResponse_out(opCode, cmdSeq, Fw::CmdResponse::OK); +} +``` +> We must also add the m_greetingCount member variable to the class defined in `HelloWorld.hpp` and the constructor +> defined in `HelloWorld.cpp`. This looks like: +> +> **HelloWorld.hpp: Adding New Member Variable** +> ```c++ +> private: +> U32 m_greetingCount; +> ``` +> **HelloWorld.cpp: Updating Constructor** +> ```c++ +> HelloWorld:: HelloWorld() : +> m_greetingCount(0), +> HelloWorldComponentBase(compName) { +> ``` + +The component should build without errors by running `fprime-util build`. Resolve any errors that occur before +proceeding to the next section. + +## Conclusion + +This tutorial has walked through the creation of component that implements a "Hello World" style greeting behavior for +our F´ system. In the next tutorial, this component will be hooked-up to an F´ deployment and tested! + +**Next:** [Getting Started: Integration and Testing With F´ Deployments](./Deployments.md) diff --git a/docs/Tutorials/HelloWorld/NewProject.md b/docs/Tutorials/HelloWorld/NewProject.md new file mode 100644 index 0000000000..ba45857cd9 --- /dev/null +++ b/docs/Tutorials/HelloWorld/NewProject.md @@ -0,0 +1,77 @@ +# Getting Started: Creating an F´ Project + +This tutorial will walk new users through creating a new F´ project. + +### Tutorial Steps: +- [Bootstrapping F´](#bootstrapping-f) +- [Creating a New F´ Project](#creating-a-new-f-project) +- [Building the New F´ Project](#building-the-new-f-project) +- [Conclusion](#conclusion) + +## Bootstrapping F´ + +An F´ [project](./Tutorial.md#project) ties to a specific version of tools to work with F´. In order to create +this project and install the correct version of tools, an initial bootstrap version of F´ tools must be installed. This +is accomplished with the following command: + +```bash +pip install fprime-tools +``` + +## Creating a New F´ Project + +Now that to tools are installed a new F´ project should be created. An F´ project internalizes the version of F´ that +the project will build upon and provides the user the basic setup for creating, building, and testing components. + +In order to make a new project, run the following command and answer the questions as indicated below: + +```bash +fprime-util new --project +``` + +This command will ask for some input. Respond with the following answers: +``` +project_name [MyProject]: MyProject +fprime_branch_or_tag [devel]: devel +Select install_venv: +1 - yes +2 - no +Choose from 1, 2 [1]: 1 +``` + +Use the default for anything not specified. This command will take a moment to run. + +The above command creates a new F´ project structure in a folder called `MyProject`, use the `devel` branch of F´ as +the basis for the project, and set up the matching tools in a new Virtual Environment. + +> Experienced F´ users may note that we have not yet created a deployment, but rather just the base project structure. + +## Building the New F´ Project + +The next step is to set up and build the newly created project. This will serve as a build environment for any newly +created components, and will build the F´ framework supplied components. + +```bash +cd MyProject +fprime-util generate +fprime-util build -j4 +``` + +> `fprime-util generate` sets up the build environment for a project/deployment. It only needs to be done once. At the +> end of this tutorial, a new deployment will be created and `fprime-util generate` will also be used then. + +## Conclusion + +A new project has been created with the name `MyProject` and has been placed in a new folder called in `MyProject` in +the current directory. It includes the initial build system setup, and F´ version. It is still empty in that the user +will still need to create components and deployments. + +For the remainder of this Getting Started tutorial we should use the tools installed for our project and issue commands +within this new project's folder. Change into the project directory and load the newly install tools with: + +```bash +cd MyProject +. venv/bin/activate +``` + +**Next:** [Getting Started: Creating an F´ Hello World Component](./HelloWorld.md) diff --git a/docs/Tutorials/HelloWorld/Tutorial.md b/docs/Tutorials/HelloWorld/Tutorial.md new file mode 100644 index 0000000000..3c3f952a11 --- /dev/null +++ b/docs/Tutorials/HelloWorld/Tutorial.md @@ -0,0 +1,78 @@ +# Getting Started: Introduction and F´ Terminology + +The getting started tutorial is designed to teach new users the basics of F´ usage, instruct existing users on new +command that help in F´ development, and act as the canonical "Hello World" example for F´. + +This tutorial walks through the following steps: +1. [Creating an F´ Project](./NewProject.md) +2. [Creating an F´ Hello World Component](./HelloWorld.md) +3. [Integration and Testing With F´ Deployments](./Deployments.md) + +Once finished, users should have a good understanding of the basic development mechanics for working with F´ and then +could dive deeper into concepts through the [Math Component Tutorial](../MathComponent/Tutorial.md). + +## F´ Terminology + +F´ uses specific terminology to refer to specific parts of the system. This section dives into the basic F´ terminology +used in this tutorial and an explanation of how the terminology is used. + +#### Project + +An F´ project is a collection of files and folders used to work with F´. At its core, a project is just a folder that +can be used to hold F´ code. Projects should specifically exclude the core F´ library to avoid the "clone and own" +problem. Rather projects should link-to a version of F´. + +This tutorial will create a new `MyProject` project used to contain the other things created by the tutorial. + +#### Component + +An F´ component encapsulates a unit of system behavior. Components use ports to communicate with other components and +define commands, events, telemetry channels, and parameters. + +This tutorial will create a new `HelloWorld` component that defines a `SAY_HELLO` command, `Hello` event, and +`GreetingCount` telemetry channel. The component only used built-in ports. It does not use custom ports nor parameters. + +#### Port + +A port is an interface used to communicate between components. This tutorial only uses built-in ports. + +#### Command + +Commands represent actions that a component can execute. Commands can be sent from the ground or via command sequences. +Command behavior is defined in a command handler defined in the component's implementation. + +This tutorial defines one command `SAY_HELLO` with a single argument `greeting`. This command will be sent via the +ground system and will echo the greeting back via the `Hello` event. + +#### Event + +Events represent actions that a component has performed. Events are akin to software log messages. Events are received +and displayed by the ground system. + +This tutorial defines one event `Hello` emitted in response to the `SAY_HELLO` command and containing the same greeting +that the command had. + +#### Telemetry Channel + +Telemetry channels provide the active state of the component. Each channel represents a single item of state that will +be sent to the ground system. + +This tutorial defines a single channel `GreetingCount` that contains the count of the number of `SAY_HELLO` greeting +commands received. + +#### Deployment + +Deployments are a single build of F´ software. Each deployment results in one software executable that can be run along +with other associated files. Each deployment has a topology that defines the system. + +This tutorial will create the `MyDeployment` deployment, run this deployment, and test it through the F´ GDS. + +#### Topology + +Topologies are networks of connected components that define the software. Multiple instances of a component may be added +to the topology. + +This tutorial will use a standard command and data handling topology. A single `HelloWorld` component instance called +`helloWorld` will be added to the standard topology. + +**Next:** [Getting Started: Creating an F´ Project](./NewProject.md) diff --git a/docs/Tutorials/README.md b/docs/Tutorials/README.md index c85da4fbc9..5014623923 100644 --- a/docs/Tutorials/README.md +++ b/docs/Tutorials/README.md @@ -8,16 +8,20 @@ users to learn F´ and walk through the most basic steps in developing an F´ ap ## Tutorials Index -0. [GettingStarted](GettingStarted/Tutorial.md) +0. [GettingStarted](HelloWorld/Tutorial.md) 1. [MathComponent](MathComponent/Tutorial.md) 2. [Cross-Compilation Tutorial](CrossCompilation/Tutorial.md) 3. [GpsTutorial](GpsTutorial/Tutorial.md) -## [Getting Started](GettingStarted/Tutorial.md) +## [Getting Started](HelloWorld/NewProject.md) -A basic tutorial that will help the user start using F´, build and run a system, and learn the basic items in the system. -This will include looking through existing portions of the `Ref` app in order to learn the tools and terminologies of an -F´ project. This is the **best** place to start for learning terminology and tools. +The getting started tutorial walks a new user through creating a new project, their first F´ component, and testing that +component through an F´ deployment. This tutorial has the following subsections: + +1. [Introduction and F´ Terminology](./HelloWorld/Tutorial.md) +2. [Creating an F´ Project](./HelloWorld/NewProject.md) +3. [Creating an F´ Hello World Component](./HelloWorld/HelloWorld.md) +4. [Integration and Testing With F´ Deployments](./HelloWorld/Deployments.md) ## [Math Component](MathComponent/Tutorial.md) @@ -25,7 +29,7 @@ A tutorial to walk through the full development process of an F´ application. I one to request the results of a math operation, and the other to compute the result. This allows users to see F´ components communicate and run and F´ project without the need for embedded devices nor hardware. This tutorial runs entirely on a user's *nix (Linux, Mac, BSD, Windows w/ WSL) machine. It uses the existing `Ref` application as a host for the components -allowing a quick development. Users should first review the [Getting Started Tutorial](GettingStarted/Tutorial.md) for +allowing a quick development. Users should first review the [Getting Started Tutorial](HelloWorld/Tutorial.md) for understanding the tools. ## [Cross-Compilation Tutorial](CrossCompilation/Tutorial.md) @@ -35,7 +39,7 @@ complete Math Component application to the Raspberry Pi. This allows users to gain a basic understanding of how to cross-compile an F´ application and run the deployment on the Raspberry Pi. To get the most from this tutorial the user should possess a Raspberry Pi. Users should first review the -[Getting Started Tutorial](GettingStarted/Tutorial.md) for understanding the +[Getting Started Tutorial](HelloWorld/Tutorial.md) for understanding the tools and complete the [Math Component Tutorial](MathComponent/Tutorial.md) to build familiarity with F´ and to have a complete Ref application. @@ -45,5 +49,5 @@ A tutorial covering the interaction with a real GPS receiver. This will cover ho and cross-compiling onto a Raspberry Pi. The purpose of this tutorial is to expand from F´ running on *nix machines into the world of embedded hardware. To get the most from this tutorial, the user should possess a Raspberry Pi, have access to a Linux machine or a Linux VM, and have a small UART/USB GPS receiver. The ones with a USB mode work best. Users should first review the -[Getting Started Tutorial](GettingStarted/Tutorial.md) for understanding the tools and would benefit from running through the +[Getting Started Tutorial](HelloWorld/Tutorial.md) for understanding the tools and would benefit from running through the [Math Component Tutorial](MathComponent/Tutorial.md) to build familiarity with F´. From 6ac7b73ada280d2935aecfca593820d36a145949 Mon Sep 17 00:00:00 2001 From: Thomas Boyer Chammard <49786685+thomas-bc@users.noreply.github.com> Date: Wed, 19 Apr 2023 14:57:54 -0700 Subject: [PATCH 167/169] Update README and bump fprime-tools (#1971) * Fix tutorial link * Update README ! * Fixes * Add user guide to getting started * Resources * Review update * Peer review * Bump tooling versions * spelling --- .github/actions/spelling/expect.txt | 1 + README.md | 96 +++++++++++------------ docs/INSTALL.md | 115 +++++++--------------------- docs/Tutorials/README.md | 18 +---- docs/img/fprime-logo.png | Bin 0 -> 106388 bytes requirements.txt | 2 +- 6 files changed, 79 insertions(+), 153 deletions(-) create mode 100644 docs/img/fprime-logo.png diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index 1da60d3633..951b41dfaa 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -1504,6 +1504,7 @@ toklist TOLOWER toolchain toolchains +toolset tooltip topologyapp Torvalds diff --git a/README.md b/README.md index f85916e81e..29fa2022e2 100644 --- a/README.md +++ b/README.md @@ -1,75 +1,69 @@ -# F´: A Flight-Proven, Multi-Platform, Open-Source Flight Software Framework +

    +
    +

    A Flight-Proven, Multi-Platform, Open-Source Flight Software Framework

    +

    -**F´ (F Prime)** is a component-driven framework that enables rapid development and deployment of spaceflight and other embedded software applications. Originally developed at the [Jet Propulsion Laboratory](https://www.jpl.nasa.gov/), F´ has been successfully deployed on several space applications. It is tailored but not limited to small-scale spaceflight systems such as CubeSats, SmallSats, and instruments. +# +F´ (F Prime) is a component-driven framework that enables rapid development and deployment of spaceflight and other embedded software applications. Originally developed at the [Jet Propulsion Laboratory](https://www.jpl.nasa.gov/), F´ has been successfully deployed on [several space applications](https://nasa.github.io/fprime/projects.html). It is tailored but not limited to small-scale spaceflight systems such as CubeSats, SmallSats, and instruments. -**Please Visit the F´ Website:** [https://nasa.github.io/fprime/](https://nasa.github.io/fprime/). This website contains project information, user guides, documentation, tutorials, and more! +**Please Visit the F´ Website:** [https://nasa.github.io/fprime](https://nasa.github.io/fprime/) for more information. -F´ comprises several elements: -* An architecture that decomposes flight software into discrete components with well-defined interfaces -* A C++ framework that provides core capabilities such as message queues and threads -* Modeling tools for specifying components and connections and automatically generating code -* A growing collection of ready-to-use components -* Testing tools for testing flight software at the unit and integration levels. +## What does F´ provide -For installation instructions, including virtual environment creation and installation verification, see [INSTALL.md](./docs/INSTALL.md). +- An architecture that decomposes flight software into discrete components with well-defined interfaces +- A C++ framework that provides core capabilities such as message queues and threads +- Modeling tools for specifying components and connections and automatically generating code +- A growing collection of ready-to-use components +- Testing tools for testing flight software at the unit and integration levels. -## Example Deployments +Learn more about F' key features [here](https://nasa.github.io/fprime/features.html). -F´ comes with two example deployments. The deployments represent working F´ applications to help you understand F´. You can use these examples for reference, or clone them to start a new project. -The next section links to more step-by-step tutorials, but it's a good idea to build and run at least the first example deployment to ensure that F´ is installed correctly. +## System Requirements -**Example one:** [Ref](./Ref/README.md) +1. Linux, Windows with WSL, or macOS operating system +2. git +3. [CMake 3.16+](https://cmake.org/download/). CLI tool must be available on the system path. +4. CLang or GNU C and C++ compilers (e.g. gcc and g++) +5. [Python 3.7+](https://www.python.org/downloads/), virtual environments, and PIP - The standard reference application demonstrates how most of the system components should be wired together. The reference application can build on Linux or macOS, allowing you to get started immediately without the need for embedded hardware. -**Example two:** [RPI](./RPI/README.md) +## Getting Started -This Raspberry PI application shows how to run F´ in an embedded context by running on the Raspberry PI (a $35 embedded Linux computer). This application shows you how to get started on embedded projects with cross-compiling, drivers, and more. The Raspberry Pi was chosen because it is commercially available for a low price and runs Linux. +To get started with F´, install the F´ toolset with: +``` +pip install fprime-tools +``` -## Tutorials +Then, create a new project with: +``` +fprime-util new --project +``` -F´ provides several tutorials in order to help understand and develop within the framework. These tutorials cover basic component creation, system and topology design, tooling, and more. These tutorials are available at [docs/Tutorials/README.md](./docs/Tutorials/README.md). +See the [HelloWorld Tutorial](https://nasa.github.io/fprime/Tutorials/HelloWorld/Tutorial.html) to guide you through all the steps of developing an F´ project. -## Getting Help with F´ +New users are encouraged to read through the [User Guide](https://nasa.github.io/fprime/UsersGuide/guide.html) and explore the [other tutorials](https://nasa.github.io/fprime/Tutorials/README.html). -As F´ becomes a community centered product line, there are more items available from the community at large. -To ask questions, discuss improvements, ask for help, please use the project's GitHub Discussions at: [https://github.com/nasa/fprime/discussions](https://github.com/nasa/fprime/discussions). +## Getting Help -The F´ community GitHub Organization contains third party contributions, more documentation of flight software development, and more! [https://github.com/fprime-community](https://github.com/fprime-community). +### Discussions +To ask questions, discuss improvements, and ask for help please use the project's [GitHub Discussions](https://github.com/nasa/fprime/discussions). +### Bug reports +To report bugs and issues, [open an issue here](https://github.com/nasa/fprime/issues). +### Community +The [F´ Community](https://github.com/fprime-community) GitHub Organization contains third party contributions, more documentation of flight software development, and additional resources. -You can open issues with this repository at: [https://github.com/nasa/fprime/issues](https://github.com/nasa/fprime/issues) -## F´ Features +## Resources +- [User Guide](https://nasa.github.io/fprime/UsersGuide/guide.html) +- [Tutorials](https://nasa.github.io/fprime/Tutorials/README.html) +- [Discussions](https://github.com/nasa/fprime/discussions) +- [Submit an Issue](https://github.com/nasa/fprime/issues) +- [F´ Community](https://github.com/fprime-community) -F´ has the following key features that enable robust embedded system design. - -### Reusability - -F´'s component-based architecture enables a high degree of modularity and software reusability. - -### Rapid Deployment - -F´ provides a complete development ecosystem, including modeling tools, testing tools, and a ground data system. Developers use the modeling tools to write high-level specifications, automatically generate implementations in C++, and fill in the implementations with domain-specific code. The framework and the code generators provide all the boilerplate code required in an F´ deployment, including code for thread management, code for communication between components, and code for handling commands, telemetry, and parameters. The testing tools and the ground data system simplify software testing, both on workstations and on flight hardware in the lab. - -### Portability - -F´ runs on a wide range of processors, from microcontrollers to multicore computers, and on several operating systems. Porting F´ to new operating systems is straightforward. - -### High Performance - -F´ utilizes a point-to-point architecture. The architecture minimizes the use of computational resources and is well suited for smaller processors. - -### Adaptability - -F´ is tailored to the level of complexity required for small missions. This makes F´ accessible and easy to use while still supporting a wide variety of missions. - -### Analyzability - -The typed port connections provide strong compile-time guarantees of correctness. ## Release Notes -The version history and artifacts associated with the project can be found at [Releases](https://github.com/nasa/fprime/releases) and [CHANGELOG.md](./CHANGELOG.md). +The version history and artifacts associated with the project can be found at [Releases](https://github.com/nasa/fprime/releases). \ No newline at end of file diff --git a/docs/INSTALL.md b/docs/INSTALL.md index 6650a25e4a..7c398b69a9 100644 --- a/docs/INSTALL.md +++ b/docs/INSTALL.md @@ -5,17 +5,13 @@ title: "F´ Installation Guide" ## Overview -This installation guide is specifically designed to enable individuals and researchers to get up and -running with F´ quickly. Larger projects with specific requirements may need to extend this process. +This installation guide is specifically designed to enable individuals and researchers to get up and running with F´ quickly. Larger projects with specific requirements may need to extend this process. **Note:** See the troubleshooting section at the bottom for help resolving common issues found during F´ installs. ## Requirements -F´ depends on several items before the user should attempt to install it. These requirements are -listed below and the user should ensure they are installed before proceeding with this guide. Should these items not -be available on the user's Operating System, then a Virtual Machine should be used. One option is -[VirtualBox](https://www.virtualbox.org/). +F´ depends on several items before the user should attempt to install it. These requirements are listed below and the user should ensure they are installed before proceeding with this guide. Requirements: @@ -27,91 +23,44 @@ Requirements: **Note:** OS-specific notes are in the [Troubleshooting](#Troubleshooting) section below. -### Setting Up F´ Environment +### Bootstrapping the F´ Development Environment -The ecosystem of tools supporting F´ is installed as python packages available via PIP. In order to install F´, the user should -setup an environment to run these tools in. - ->Note: Python is used by many operating systems. To prevent problems users are encouraged to run F´ python ->from within a [virtual environment](https://packaging.python.org/en/latest/guides/installing-using-pip-and-virtual-environments/) - -**Setting Up a Virtual Environment** - -Choose a location to generate a virtual environment. This can be any path the user has read and write access to. In this guide we'll -use the path: `$HOME/fprime-venv` - -``` -python3 -m venv $HOME/fprime-venv -. $HOME/fprime-venv/bin/activate -pip install -U setuptools setuptools_scm wheel pip -``` - -> Note: `. $HOME/fprime-venv/bin/activate` must be run in each new terminal where the user wishes to use the virtual environment. - -### Cloning the F´ Repository and Installing F´ Tools - -Installation of F´ requires cloning of the F´ core repository via Git. This will bring down the core framework and C++ files. -F´ ships with a `requirements.txt` file enumerating the tools F´ uses and their specific tested versions. - -**Clone F´ and Install Tools** +The ecosystem of tools supporting F´ is installed as python packages available via PIP. ``` -git clone https://github.com/nasa/fprime -pip install -r fprime/requirements.txt +pip install fprime-tools ``` ->Note: When changing F´ versions make sure to re-run the `pip install -r fprime/requirements.txt` to get the tested tool versions. ->Note: Alternative tool installations are described in [Advanced](#Advanced). - -## Checking Your F´ Installation +> Python is used by many operating systems. To prevent problems users are encouraged to run F´ python from within a [virtual environment](https://packaging.python.org/en/latest/guides/installing-using-pip-and-virtual-environments/). This is set up when creating a new F´ project. -The user may easily checkout that their F´ installation has succeeded by testing the following -commands. First, the user will test the build and Autocoder install. Next, the user will test the GDS -layer components. Should the user not have installed the given component, the commands won't work. -**Testing F´ Autocoder Installation Via Building Ref Application** +### Creating a New F´ Project +The entrypoint to developing with F´ is creating a new project. This will clone the F´ repository and install the necessary tool versions for working with the specified version of F´. ``` -cd Ref -fprime-util generate -fprime-util build --jobs "$(nproc || printf '%s\n' 1)" +fprime-util new --project ``` - -**Testing F´ GDS Installation Via Running HTML GUI** - +This command will ask for some input. Sample responses are below: ``` -fprime-gds -g html -r /Ref/build-artifacts +project_name [MyProject]: MyProject +fprime_branch_or_tag [devel]: devel +Select install_venv: +1 - yes +2 - no +Choose from 1, 2 [1]: 1 ``` -**Note:** `Ref` should contain pre-built dictionaries and binaries for the user's system. This can -be achieved by running the Autocoder installation test (the user must have a working Autocoder -installation). +Next steps: [HelloWorld Tutorial](Tutorials/HelloWorld/Tutorial.md) ## Advanced -There are several advanced options users can consider while installing F´. However, users should be warned that some -knowledge of our tools and versions is often required. +There are several advanced options users can consider while installing F´. However, users should be warned that some knowledge of our tools and versions is often required. ### Installing Tab Completion -Several of F´s command-line utilities support tab completion. To enable these tools to use it, see the -[instructions here](UsersGuide/user/autocomplete.md). - - -## Installing Individual Tools - -Each of the F´ tools can be installed individually through sub packages. However, users should use care to ensure that -compatible versions are installed. - -| Tool(s) | Package | -|-------------|--------------| -| fpp | fprime-fpp | -| fprime-util | fprime-tools | -| GDS | fprime-gds | +Several of F´s command-line utilities support tab completion. To enable these tools to use it, see the [instructions here](UsersGuide/user/autocomplete.md). -> Note: `fprime-gds` depends on `fprime-tools`. It is advisable to install `fprime-gds` and let PIP pull in a compatible -version of `fprime-tools`. ### Installing Optional Components @@ -124,8 +73,7 @@ Some F´ packages contain optional components. These components can be installed | fprime-gds[test-api-xls] | Installs excel logging for use within the integration test framework | -> Note: these packages are optional as they pull in many additional packages and libraries. These may not be supported -on all systems. +> These packages are optional as they pull in many additional packages and libraries. These may not be supported on all systems. **Example:** ``` @@ -135,20 +83,17 @@ pip install fprime-gds[uart-adapter] ## Troubleshooting -This section will add some known hints to trouble-shooting with the installation of F´. This will hopefully help users -install things more effectively. +This section will add some known hints to trouble-shooting with the installation of F´. This will hopefully help users install things more effectively. ### fprime-util: command not found -If the user is using a virtual environment and receives the 'command not found', the problem is likely caused by the -environment not being sourced in a new terminal. Make sure to source the environment before running: +If the user is using a virtual environment and receives the 'command not found', the problem is likely caused by the environment not being sourced in a new terminal. Make sure to source the environment before running: ``` . $HOME/fprime-venv/bin/activate ``` -If installing without a virtual environment, PIP occasionally uses `$HOME/.local/bin` as a place to install user tools. -Users running without virtual environments should add this directory to the path. +If installing without a virtual environment, PIP occasionally uses `$HOME/.local/bin` as a place to install user tools. Users running without virtual environments should add this directory to the path. ### Helper script 'fpp-redirect-helper' exited with reason: Permission denied @@ -175,8 +120,7 @@ Now you should be able to run the installation without trouble. ### Mac OS X and CMake Command Not Found -If the user chooses to install CMake directly from the CMake site (not using homebrew nor Mac Ports), then the CMake -command-line tools must be added to the user's PATH or default system libraries. The quickest command to do that is: +If the user chooses to install CMake directly from the CMake site (not using homebrew nor Mac Ports), then the CMake command-line tools must be added to the user's PATH or default system libraries. The quickest command to do that is: ``` sudo "/Applications/CMake.app/Contents/bin/cmake-gui" --install @@ -186,17 +130,14 @@ More information can be found [here](https://stackoverflow.com/questions/3066860 ### System Python, Packages, and Python3 -Many operating systems offer python PIP packages through their package manager (apt, yum, etc). Most python projects -recommend avoiding those packages and instead installing them from PIP in a virtual environment. The reason for this is that the version of the python package from the OS may not be the required version that the python project depends on. Thus, users may choose to install F´ into a virtual environment. This is outside the scope of this document. +Many operating systems offer python PIP packages through their package manager (apt, yum, etc). Most python projects recommend avoiding those packages and instead installing them from PIP in a virtual environment. The reason for this is that the version of the python package from the OS may not be the required version that the python project depends on. Thus, users may choose to install F´ into a virtual environment. This is outside the scope of this document. -### SSL Error with Python 3.6+ on macOS +### SSL Error with Python 3.7+ on macOS -The version of openSSL bundled with Python 3.6+ requires access to macOS's root certificates. If the following error is -encountered while installing fprime: +The version of openSSL bundled with Python 3.7+ requires access to macOS's root certificates. If the following error is encountered while installing fprime: ``` -Failed find expected download: 4Cxo(F+Ij5^vH zMj#MP_}L#F4G2V0eoapsctP)`ZRQRF-4Z$bqd*j>c!5BdKsp-t9wXA%2#zfhCYFn* zbwls$FE`orfxfrS@eF;%)Z^>nq3gq9cO4tfUy%b#{bJ!AHV*ewcXKf3KFB_d4#0 z=bl1Y+pa~O6IK^i4tnq1VNd%zhm|75K|}Q#FKb-1Ce@4Ff6L=Cy??N2DBkLI0i@-y zYmUs#jzQjv|JtJ$yMw#q?iesN(j%6n)o zW2An!sN@Ty_Q;zmDi@M;b>xdes5=-spKt6aeYqc}^vojyWALFb>h+-XqO!jG@qx^K z=IvCqx0>NiFkaDDOhR(KQ7+F&(wcd%oU*;z#E0M9u~>ZOcF1T)YOK?j8_>JF7&oL{ zCPeCs_$8k2pz*0jv&@1J8#b*j`=bqHjSb-7x4?(pe545_&uQBUQZVCY1V;>=`_6+Qzf^;j zdWiqjfe2S>PiBx4K>y&d%c@suhGs8vXnKDlUp!w|E*ILqXO@@Rx?f1~U?fLwY3UIR zvRs$vIQUFY2|Bg!S;J>hkg@ONmsWS!Eai&g-hF1V>4V>29eADba>YdfbG#~7>*xA% zOptK5u5OKc>SXf!=|yI8S39EA3sr1Oz@#bm>6F>!j?jN7)k#Dn63IopPc@z6bB5$` z!Bd(x5;qFAiU)+M2zQQqY+W>6)y;0J?(3s*<}-!&c!uO+u<}AR5>Zjlr-d!@Xx* z`p*fNzcy2QPB|D1--t6aA(4#zB`fII6o&3KRV~@kNnMbpxe<_FE1BgTqjNBPEt`-0 zQqgU6O!+ZPi6uX?se4gnOEjo8iNgr*tnm))@u+&|RefK^kapHYP8u7ZTEpda16RJJ zaS%R;yi>i9G}@z(D1~iu)U$BVP&wL#D#X7Yl}>~#*v!@gG#K-a7@@WNtzMHRmUE_h ztT)JnKUAZlb@LtRcC9MOvV+^2N4sN*shU~XY8O}@<-OAA{-7EE(-~)ph_SI4hxp|L z-=)Gr9ieSzLSSVUB=E-pqev?EwM2;VXsdo>J{EVSmvb&E@?+n zi79bQ3w|4FAmlhb=CZmsGeW=&=9o$c^f&h{7vMG7$UAi(os_fj=A|*XWfij3saKhJ zexZYgQU;{6C(jpMWY6sa6Px`TP)%9~ z^cel1HU;uad#wjrp!w;<{gljrHKar)RAvw7{}D4cLL5h3QieTDB+@#vcf1dPXbson>gvlBnl5C(|!FF*xzk**(F z#b;FCPAkO!VuOpA+Vzy}lV7LDzb5}$d~*3I!nF_&A$%5J&db=>;EhJ5rxGxlc~zsm zinZ>Vbf01d*ZsvlJC0cxp~}nEn|l0Crhf6s4RdMTbXExX=g^EI(luqT2lz4(`c<5~ z&BX%p&9ztRnF@vqw|Iuq2I_h83JWTWQ!hoY#fG@>-D+m+1&71d)LXh2T~B|uw-+5_ z7;7R}8Q2Skiq+-p%h=GpS=deaI}JY};8n-R>|Pek4}{w5@18b3P~3iERoa?RY(%S8 zrR2ArX`f8^^6DCYb=(NzoS%vSLQ*MU%H!1{t0GhXK%airG|eCBH(ry^o>MC_;Qq*9 za)`oTkUo>3EHf z@V7bsI3!;G+`r$;{1^TUSEBT%_4JR4RasrL-wJ-jLXH;Vzd5(lgUE6}(%4pxaW~l* z5STkZ6+7+Mc9LUUmSkQ&Mhd!7XH@D}VNBQ=sGVP=U0sf158N1Pzf*=n4}8z%8=>54lKE@%{N^R5q;Mwe`(9o8pyT)*`f=I7ux;jn+Bja9ydSLs5+4?Y$5?nYzvYA0cNtfD1)qKof~8>6sDRlL03npD97jfuam7_MW%e3D*~mv`A|H| z=P~;H4`$n6M;ALvEI<49!dYB?@k6+Hvog$|obubbdc`c=3CML6kv?BGe<=>K=hqdp z>{g-aq;14Fb`UeP28wgK+;DHl^HOchAh-peKcuTIG*{JM?rntbRhABSmW^4eKo_|T z>&~R6L)747ri|CqA+1rb>`0$cP3lq3uYc7t>TZ<7(!1;0QhSxdAK^9?lvwyQTJSiy zn3wupKK61kJFb|%O?kR}q#1Y0a>5u~q6q5LP&cU$FGQwY1Dv^BfsrChC;_9q%>LOs zckz95uS;0I*xRz{H#i!Om3rgV#~1N%0k9+P{U&gbp*0mYpQUxz>LHL9+sua_Q02_0 zn;kmrtIB~5o<;*>vR9~{z%`;4{T~TYLla$9E_)f)Q9Sa>Fc*)zxzOuj5oM4nyYb~)cjJx=tbx)7 z(coFEb*mcht4iX(xNS`nvqXu_@ZZZ$DC8kv_Hv%8F<#*(>4@rYH}m!ma8IO7NSh!uasDT5aVjaZoEON zAR^{=>&GD#a6acZz3Dg8`(Mf`zpvMClzRhQQvxzO+YRt#Eda|oUn_TY*6U+sK8%Iu zGJeyaKBG*05?=0CvFr0EO7NFSY5PD zwRyBY^y*@i*^TKppS!;p(uO5Ks$l`atuPJS=5lo`X=(?>oS^opl|DhN9Iq(r#xe0z zb1c^3)~j;nDysW@BkZhPBNE7O@{MdAG~}NN4kFDHXt==9+tLB-gIDrV5#pH|SKD&mb}QV}*@}%AJ0kVT zF>E-ASc|{)zPUrditc*t04rafbD^)^i6+Dfn!f!az`(P=`>K7O7hr^AwLV#iwQGNu zB01Ne?LKhUaAICoLe{tW;(bh-rtl+_4<0t!3cFclu{Pw76-SUB@Yx?LS7Y=?F*#kX*EwZ{DAKApDDf(O+tEQ?~}ze&`*A za-$7RfxvZj8X{2`sY=g8P-6#o&}iPK014zR_kIiU*Q9y=o#m zjb_X4)(;n2Mog4W_dSoLnp1%}F*SVp%-8Hc|V z_e-dJf;GzycY!t8eBWiQ;<(QjpK{Hp!7~jqYLo6%RK^)Y_YP2IO3Xrs@{0sEEdgfP zq(L5lPD?hPWp@^(_X)gwK@iipFELBmDgjIw_WqvVMO;B@rmt=mS8Xv)c~*v-->5__VtnmidRzGA)we!VGN^yB$2a;Rg zjcX*o`K@81UJdzoYY7Dew+jLWlTZ#|K4(+l(pmtLRoV12{UCb;s(fHaA$!YO%enm8 zT}|iqUkgZOuUM5!Yj1zGx~EYT8Z_+kshr4{gk?xCzlrD$a?RPY?$y8Ze6D!9=`a}z z4op@NTnppe*P{N*PdudX`L`$3XQ9q7hV_sO`7CiEG*mCLDJXaxR8?ts|6PxfqQp6y z4VR$rNm|~j4z3Di)8{iZ=U>@&Q2J7T2H_%`QBgJD`|-YO zjhtMJbTyuMhRQ}Qi2pnOQAZ!#oL?YOg!^qFGMB<;kheU`w!i@G$@Y~Aoo^6sm&+$P z8hppXOTFq*(W}+VHmQ@J0uT0u#4{mpX~LUGSi1+ll?RjCie>qU#NhYTwFcpXKjia+7}D9akNe^|y-l zK8JAE5p%r+8(oz%2@{uXAn==C)3m&|ooorXG%Y;3uKKG!^vR1<42FbTcR5uZCoxxB z?#<zsdl`r=YUik?7iG@> zk-o4RFeub6SINbz*N|Hga#gz6P~B08Px&cO3#f5MNkW$w+m}ml>#4~GZ&Jmtc=GGX ztf(3lQ2Z$}(CntqkL7yi!53RQH9c0%n@)Zwk))`j^MZfl6Q1D7>Al)8`1gUzj>cyj zd9?vsugj(}rCX1ddQT9foricA)nA*!a-Jl-kz7FkT?5#4%RB#PI`M&=K>{ zaiS#D2)8kG+vQsR=vB$=^^UrvkjyJhUR z=4gK1($b69W^2kg5ASN+HvRd5X?sn%)#t#z!uGoBVYBG!Ed5B&W~x_K+BSJC>tr1> zs--_3%$1_(5>}PW=_qeN$(N)UZHZprNgRuJ5^8`cCM%{zHbkg5zU#3`c?tylU!ghg zIMG`ABf)lQiaZ%qKMvFzrqf1b;4U8t^1i%}tyV59rPi-p685aE`7C}s=6-9ux?4+dQlwnV!`b=|im;ZKekuzIyA4`1>PKV`xu5)k<>`V9nZDGH249nI~q9!o3( z0aF!aBN#2S$MYWNzBU&QjBW8g&T~z(V>o)kAI;(_{*4*?_@-yN#Op;VBT=u$!mpac z<=QATfhi<&Y)grm#zQ~KNOYKe(eoO|-n^CjcgmbGN4|t4*$`<(y&S89ckQU0W3IxI zJ8U@yD_;Q`wrGKh3FN7i5UNB(?v9G5krI8sBj(6fd>$+ZebZyq>!M*0c4O^%9yBH6 zTux9yw_FVjHA3QKcYgLo0;w_adgZ6j>|;eW)_XV%1omP1y3K#evOID(!yVX* zL;8J~Psx8ycfYwu$hpQz#AtjH^SrA_f3|U}TvNiOWW@;Ro3|NMA!CxOm!v$^JfT-S z`&E`c0M(&QC1Ku`n{K?LAGrxtto3);Y=leZ3*Rb1Lk!MsGb_r&f76c?20&+7$}KY| zW#E?X^Y4|Ee4YJc9_w&tu;<2CINr{=#hby{zL(P8-oBR1C^x4aepp~o6@Rs8kgK^c zuOz`strn)YRpEH!RZF*=eN#lsi4f$WtC6TAym{H!(!;Sj=0_E-$Ivr-x49DWi!=pw z#qJa`y+$=M^P!bapf$S>Y1!J?DJ-@{PG=v~n*5|{E+jl_(hqa0^wADIcVda#N*o*`oXRdz=5lkJ%J$81A=yvR1Zx>PVV9y}YzvHOSA*ox z{rmh-hoXD+#WZKRyqtG)rO(fOP1N=g8aL+n=w7oYDoN3&!Cxg6(>5&|9JV{tnkGj3 zJn!$L-gMe8_ocJX()kUcdZWEzC_EHguEc)XF; zQA|nvLcCK7YlFYsqarx?N4aYvx_Bxd0CSYyf!$>A1~_1)vFS>oL0*QzIpGl8*wzV= zvIO0T4mY4Glf3v-k}veAck?tY=;wYIrKsb%5_V;e1m4sXJ(ht|3W6tTjBLJqoBdJm z(v>RTAL-_OE_z#Ij?ZJX`AS6i3w@&Or`xO5|)x7U!hWiIY>#N1#r&~7~+Lm=P zDDx6JKBuhhdkzVw=~FrZNKjnQ%BxXQ;dn%ZBe1o2`a89-X4b-nAwE%0rYs?{4REOW z-!|oFy&Fsi`799w%tdt0AxN=9JiCY_fVQbky? z5Qg*jpOpdo1@@K7oaw2>3by+aBRu)0VtJT;#32BUl@ZVuXpoIxP4mjEWzY4oMB9n* zOv?!93)l)kD(qa|!)YZ#KuUJ-H(T;gxVTo?GKN$E_vHax6VP@tSy_amG44Q(| zuph%WEP&1OFT<=n9;F`{7RL2eEVpTXc&#?3&(Lu1TXUg$33^be5a!Ft_Y;Fvecw~8 z_A{U6EzXy6)SRqZdnSUA%tmVgfF^?br{oWcaFMFfYt?7J+kGhx0VsQJx*LL^b4Mt~?WIigMZM`UWqcIIFy^egS57H`M+k%Q2W|j|Z2YPq{%ArK+N^ zVz%8~tsAQKNi;7C4F>BJp9kbM8rwSqDl{fDvM2ElA3gJ`tAAARAfpt!LYG1H7uH>Q z!876du6aher~dxVLP?U}C+$`Glv;|`{g)=~q6IKgqvWI|T4y)LU2Vq?vcuBuMi7-i)<9x>1{9A4olb8MagB_OcsLkpEO zGWwWckGxwcE9M!SZL5{?kGpT`jRv3m^oGp;%Xan4fP{ar(;xV?)_Ad|a-6lf&^12+ zBqjBP5-^6Hie-~g#2xi-e8WM-iuXT#+wI(y}CxLI`;>*Rd*~NE zE2F%5Z%(~Y8@tm1^8^xp)tER%BW$ffV@xmLE)psR98@ zNP|CZvh@e{k^pac2j-a;j!|5*6Xz$?_vUK%%`+;t48q4O+E9!?T7j*D7{!PMs{sxE z*scK2;H#es*>gH1WO$=eF8=E0;8Dcau_&FpyDoHZ+xbKmF`5|7Y!U3A+0?kd1U#(cUa{U>{@H$ln8I+;{kFg>RxpZA>9ImRJ zq#mbBTRsjdrf+i@#Znd1G)D*AXQeN{-01N4j~BS^@(U47jZ(_NM-5c?Iwe3-A)fHq$l>qAN# zGeEWZ-fX5(F4GFasVvDkMB#M&Hm1Pf2T{PgkNJ)_ApaGe3~PHz85S)%fl&NeYj99SmvJ?gE4!gX3o2^ha_)GwS`0 z7=;3M1W$Ycm5!-yGzp4$KJWG!^xu)}qJ4LF#9>XAH$bQ3bZSr{1I{GcL zCw8xer^J1`SDWwVj7DDdA59O{?#|d0qDJXRHj^>3Wy=iPcR4LEh9sajGc6|Iv2`ZfvV*(j6 z3R8iKBU#RY9;?$)fJ%jdCV_DlH7vrh>pyz|K*3IQ!XQW|b?HEN9m`ebH+GPh z^KK(*+3&>9I`+TR2({l1oNujcTRgr=sm-beidz)8-JClRF+E#d_${=Ekt2x(>|&Dj zP(t8jQD%QoE|>$5+B{*e>xPFI;%h~dD$zkAedb{xv2W4;c-Cy_sE;}DcUN@NsV}`S z=;GWI!!6hS!>~|M#VXYp20@#u?l6@dKkf>%uFWKtbHO1lWXw-bZn}t2QHrpEQ*4IJ~KaO%z!)nEj7}Rr)kxtNXDE1)CLg0Bd?Mnz&_eL zWkc`Z?TkuMk4omEq2NA|$+v+>tcH-v)vs#~XAR=p)c15fzy zpzFSjP`P%GKrL|v#Cz4FYL)2>kkJvF8r4wtWQ-_fSkdh(q3@Wepw3#GdU}k4j+2v} z^TxdEza?mpvRs19g7E&^@Q=KLVDl6IUKLpY9!IFkg~cWLY8mWfGa&UJ&2o`db+U7a!*Q%i>ag z@n(*(!WZgyXpqAL3%6AS!Oa%mejTG0pZb<#NVSJj4?1nLen!(m`3wR&(c0XoijTV( z=%yB^Pe@+!`(VDTOyr1FdbRznaq?~@U(m0JL-O@s9Rt!L6%^_$fKmQU#He-d;0V>u~uoR z;9#q=Nh2*Qi~}6QS|89U;#J->g#8JdTCrE&3_1`BYVfAW-`nJ4rxS!>REZjY`>YD9 zqz0Ji1vvgkP+%M zhCaIddFU+9YeR=ky>8bFZED1c%@Tev=JoSVTM0iB3^A1@EL&x*O>|gPcK7;eqO$BD zl7Sa?uD2rj*kXx|n~td)`}_=o+grC!D{pVW0V_VA)3H(Ox{z+x@{-AC=oU3}Nep4p ziS~|lD9ssLX#Rb;KD*Ur`x8sNLW^{R+~5NLvcID)cRDY+oH(n~8fh<8$s--zi4Lr2 z|J!~VSV^fZp&Y&^gD}EON<4eZcpBZmnraHKHb?JX7bn19f}VlJBTrdyaONzfMGFR;g-aaekL91!EHu*E8d zL2^sJr%dzFP1k_gU(+V4ro|gU++Np#)g+jG| zwe43l_IkmlSD5{p40vmHi&CGb6Ww+)I3!CIXItsI$!P6eHxn5L!01fJxtA>sj)_mq zB0}xa)I~|nb*VfVRlPhxCJ79A%E5} zKl=g|6rEpQHZlj_54HDf*|xe$h2#+f4mpk9bE0#y!Lc=!T5%On+5i{TDH3kUaDh)? zuK^?9wX!hhsD8A`kg5OV*XKv)1>L7j ziPAkS3tqaN?pK5n$5n=%v(Yr~O%%$T;cgfL&CriYL2EiSF?2=|wEn0m=JRa4*Y8q1 zg>R*qr5CUr!Flg)|1OE3-?@K*UQqJIxlWNaBEd6F3FfL4KD+f%ocy_W&bnOP)E*Vv zb0IEsc4V;r6W)<}sQEQ6Tor0!p-Xfw^fY6;kXiBiEiKa0X3~c0!hJeMkHzIj+=-(f ziyeqdnTB`0K5W2pW+js??;^S?70?+jvaWtHvm-bP-KN}E`_trcotm&@BFA8r^5h!D4?Tj2Jp zOki7PUdVOP>2^1hpxhV$Z5#Y@HE)z&`zhIWqCLaDg%wGDd?<#<7w{HCtewBg1~!nh zD4BIcVMw7xN-B@1Tze5F`@e%SSh(5|d8EnYtJe5tWOy$foTzKmxE5 zyr2T&`Mnp^Q8jID#4Ah%vfUbZdi{{6@d{w7|rc4WXYauWRD2hEY9FU5A_W&sc+ z78ZGxP@^cx>+#JqQ=XLSYj8S79^LY(V59h1*5=9MKgVmPYrTT%O#02i#VP zIbMS5%&HrI;?jR^l`)GWl3z0p&CL(QHUdGNqk2gc4b*kt0;L=ezfg`p;dvu`p+Qdg ztj@b>q8nglOw?9-J-!ZV#eTk}q=5Lkt+a7W3HZT~$a+U9i7j5i)pRJ7sGT$7g5(2x zR?g}0=?3gfG(|368Y3hrCgLU!e{RNKFG3KnWbM-%s|OM_8XjG2W4utk{m&j*L$ zAGseiMT)}3>Tn)mz~N;-S3Mg)xcQrA$f#m&(xbDE;Ory-?iBD1BJwL&1TsQ{p46wP z)Mwn7xBv1?B;wALLDVqNmDV)*a*ulG3YJLsB(e6Ex7J#lU8~m8IUqQJSaqW>Ztqb; zS7g8?>Lp2tTSX@_U@{>jetnHzu=LXVx&+}J04D_l%I--c*ed7ZQ7gaCd}r^J&mJ{W zMuH1$u*=0LXwSFk%ZOBdE+Ggm!4hkq#O}Jkq#ddf@NEVBemDtrbgAT{-lZ@;msgSaJE3KWj1MJL#?Igp)&Uq@Wn}}pLfRghS{W9P^ zIias%_9~Tgto1db2-0=YhGxo0Tr`XC%+Cth8WDbQ&!93F7>CHYjraig+UBn<`|_Q( z`tPWq#pkL6pTRdj5j>G?k-f`y@BWbx5Q0s?5V323b>!T6ja9yaXere*jXiV^SL3?) zd`oy|+7qPHIlnO#)>)GdLu@=T&mgzW98M|!f!qTX+m8SPK0YgG4K^fqN-e?=F2}>_ z{D$Wy_}($*c(?Cdm$L8bwDqU~LaH@hTt9$k&#}aogC3NiFSH3t4N86)FTAs{*{mBC z+N<2oej!sAOZ4Bj47y)H34*<2$eB4FEc0-nt-Rd%=#V$_fh({&ci{mTWc{6sQ|4<+3LbugJ}(2;xE{Ylq&bg7`5Z)C?K^Z@&rIkI@H0=hG{ zroJTCMqVCD4i(+y&78Oc^Y&c{Kmitm9j*FLDu1uQHFUtqD767TC16?aD!P# zz*>Cw{Mt{wA>QlxLLksu)nSw&T6wxB0MWA1ObkE>wk&%KT?+efyB^R0jCi|rOYaN-29*ysh(HIrnihZFX|FbEPi>>0WAbz3MvqFzfySkY;N4(!? z-*?$n2L%hr;x`)IZ#T9KL@&Lmf7r>s+Uy?ITT*}4O;8*P%8r{fR?}DeCN&EIZ@Fvs zxNS_kKtQUJHH(#OFuuHEQp_|+Zsg#U~E6ka)>4`pk z^dME%8o^uvhRh8HZT3*WRplMeN}_guTd2gTfec6AYxPcAO(wi%MDCJZ=sQJXG8003 zS4t^C95r$7YIw%XYp61C{@tYLVp-KH5~zfp5{~j_U*eT6xO=iC+E;1own1Y z963a2cisA847!{aBxXOIH&64doBh1ttL%H15UCxzI)r8rsGvXa&0ZV~;ZenRiyvIQ ztz*}BR{Y|STXk0x#}YjVUgS>O03|PJ#Ifq5w?I8*)b1pP-f36{j5*At5Lse!<;w}z zb=rnRI#708;c_z&1H_s*>-gU1D70vmP5M?kHNb85hCJLvU0J<^;I1y-Id7R(8`xsh zd#WHGNCgsm!D?ll3gq8$v+->b!W`f-&%Mummq21p(@Db}FoZ7Ekdr6BB7FK&XU*jZ zPhEOE(GK7y7D(OIJlWGJ2>RUWCz@JP#UG&eX3iFc`Qo1N^pZ#B3;p{i5E zEG#q2D|j1$NkT6i4=Q?2%}zd6(q$6#Rs?0gpA5291I|*~EqO-`eBZ2sZ;KE7TL(aw z^9kV$?@^LILEBFQp*!FBj=Nlk3dg$`kFaL+Q zAlToPAEamBmShP1#@-xR7*k|_HZxIE2a-yqkL>G# z?-)G{AKwGriMSsd`+!F`V~o7OCEzd5&LLXjk@7y!S4OBIWL*Far@GP!6nA2YZ@6o`I=5#Bg#6Z0*H5p2 zg5x66*>zhYd+9Re0^hsHfIgw_PyM);viSPmX?9>y2EPfiPV@ILQDwGps_>DqH>Hm5nW>-+RfTjgKzIXM%DtG^H zBya!LO8Ea_V)?&9+W`B)62+yN${>8wz5_u*voeeSBu@?GwjQv1m>&yBfSKv!H?BEtwkB&mM5cqKJ52J3$VzJ?;S{n}kffPZyEPXK^iu^hu z$PfBU8Hd~Y(EvvJHWXklrL!wKdSmm z58P{9tbDPXptwddoTvWqhER*#3l**NebdASl0PUL1(~b2_YbE8X?iX3^Kl2#wZhdfMc{Xu4`<(&4R8wItZ>nm!X-WEycIW4>fxnpr zQ~t=k>}3INGL}rTg3M5--0B^H`o)24QI;s~jGj`VJipEQt0#hI*9M73q~#6ao%eJ2N}&3WJbPunyjzZ9FU$IBg9R8- z+ntXZ8UfowNJ~vuPfq}CygB&e8i->|AgqcGk7G>8(uAhM#am==Ex^*kF)Nt175o0y zKvHRz=F!}IVDHrA*(JnsyAnXvxqt2;BwtL_@w!!JCE8%q-u^V3@x|D0bZx?ug?E;* zkX5(*-V}JnBl{u4=LGs2%PB9%>{e_x@%?4xFrU|M86n=TynZuZ z2!EXB>^H5FxsurfD>4{|tM_@N8ims8r}Nf*YIi0e6q_f`xWhv{_8D;f!2RkpRT#K! zFKWah*-EqeIw)@kGc5+q_X-7B7YgAo`B~AkLc;9iGQ($h{O{v*BJCLS^~63t4-u8P zcm4v*$jzeeAnzz=7E(>Aoo;ph(wz5i+K=ovyN+s6j2o{hDSk&HkG4@t1j~fKNlGFc zyYsXkq_duqYgbVoCXkg@CgF1q!)vRwTi)NgE*&&0z%IR1n-jSu#RmB?LI0+bra^`U z()#nQiApE&Va}yj3!Xt3)dQ+Uo#Mdfb0WtFO7q-p%O&s;kx1b9iS6b-QgKK$CD(F( zKvh^kwhkgJ57YPWhSO!;tKoxoZC+@*Ypo@tzst@nP=JY9P!mm z+URcKlt5PP)bHS}c23;03ZYt*YV(HH`S4qD??Ji(UhCBQF9KGv(>u|<-lcf=O|{}c z(AA3U*Pwz(sG9|;>vH3Ps$Q?xK~K1$|9y3l#&XATsMSHSYJ|<_Z@!X(Pv=X8U&Emnrtx2D`A-WH_-a{p~(3jipow5`CkDA2O{NX{tdpL4Zjn0(!cq2W4d~MY@9*&Uw^kMtbJs>$8@PN zx)Uz(hnl`$gufQ& zLX5KIcT`=YZt#rkt{BL31}e*q;ax?3F0^q%ca*y;Y{!ugS=T}v0?3atTj^OA-TQdF zl=DfB>BPypIPdkRbh{^|*N!cdFJwPVYpSxr?#b?a{+FrkNZ@A3kJcM?=**D5k3H$xi_BS=pl3Jszbl-{HxiC#Sq4MLEBFl~T)>BunF96vbYT^G} zh0S@>Sg}$H-#N46CJqL$BfXKeX+kJokz56XZ9MO;$bgI8S;I|n$@%B+JFTDUq1e;{ z76WlEQZFN3^;E46+)d(!U_Rz=RAtcp{~Zla??_9F?JJK}9Or&-zF2=bLBXL&XPVn^ zvMmZzlK(Z1BLp_Nz_oe&KmE{}8td73M}H@{aV%L2o@;Qz%|UPTjJ2 zL3fpGevLW%E2kcds`|;Tn*Wzg$$sQKpS4u)(oTwwiNp7=Mg+GqJ_B840^bo5jd=8< zgVH<2?qE&zxB7% z{O$LQ+1j@befzsFvnZ(UkXjek|ad<0K_lRuDm z+;0bTFwNME1BL#uHc$e_Po6w;iX~Krjv1*H@4NbUX&T-Q)`Tx~(Fjfe;veileFJ?+ zUf(<}&|a~?R9ryS2L-C6zt1Q*!o683O0#d$$*)uV6A`n*%v|vM42Ck;e2=U#!Wst` zQV9sQKzkymjVMpLOx)d^r*EkTS6QEj`TbVGye#pzX1MWU*wuxJDn z75mSJ(-Wkqha+D!d-VlXqi=k=6dWo2+h~qGL+h#kr9xXJe_J)Nw%i=nDdUY@cE%#W zTc-)+$RMARzjoQ@EZ!MhRXzALSDo_AVWRG^#j$@^aNyKBhB>$JW%%&#xrD|K^j*D5 z=LEmdt5X7Y^&bZ#xl1c`W2mb&5WwLa;#RUvpaK0j5-|u9o&x=7#X_BbKP_G@x9Hv4 zZXh25y%DooDKAfirAMs1|4WFK_3p|cM!VeTuBa)?N(`axku7+v;yXL@m;d-THgovf z<}UgX*?EDp%bt8Z9TD*Ue!pD!wd1l||6r>PCG#3w+roa9@Eo)YM4ObwL1q9k9FVS| zxUt=ZmfHoS>V;@3y?8$|9mSZ^8cq@C`ca5}EaKBjF1jKWaG^1Ln&xF$r$RyA>*rK{ zIB#Fbi9RWP5DEQtbDB>x0{NEKkjUvM%9Hy4HKjk#ROYtT3=SGM1&qj7n80)ddwZRS zJM5=B9~f-Qvc>=$wT^JuMbnJJWgzbqCJym_4Z1YL#S8U6$DvpJWszz>>0Dsu*tGV~ zmQ72w$E|_2)y_U?#{w@JuCL#0Piw1{q>nNFC?PgJD zG+vN!E_`!<}&W+ZJ< zC^$I3-+jjF`E1BvwJR);>l{}GTb|MN&9SG8=8$w4L{&J}&S3U}ko{4u8$`$aqj3n) zY}iM*e0SMUCbxe`tu)Y=MzD4$!Uo&9D-emjO&+?PNg&ZmiYW1@g%F%(`fZ;vwK+aM zC`N$vIUy&q`Q?vD=>^32!lRnCzg4i)#cfKv!tM&napWoP*mfzoGH`Sx`qXeY0lbEz z=eY5{zeBS7##6`E+#gZEn%ruGw{l#2rhsc)7YYA#?j9P$D<6+v>MFf-H~YuZ_DRu^ zkG}hnov-H~bcA`a?ltAO?dC;8?oP(rmt8D%6m+X>zj9JtQ%omo_*U zZfMaD z-l>AE2W~#y0i#EbGL=rDaNl>#IUnW{ z#OCIS4ekxM6*;?m11eeWK3meYbPie8ov2P#DSJ$Q6C$(C(tIcsP?CJElaYN}imNOO z@XzqR#=JG$N)h?#%*n@~AZP^gxfhp!+Eq%2$9(1!9h822qZppIw;g*${?otTjI?y^ z>NWEgd$AVB`;7cG@`VL@U_G@Ou;S}m&r~*4skhw|x+)ykb{)zy6^@wU54d>L-Z2Vs zGH1`;=rXt~|KB}(PTn)`I-{`*LWt}Z&~At$73jZ4xjkWs$}gjM^uE4|91 zGFtX+D-Y@prBIyFhc%7kNRP^_y~TANFM+4nxt0cq+g8Y7;B$OkBa68+=t*hde+0n) z57-8b4^2f``h{@+cV70bp419*BvCzrc7(jAnKa_kX|crLJ~9 zYhzKL*9%@=CW(@(Gg=gELD(b<8D9l@E$lzW-QAw}_~$+o;!z1PdQjvRgautK&?YI& zVbyv4T64J{q7pERMtpe^KV)HEJj(KhP1IT&rcIO!vavTM_=b1_}|!judt@N?_D$$F?0~6iUCmpkuDtxMFkrmy$Gm? zp$LdbhkzKsf?z=rDFFci>C(F<3Mvp#O6V9PHIyI(LP+4u;QzPx+2@>_bFufcFZRvH z^SRcVYtAu8dB;0O=6VHr4)Vre94NzIC{tyV4H~N98Y9VGVW65Ox~6JHDls4#8`61V zhkj@W=fsxPg!p-eQu+*989UzZvmwUNk2v|Ta#;Rz0H|`R#00f&+bkMfzsd^9e!~X( z`wSI9ZuvjAkMMsXd-DI?J^4S6PGYtU^z?1HAt{cf{bKn8gdJF4_^N~dcHgN%Qrc8l z20r{93_h6dwN4rdZ5wHhR&P`Ft#TRE#jn;bS54z5)JpMMqq&(u)Yb6OHss`wKtxo! z?~6g@7B`3Gl{-&*+F!egm22S|M;0%)f9UpT7`=uJRtTb_2fTymRI=BWp`?ZVbYwc- zez3Z`EuqhT{EpqTDThA$^DT=#ZC6Xg%uJxR>z_#GuEj4~M@KgOw~2c#RU&Qbtk+zt zV!JXrpsezdW1B$>8i;VI$T8oM5@#L>EddOH=w~gbuL&sB415ap}ms`3@dbE65!4 zZd3YB-T@?0kN44p2AN}it*gTZq&%G#Fe9)jBeji+=I*`^v zo{qoIlWc6steiLXfk!qko*I)*@07D)m<`>vG2xl z$HnAhuDkfBNAI;>xxD|(gf){sQ+bsN5DBlo%8Uh*5Fq-M zJD+1OW{xVVi3tqMOrL9E<4;1L)NSqteb0VXWSSL-&dWZBnG?)zy|?!~S83LKfpW@N zPzS4^Xsp2TU${Qma@+G19wkv%;4?d%<5yfGvQ_}j+Mnag9n{h=klYYhQ#;C=-7BYc z?Ty5tbPrLqm)^KRvJ9hS{cFR}$NM=0$r9$Erz7_lt#QJpqVwXO_vlc(v)=gP2&ouZ z;`I@VvWy3P54y!E2Dzx?*;@sM6rs6rbvIHlopZpVgw*Zu%F5V*{XG*|edk2^Mf{nU zwc|ZUkPdEf?7Uqt#m}U%J~vK`&4U)zUIUzHaOPb;F9(XdpRCG$>5~}HEi#^+(rVkF zN9~SYkbJlH#>$+jO^umvH{J*Uf-}3dOv__IbPA6-VCF{2tvP65MRDI_WkC^I3|BX> zZg^{ToziD(y)w^qq%cjwe8F^uPku@upS&xh{@&M3sT4yf?``~?wQRN3%;@+`@4P7w zY@@~GJsMS}bzo?v<30M%V{;i7e?LgR>)nwx_Q}_~L)qkm?h^wGNoG!d?%#jKLbDH( zlJ*>)xo^oToidB-E6{A}xlOSS9;#_5vjXs>>HYy%p8_9WfBS0M!@Dg{T4wv(T03?e zM}ywE-gOEb3exf)o}ZarIgKr|HZB?$zRF`<*x>>skoz(`X`WYfhGGbi;o@#ELI1gi zk6I33HRFN#Y*QOVNi#2l2iu!-mJ}kKf5sap{F8X2pKNOx5WQ}|uX|R0scG*4XK3lsIdCGrkAHnXq-XgVb_ET4}G4O z4H&9%?*9C5WNoc}dw@7xn)KG+V9UOEY&?m7fe{eBC$Mh}{2(l%+DiE#z)%Dk+udZN z^653a_s3oK6ue+AJdn+Z2R4IHH94G5dl;7qNauB|>3ihb5o}ojfYm#ZPd^kZ;kc#Q zr2jy7T}XRUbwq{=*|1Q}2FP1Hc+uui)PRMYXv>E7Oy%1Fi#(E|P28F-9E>B27^?Zp zA^aJjc|gvV)mu_>Iry6FtmJ&>-u6ik^c-`zCkU0s66z%7LiV<8_B@!E6#zq>h4>&>M{7i-wt(wbD_P7J%0U)*Pp=l13+=zF@Uz6OpzF9(EfAVaVrM&F}TVhg- zw!}N%-k-j;{ZU_DBy(xL1!-f|OC1#}LoSe|@2d<>Bv?jMto?^-qN*obwQLx9yiIl^ z&_}3UFQ-XTfAR=L!e2*a*AMWcr^xB*{j6PwzE6!TaKCa~;&P_2Z}!$cP=76xoos z1euo&^>r>Jb(bQ$GJTpZR?^NL3@+vPw`BWE6wrzaxTM=^b%A;!nSKOUxEQu9qOMPL z0m4%Q`hi3ZE6JB}No%2)bpRFJ_YSpWxiMLKy8(a@wHHQsUT4iCo?pYi1plkQ;M6EA z=fL>9_fY8QH!ZK+m=>tCd`#D6PQY=A8oVEs4=+Dz1J5bbD*F4>joV%-Y9M)#85u3Q zBX-B!0;DJ)1-^5>0jX+TCQkPo=+Rk~Ui*Yqsy7CAUBg#GRPO&MPZ^=0{W+eim;>z@xa`()-?k64woLkLIBQr zWX@?Xren-C5aC0QoS=1~6+mcHf`g>%8!&zE<3C+QX2S!qNf8V=1<%+6Z_W?lUaE)t zt%`G^R)RHA2BG8Mwq9BS@}eW6rGRuvN17O)?Cer{u;j-D?L@bcOa z+)|^-xcz!uSabLIrjUqR`z=ma7ph(N!Q8!y%H)wQ?MJi&0W)ck z<~keZim#2nb@6Yfg9VLx9J66&lLJqIS>0`E7!~8zQ;(Sk9FFf0rFUM|W2nZqd(95+ z#m1kqx%nW6J+Uf~*&bD4o6Na8*If+L0o!n3x35WLq@!iPLJDA`g0%{g^nk@YAix%9 zn>^046&27P0x*Ftf}JGHBg%INbK-jQHF(`O*NSsgp0{bK6ls_KN#vtwlO3naTa;w9 z6-8)1JkX7lR>rEg?LetQ0q3*p#I5RHH)Q%zsse#|9}Mlq!4|@WUMYsO?5S0+qvh!F zi3J}+P3-(F9%VdJ+nx)41zIP8_fQKq<1I!01hpk!_A_owZ=N1LR5P*~!8id#qlR_= zQ$ZTKx@TpEl>>BH>2hToQsvxbN4Kq4-&zMEyvyw0BR`WXr(wV-#vLVAlMV$-7Md9k z@PkS4yt!&d8&#jGAOS!~bG#=Qd>AzbxfAl?{IK5H{KU+14U0Tl5vc6(*5ko8o4-fq z%^Q{MR@DYB7VSDhU~;eS9|KNvU#)48+JMFPV7?;cSfE*D#h!MDNNCHlhkZ!eQ}u=L z_m9op!H(CSX__e6tf}h)VFG}M>&*46vNE&ExTjBnf5kZrrLmm+0%)^^q15nlv;#$` zRoHCUsCLtSn2+laDkW9kgc9yAX6qjzQp%NfM1%jfnCodUE)bgnU@`;ylcz` z1rT3!Tj-aKNbr-?qi|Ws>#8sDPwnPyN=S+Yv^j~;?36%POhk9uggW^b=n;GCEcwyZ z=>~N7@TuEug}@0)5AYM%Aem?4pAIf*$qccisFAayx|v{W9eX5fC`ivgkG8qgwEc+8 zQnA4&d1BEzbR)!t5~J3L)sz;3N)^*o&bBs~#MwG;YGY%+Kt8yxPJ*aTT8vT#omH7% zY>g9UV%zPQ7L#BDmuKS#l_bO3LIGO$a`Sxr#A9kVRm1DoJ#hyn z^=5gzh33fLg#6Raf9me_=lpDt;Ex}0oO|M3A~sqCSqr!3MF{%lOS(EIkKkG#i(|Aiew_QtW-8ikJyNH9!Q@-=7 zLRlbIin;rK&Z}Rj$M+~iKZdZzNDB)Z2ObRewS$A#Csrj2s2w`O-xSQj3t)#lKzB>i zH8XhSEON)*m`shWK;yO*WptTsHtigvmQ?f}t@*SS=!EG3P#5oN-N)nx0oWN08z(#V zoQAL%X2sp@;4Md8`9WA17OTgifh4+pLy*sOm_O4Cc^Rgq9cg+y1$sIj( z(@hC9+wN8HLt#JLJ42LrZ|2I8;s^N96t(3{+RWYbn|6Y2tH$+xE1 zATg&@CIx=Z@3Xx+6tv|(UqR~aU0!E^ANlEPy=RLtz8P&^NNzzUu9`7GlHr0vU>`GLX$X%h#mIR#Z-_WR+K& zPg*sCSWYx6LNrDkV4!~t^cm^^Do4e?gyvNZGg!L1xA6}oySX7t==^(R zyX#%?V!)(fgFpk{gucmF(Gx0USNJ(*q`Sl=73jj0+?eFdUdy7#=2$#yTtb)@AbCK) z+)}**90BvLr3oUB=y)lGAIvO-nVCvOF1DbX<_^qhcFdB%la=gy7^?lO;x94^T2L^ zlGojV{di86kNbsJo^YDPyYLqw-+=UW{~a(t;Q({bg$fdO?-M502I=_U26-Su(5dKh z7nF0--q+E*@*dwfCk>JFYaI_b3vuk>=4o1LB+-h|@8$-%A#y&B;{oQOg&=MM;HU5K z$z?BCO@4PcXcdfLB!cK_2M1#_Tf&}*p@l|p6(o>F^2SI#1f5Wu!5tnhci$K+=z{7( zmd|fz(CgOh7;iagzXak1U(($`w8YG_>ui#s4YOMf^~dMl-*^`v{|e(~S|!`VYhc-N zX?Dhy;GYv*{2PDo0|I{I4TZd`c%WD8#FC=D(7628TA|`FUNr5cFa$KJxygd;sD38t z`ap8n53dpsvR7FkkKQow>v=p)nx?q?D|g>GG3p6GCwvCoM%CBf_H{RdqObLPScoGe z=FYU9N>1;Yf+(PazwQ*n8bK$YxcZ^DrGV7qZj#E4%XdZD}<~xM2%dX#5Sidc3L)-OJn;Kn#~4?OgUAv=x9{bYHLAIHa~f z3$2J1*IXEZ!is2KY@TQKu^0waG1^gM*YMl34Q3P}PS_a;%f}lxBh3rPDtvt7?3-!N zFo=B7TwaLv>zyFuxCECvk<52C@bOt~$jAND(TD-g1eXFEIFC6bW)5_Z1{czvEm72O zf?S1CT`*jVdUnx>^SvDRtR|5M4ESb!3MGbW8`nrETDi@?HVY}xmvbq)&@Wx^5tMT&;tBsLnlWO zOmeY|7zu=Xvvmd)&(~CIeC{ZJ(^4^VjN6q3c+d3=OI(GIjwj$<#0_vKnfA()^8s77 zb^q)et!h7DgP?ZyX~1Hnf|N60v5|5IsI|)Ic{5HHo4Z3bDiuZt*FJ`HFn2@J*qa-4 zD)`(>`3p4i59F$D6_4~w0LC1_qI4E?RsJ}?f50@L>U|?iOzR_>vjGL|yT=&@l=0)d zY^dM~fEZplef)^>+TE@UepcXls2NX%I6$#GDek#MJkym$n13xte&=g4=R1n{ss+i; z5CiS7^|ZO2-#-Zh$y%qK=egJ+`!$vY#6dIyIsO(%CgUn0G0&&&LjM>hvFJB0kY$7KV*86pK-Zy4VXX0I4;A(F;%=yO{d z3uuzQrI3^H*gS!!DJiJsA&CQY3n!9LAbJ3<>h%WC2e%nAO zj<|Q6O^9iwJ4^L1S0fqzK-YXG03j!F%$#YIz|&}&T)^-7w@zD=+K$ne_DYlI7m*`v3F-?6x=W zzv;wzpn101|Cf>8DFFlT8b_MKvF%EhtIJ(<389gKO<=Jq04H8Wi#Qd5hSkgGr68}r z(#wUIIq@G5&eSjiJu;vJZ0O-!v=wB?U%eIG+Y1aA7VK*S*Fta3x+CgVtyv+{jG9x< z;=xhttsS#>*kZV*;in^jtWo@sevQ@g#mn~-Tx4zF@IY|gZ)C}W9rCnG8^r~jUHKlT zq6^HE>*IWPPC#NRnDPciqfq>4H!Qc47c%YLo=fcNV1O8^q}#H{JY3P_<&(XTBk7w# z#&e*uZx8Q@Bz7E%$Q}%4gT$vXGHq>3XpR;UpslL_JTL6oYEr$WtlP5jDjAOSt$D%@ zxskrXK!L@%Av-%@ZEb&rSpkOG{D>-}h4slYXYa!7*ELOB{gnD6Qy6~|(x9;;k-39#M z!xdM{dnNWV|1Mhs$v_}Odi#yRAILgioB;R}(_#YJKmX6=|E}nq4Vm9a${%Ty^TG1BCaWHsjC>Y$FI&W)%@zIaJBp%{HD_Z-nwZELsCnO z_W>^jf!Ks>T_~$g+Hn7p>?S%C_~r4wjh4n}*BmN1dev*<^KaQ8J()c}6$2gU&T=Q=h8% zl%0Eo9(r2$t6Ba_vPy*xir&C%Ua!#<2lPzu9)K!l-~+CuY7aKQoS7N99+h| zRXH;FTU3?}9cnURlT8&Y-Fho+Vw{;3q|C0 zlZn{XWBcKs!c2wXIg4E<3QoF1WOQF)o!v6%!kM-a75Hhf6FZJr7e{K-GD(Z31hku#$TOx^N+o7kV49o!z?E zTEAEj${YAf_3Y^NtMuOG%j}o#{kx$t$c6ozn}8Hg*o$eG=~KwJotNZk+q`FbZ^(hu zX8^=^ZX3`MN^zn?5m7dU)Q2vCLXEBnS_D0`$NF(=a4T$^VJa7U?BA@;(MRfBTQ?ug zSbed$9hw1zkKba)FW%afV}dYzLf@$fw#oJ=yXZ30Rbxt{SU z4AnCg6m2G0tvF_R0L=PJGh;K=r8uQgFQ4l8{S=Z`HdX1mlrF2bpKQ8AzWgX#@$IfE z3i|K7>NJXBWYIz&Ug*W7oa!4B9@f~%gaoVKwVa?Y0 zFZ{2jM0URPP2|2bnA$#dKmjbiy01yhm_*+hZo=PoPHJjhtqJ>!OAWjs;dZ@5rY${0 zH5DQqbA*`qg6ETF*PpWsf%KpE9xgsb5srUL6_vPuLqg>ZJk=7DMUKcU)cq0-lfV|H3jTf%dQoznr^VJEPZ2x2axMtD< z`2}@ZPK%xwCsdm3MKGvv@y*ZVJ^b*ugAvq+T2-IOxvkOdap+KV zha|FnTuEyogM=nN9ifrIB|k(ScU`_yhyp}fPU9DR~&k%Ax(o`NRVEz7?q8KEoxNb+#AU5 zdnYRivNNX=r|xD(m__oM#-nTC#F^d=a*A`uG$TEVyx6ur?0nGfvDDqu$D)z9*4R8t z2?Zl_N9cc&uPG8_DaK(dWOp}ul9&i#<}1cxpnJdY z_;!r~#y(Buj8+)By*NKi%*cf^4hJ<6W(w`XFDw*VM?a*fjXA5+KR4=blZ7@rYoC+d zIbMI_!1PpxO)6wbG#|CwNQ9LutJ9B^ti4MP)He3u*@&DhFffIVKx2E)3Lr6)T$)#! z!Uwfy=8NxA)5Ie`j6R(gLaK#}EtLu(b(^}%W}n5Q^SC0i z6-MrJmF=fY*z0eQKZvn>iqI>W7K3Nn|KNgyulMNbMiedTO@vVb>-27M7!R$ z4N!AVg_gyTJf-?xosf(8yO0?2JQ#)R_A<9f8b63!%_qTTaeY`G5=!jKyDVt^G(Vw{@_ng|UjR8mBX2(V;&? zi_`ZZ-`-QuqO&i`iQo&DaA4#CT*GL%f83d@l@}j=j^_Bcl^jBLec?+{J)JZ)7_!q2 za|;+c5o>w$pS}9n^&FBV$mR~$pwRu?Q(v&jQ7d{kuUtw%o4KX)z$=M|#E@1ZdSChA zM{>@LZT_7Z>knF*xpIVVmea0Wwbk!<(SOPoWAWb=-(lKm&U*H1Ib4JO;NF?y(Wa{}kLSk~hEk>36ldnjB4(Yy z>2JnR)~ItV^3tKR9*D5^p5Y!~ja^DDYkQ+tlVPq4UyN1RbHI)e{P#$dxtxl~2wW?0 z%k$Hs?{{91QhPlRj~@C`URigO`Y`AW^&z@LoY29ea-Y|WAlp2vAcV|Ym3{JJnR8%+ zt#0ggXh#7G?U080C7mkC!LLqdcNa}m(W6s44)4jWVkoz)!nZl4XUzmqTvBvY+ksp4 z!IY8!+<^TYSzUvAqfUAN{*L@2RIT>F|J^{wE)q;7w?32I6@z~*nsLJA7Z*t0Gfq60 zGaLC=BR0ICPEz!{u4feJvpF~FObD zg1~8hFHCZ!tlHBW6m0RWa=>c#PbZAU&-4E0Wi-$$FAkaK86>vds*K*a&-fdc<1qCA zV{!7U0Md>$t~FT^T`ak&j_h|o2ZigQvSm&Sd{^1zr*Q22OfWe{@9J%?xKFm$rT;0IJMuAWv-}&FLL{eaKQ-?I4Il+ZAHDD6mg5nIr@Wi zvA$14CJMACe&>M~eKJwf)1X5MXT?kw9B5njqqf`9NNtnktjS~Sk}|QqV^H{+be$1$ z)vt{xrfW$yQ$wM<$m-K$CHnNwTUX9eIoDru!ilX4Cl~Gt9J?OncZ5!@;*(o;af{dv z*lZDOMfbr)R^%P!HtiF%}gGE!ZYiZ zD-?L(*BnpL6C>L#Dtch)!pLB#k*^f=$rZqt?5OOkF;OUGu$#u=-(_VDj$ z%w3@xWQrrJH$EK1p$tAFONJF>L@6T-L1Rm6sIloIvbvjFKDMX-7t@9AyvA7k{x)Ps zeWsjp|E)R-?G^Qk6MpWoWPJviSmWNZJwJp$fV3JJ#t-0XMBnNLq5G01q403VTC~Mi ze9%&k19`UXn9EM88TE(BIqJwOKKQej6VI_dep_2RLehmA>^U-O7pU^R7hm>h5D&k< zx{Be$Slp8G;e?Nzar-@Oln>NBdgUtRS@@C&ANV!VX%d#&DZCYe7DN7Kxfww~Bq8Ws zV#u#XQ!R{gG>N|PEV60n_Wk`xJ9;A8h0i{a<_e?_3{E+5Z24cq)T zV z#X?BbZFRYbq4GMRb)f~Yo7JP6$Tj$mm~`P~_M9iu^sdp=$Y;8(bwz}N&jH`DbzJF2XKut*tWhvDn|(-ue0Rr=z6J#yJIa*ic)q;DI@C} zyz7V)geb*}LAa=28&D$5?TfenJuB@y!w2-S_BIt?SDx3t_ z;4$@hSW6~=seDQ~{bcv?ztec$t)>1C;OHs0&4rGHnN@1mN?*|WMikv$50#IVG9X7p zn?qTRJTF0kgD|B!>e5fwPXCJ$8=@Hg9_nS7H!cGxm z5$W^)upc`f_*us7HhdC=R_yL(Pd(>_aI@F5KY&Sgb*neiXrJ21eRTjQ=5|1QX1zRg zFuyF&f5AR$N(^pXAMoAh3QY{oAUCZ~B z-%lzpNYOuYs3EB5z~Ma4YT{u#_Xp=?C}YY8kv}mH2TfbZLi{QUoNy-~6vz>k%W%Pt|Q$~f5Yg=AK!vAU`fcLCF8 z`O}8ZSf)+KNfN`m-fPSsK9w^(bijQ+tDl?v+4x@~^B{;t!pp;&U>dbED=QTo>dXbl z z404p`omcp=$&nY4O^DH~dOB1ZsupW$#KdFIm9089G&MjLVje~f?rgAq-qDalenI=- z{0X~I4s0Pay+)sC`kyR>ID)mP?$N;}kKn4w?t5Neljs8(&a0O=fR*VVYz<11OlQX2 z8P)}HPIE0K%X(Y>JCl!UEuh*=nD-haND8Z8PbJg8T8hrOkc`_w%_U-IBDTWHD>jblaS?Ww~pnqdOHf^930Z zl^|cdSYiL$uC$2lN{8UzKXHD`k&j6hzVmr;qE={TiAsjuty?{GR!R5* zcm&d$q5SJ8lilkTXTB8@GcCX*z#u0Rq?q(|whlX!@Pu?r?~>e}d`3)u%`kBHeULXM zOg;(Hd+`4}`oFK3GTJ_0;7eKMo}@ot%?wly#Est>oK-9%U6~o{W|%krN|;#p+o-Az zbU5Q*U`={38XQy|wH@y>8ZW`9k3&xHfqvxDIaT|`0UfNL`G8j|6)uXH@cQloEK8u|}^1!M(dN3-N zgSUH^BVBczAaX!4p~#gQ<**=p!v$P}J!Rt!%gqYu2ddY{hvMi%WT7O}Lo>e#ri&5V zZ|J5)rk1yeaO-4!~j7f~Ho*>jBvvL|xU z5%5As0wN?X`hy|$vdKdMWJ==m{hsY8*mM4v5vZ{zPPt{hT}x-id}kR$_;9xM_Fc@G zH`L;2BSinDe`(Qik-0k$_9?YvvEo0mham@@K0g0`EFRq-Fv45ef`64uhh-NqlKDo z-K19fg>@=|wA?(_4sz9iUHaCDscQ(ag)xf%&2mhcjxxeR;qoFgpK4Q7KVvP1l3Y!7 zgA3x&o}q7)=?-E>i4)*g5eJYZ%UiP^PgIXaYMJ@>D8EI^Kwb+OLDO$fevz;ck*fb0 zw3Gp#0OPvSxr4xKs(V06k@9#u%Hjv{)s{-z z&FJv{JgB?>Ao8-ufFgkKz!C2p+OGjv9rGvTT(HeSFN|Ygo+$ycfN@X}l|VL{ zO*Rl@J@V^ZqG^feLK7=vR1RWq6Z=87bCwb9GqG8XNrqjic25UqUyPQJ-J>Qux(_1P z!mm*uPCBIqN=!r&5=M!j_$q+;z0?#+cpf-D&ItH3+4xETS}os)mfs>DHvo=?K&ECc9HM%)XoHSf6OnG@{Ti@OB%_A$tHog(8RzxPprAm z*GVKDJ?L*m74!=WL6Qi`7bi(FlFm!&$X9?Y zQPfkVcU5);6_HIiSS=-tpjAyfzvEH?Y@QE?b0@&A4a$zpuo4Q^&ifl}$ukZ43R4^+ zS-E*+A+ebff~?&!X`n|$79)e&$J77m1%P3%qVA_9flLyWp1pLf4au{bfUZbHE~SE8 zH1gGyrJHPVo?!ub%?;jM58kYh8K||Dnnm<;asDr4*<#j-)@fu8GQ8$xRNdm(iiibsVMuybx?Fs`IAj!0?o$AkbXa{KBcQ!=Hp=xH0XZOmQh5{HnVv52k88H!QT!im?$mb5=#N;gr>iW4@3rvV3-{_s2j`4cM@i5A3Onk2NQQ6)b z3Fxm4EHP<IIC5YU|cInRWXCh9=)X_r-%U{>QQWz(NI`~AK1aghC^EBI?}8B>3--V;S0{&e*gb?$H!@IIybM8r3+m|$SKzdNrqjd!7t zdZ`l3T_NmgMOMN9eNY;NT)aal_;cR>{)eKf>&A|d!h2He15qN%83z4pC~gFuuN#=rnTVA&*BZBqKhuwlb9injOF$SqI(evsA_l+zu26e zsg8fe;7(HeuolsS9r-RLuv$Unqm)bm8&eL^jjdU3D;gpG9j59 zZz8LMO32pz@k%vLz*VIm0%0UMxNPdSroJ#Ka<)T72_$6G;r90t^b}q=CA9$%poeFm z5N|1{#zO03Em!Bi;UOID8jeG+Fj4-_5FUp7^Ek?j zr_vo%lJZja~jtiB42+pMnHD=4%*`Gfxr z>a(N^y0w6afr2i3bm)Uw-*fs)6n&zsG=0A|8loZ_+bg&QqI=|+PDoiaDp=r|^81p; zd`!=CU~~5$x1G|W%ZU`79UlZaSe!WcP~J+Qwn6md)#%+&|Dt_-B@ta>2x!n-z~djD zS^ew-gWNnTplb{Z8-If6*=fM>0q()H>FK2ZS04EHxaLsR(pvRss(kCu^pU!WWN}Ya zKmiIMy~NQ8}Aa1B}X%I9QE;4vccR(U|&>3CF@GN4~V4+y>;Gj1-D^FsVW)x#%MG zNAf4=SmJeG^IV}tN6Ug*w4R6t0OBZwjk(jNzhugrTDitb2&S(o zKjzz&{!}qp8l^g!D~SmS1m9v9a_#nS$%MfKn_wX1(>R$Ps?Neja{f&!U{22uzl=i@ zou)^oGJ8;D8452X@G#VOh&k`gr8ONx?-<8_kst(A`tTx3R!;&p8TyiKcj)suxbWbE7pYzU&%7vwAqf#0E3syTSMGOpT zQ{Cd}rqE3AnlGshb{$0tXoul3Lm_?+F^?yP>KgP!T{NJO4$eGu5{68l6&QKVe49V8 zxw&Stj0;sy#PxF+Jj>Ssu}f|jcEHt`VDfO3nFj(WqA*WMz`K9p;_;e+Zajis-Pjf6 zH~jnFF=C|Bb|P8|^@IXSGX|xoQ*EsjFPtqG*y*uHgka+jvRhOFa^6+ zT=fSyBbIC0IKo*U9-2W88bj#dR~o4d;)a9DKQj*nY=W|Lc)phX??`hVxK7=1){hyW z1W0~de#(Wntf^Hz;{bp)n~eAXLIQ%0ilTbdJdX4l^LCV{i++;Q#1#=txip-bE&xIC z2!%6u66>phO?HJhd*YQ7v5zSkOpON>r4SyY@iDSYf+{o0drmRag_ZKab>R9%9jY7u zyS9T7{sL+pR&&vq+}nu*Wc1Mtvl&ki*Ph*s%5!(7i@|@;WWyaX7I()`Fo@iJscNeo z8m#5Uj!U+r`bQp35Ww=tx$BB+xvr<}q3~zBxZb&GD778EAGt5~Q_ih$LuiN2K>`TI za1I&KqX*O5{Jp7;chX2vnV8)OD&N{g8RkDX^MjOaLw&gC7eU)X?fX3OSqCp<^)R%w zw{6>0nR7M%021XqQQcU{y}7`Inw^VK5hCGQ=;(J8tT<~j`H*=tv6uCgO)UXIf6yVq z2?fAO5C6BTpX}frj|Sw_f8`O5e0$co{o0gzsNXoBP2^nEL#F|S=7MuxyH%&NkS@ob z%@^DIJtIE*D8}Nv-c}J8~~nvrlyMbP~}^?YOHaWJA0^t%B~29XlA9>-y+0n$@dEgLg}p856nYP+-31rFRXIkf=Y&J%0W11hdBHDE08SKsYkG5s2MRmYk!s&hhy!QO_(71} zcZ`Mw72WV&@~Ff0G}73IZ}*O^99&6+6_=>K6C@rYVlTtj>ak93N+KXgKQ{N#jMQ` zyz1=mafO!50WR~TP_tbBO7@rrz^tyVg1r3Kd(f+}i-p=s?%peX;;g6;hsM@|-}Nd* zla%4%1AsreDg>&j4Z^XtYl$%Rdg|!Uo5$iQM1t%>lM^-UZQ#<+I&c(g1jBs~ppG=b zz_*v-^uzMeJY{R{yO`vu^Po7gzcmgBw-3|P(?-ZmZq?Oi(nbe`VlB^XY-5#mmop-| z0Hr*qZpIX_&v*^YFAB>@cI8aw1NU_#O4)q#g3jZNL9S7-riS-BP5nVCKTaQ8iQj^? zoYGeVH&vsgY|h~`c;kVZ6`;Q&t%?}_K!zr7YZW# zgS}B`06OeKrV;e!P2LT7cxvQbaPvnNBhRz&tqr#mt`s~dahE)4Yl&ngveuo)Kz)1x z44YE03GU3q&KC zpGbEMWwK+22aP;Az@x5oP$P;1js}o~g?H`(L%K2@9+I@Q*#W-aW)+&kycNuyM|WoF zZY4Pv#Tmx&?X|o(6U8z!Jf+mzKI3cT!1=zN*J4uO=KaP3#}^RW6T=&^9M>>>pqA+B zSe}V%kZqmHP0rd#W;S`fj+L_M?V*p0xQ*8YUj&BO+EwGG$pgnncA7e}gLOexwO5qy zsN$ISpqH4!khF; zv3U~m&Qm!NQP+bI$oAxefE1Xdb#}2b??STYux@Yc%qhbT{Z0csWa~0f?Z0vkPJ*c- z$WL(M;eVWWx?vN4z&v8OpvFhIePPZS=>*BmQCMVzr^6{s%zMuYm>Y?e|4BgjXh^&X>4HZC-9J?#5}T09e~p00YC$=u8Zic>VUI2EI4xOUeA?aaPcD-sEBTA6ncF7ULCa*=oDx(-;@NMnIm_JYYnu3H|MOo=)O##+9M zaHU|J%kV>2spmkxoVx$%T5HQ>+YnQs6ifuZ_XmwHGQ`(I;!w+5W*+vy36*x0$(Jr) zJ%RAuejL3)wcVW_kCEJD_X}*Y3JJ_dW-NFbFzCohSvB*f#PN`wkg59R+hD+tT!JXI zAW-$9tZU0NNter8>rA$ST4gXoZDUNr4PKvOu3<1%DnrpT-x_27x)NgQ0%*(@259%*Ge24ZZ zfRlju0SbH`YppLZ7A0LO7hQIxe_jxE=d@phGXrcNMC+DvO;=geRK}G6<{Q8@HFovm z&;Hc}9)Y@*9-aO1na~+j`Cg_~a6^s7bnz}t8h+kXLH{tJdF`n!17w%HMBJr59LM1|^}v;w13;KhTV?v|@)2~0$C4<(@by&i zUuPQ2V4_qCcFUk=8f0bmROvlT;YIx$3^#R}wJ_-wHgvDI2-2?@F;F^PatR>&nmcBdz z(cO7vqeDPXIMD6^8R%!s6DhC;+E-=^fl+UAtwl!5VL|4q$HA)K#iKP&fsVIVo+|s; z4pte1k%stUEtCAHr(S248W0g>m!#aUnuUmgllx{SK{2}C;yGrckKSSVRj0V^gvo{CkcJ^_?!{x-5 z%=q9VT}i#n&W7Mbc|wAtG`Q;)i;>*@olNv!g%+1dt1VCxCFd@6YHQxyRl#7Og7~(* zfh~~@WT7qdWDSM9jor%pb#9%5^E_w4o514UG5Ex$j1iEDlEcovFa?`4Hm3CTd6=Du1D{00>reNNHYU(jq<-zicG1b@EP~baxjkWX2 z@+j{-&t6p?FKjTj5=E@R^eBx1;R!uwzDhGjD#d6E*Rv1YhpYo(AT}niTXa{Zy~4n2 zd@A+fMlmTgwD0WX-)T^L5V8{dujdGJ1vSI3Jb<|drIEJJ`!mQy(>I`@cOMj9)da#dJX`=*9BTq_95#} zG2@X0Sb28TOo!9L$0tyDO=^QM=(5lkBP8tqkKja4prh+4LH$m$I`x82k*l=f=m;T<)Xi&b&?H!aM%Pa_fW2oO6`+wK@a1Rp zeNS{D>Qtj4r!vuRRQOBlae6s=%@f3y3FE&MPQVyH=|Wy}#tJ;eL4Hq3ZyCjJ`<%Pb zuKPLUAqqIaFF84zf(r(JQP!7U#)#Gw%nUoH+&p_0ng;+25%BWb1%SL#!=l|l!LsHw z`25rpC(@Ps+OL3lD@#<@`o26G5d`1d;{z)a2<`#tJnMRF`FIg@J%j<6zX|#NAp9dm zOkhhMM1g=|X4hwHYIdgWh*aHjr1Ed-;ADmuM~-3h z6J#y!sX}W%1hR3h>RYKZWK*a9DHixAPa+nk&MQNf zBe(zTrW?>{@dpw|*Q}m5p3cz#!VaBQjz8&T3k`=}v797m=@KE8} z8@l&@c=%tjVqW8qMyBt)bNp*Mp+xx4iDl0|qo^=K$EVtv?SNC01&^S4lb4kJqD(UCAd%hJ^=U5RG$zn${Y!gpIN6RDtk!_) z5*v0>YUsr?NXkb1P*W9enh z_RiIwpE?bRx<)WQ!)S- zwg0h~c50`PGhY&XH+>Uez~ufuvu5HYI1Pf329S zb?H#1u&5z_lh@_AeIXF99J}~BQeBD?T=J<5?D=wB&#LNnS_td$q0Grn+OO9I!wn-p zhQ?2F)h7+NE`rNoH-O=0)06QA=?gU?VGxpE^>}>rSw)B$8jO=R7--4b5pO})_JWYN zL)Gl;_;)<;#d9FUQJd1p2V=p%HV?q7fIoL`M^J$;#GwU`fdcz^O7+@D;j@tCFaTFS z)CAQ}>WSjJMdgpbXNS?s2!Jop+~DfYeFG;XrKPKl;?jdp8o$`-Q_<1OYN^( zfd9|rc{9%QGw?tKc&sNGv_=xlibEkm3pFp2b``|9q{bJ@hq$)~00VnCRa=yFN1bQv zF!B+x6{t`uo>Ih&8#$iD^o%b>%{BWKf}8k{${eZkSAioc4%uTT+d0(!iL`;uu(SbH zQiCLB|GVV(8evprVs=~>iJI|Z*bXZ-rdNU&Ac)+e#AY3?kGuqvaHQd4DItAv6UTbb z`vji&Ri^ML?cZxBTeK`y=o%5M-?&O{9;I!a@=a4dsb?3oslSVgp+zOT{QCBMx3Mu^$w9byKXrIAdr6yAG}*J!u7 ze$OLP=&x(Oxh6?@)bg9taLtH{m)d>NN4JZw#GkKqWP`2bOw4Hz{~qr6W)5xg7t50B zi#s2)!D_Ens9OcGcyNUxA>mT4BDy>)Dvk-kS%Uteud_b4!A0gdn$uX9Cyk&RPfJ7J zOkB->)G+_82O8=r`&TYVR5G^RUJeGsbo!X$B}otGp|yfBt+kNqnsJZ&%Z5J6X1r7}GqiX^lJI-qT)f1+|EzV3J{qoK_Es)@1igPQ7>K^Wv+hcl zYWGNYCA&BoqG)NYfl6;COK^7C6MT6uCuL8Hzv6phwO5{snH2xDwlRfaGPmU6wiLFB zl9RO9{8W8hD!kV9(J`09SK>xW{mMc{(8{NC=2~p4KiT)#9((IT(_TfQw&HDa|2wY+ z?>K>vZ854kZ)%%0xnfS^x1^`ne!XrPpv)g$i|y%%YuOFK7R|=O(UPJaLwmsbo~1Q$GnNp#i-i4xxv~bZH;DpFf_5s?yGa>i&5#U&l&1l_$)GRu1P(h;nHm-2+cgK z!vH1A68(L-qAadz4avuPle#YsNyVtb7V?9((Mt!GVT-@b*nQR`)?~jrm(@bsmFG!_ zD-J=7C&{8jRQ##C_LJXZH7tkfXm$>+$CDWRHc@XrxUAY_L$-0>{!Mva)5M>xiS{Z zJv%K5zgOb7U0(moowkys+l#FoOmt|NsTjpQqqrpHp=4LPT#5yT@cnN={$BRA7^Mq) zwZqvB=i9%hEd<*Z9pA}SH+I&eI(=5^(eTtkqv64Jvpy2iP(<(^p98nh_1Ze4173}d zTerWz8a5q~^EVf@Mx5S~ZV3l^@;;k&gFbRoR6M`C9Y2-FqS|<>dt%+$GHB5MRO9Vr zcgpL2anRzDT!8J5MS3dP@y#V2A83Z@oGK}DtQ0>>(i@VrZm+{HW7BD(W?-ib$AjyL z_`++arV(h{)xEvfWKtjCAjEe(-o$oe#U4dJWdg5n))t?W$G?pRX9BhMO-2aC_?PL1 z%ys$Fe+`(&ggKN;zE>U^EGfb zC9#|SOw{OV=$R<3uoMcMzTAtES~b(p%S9z&+-~2${49o<8NMvq*I^cf9+W z;T{bzWVRj|>_CxS%ND@7{_ojs%(@}S0RebaUAjh-NUl|6u?>M44VOXsUD&JLG+dI> zn>${7jQ#@?#`Ei@%`8nHic#753x!|c=lsj^TxgB3->1&5r7FfY%akm|kwm;0L4zcP zNLD+3_w8V`8!lR2^`eKS2&{6Q&DsXm0nYI|8pZrrrgwSC%6)N2u#AQfwVu%tik3K| zVMjd3tFip6tb{I5t9x#^g}il$8M_PLuEBza0m1|*HP00GZg@-Qa#@@Sh4)Y$m4D){ zZr5F6IfkYSj>i{^L*l$W{Kars#M zgFDO>z{6a+;4vn|rh4+;B>kgn$5ce0%>0W@uxfNS#V7Y{pU%5=PuL@n*xK_zT%KdA z;t~)=a1A|OU$V^0;d#ts3q4T7f-bx~D!Ht4*JboX_ZCV9VcJ>Yb80z%-?tkV6S}&h zi=?=s`@JV%u3QbThILa+FBFz1l=wBNm|eO`;a@g)!+5_YE*yu$t8%GCA5C&O-2TPP zxv+0wA@6O3bt=jxJ?{*DMKbj9bVAlm#i$#lbn<35`dVBJ_?v1)tO7DZ&ef)x8&F8q z9{+;h&VG+ef4m(TmZ{Lz5K!X7r((`Q4@LlH*UxroCh zUUo0ByY_ep7)~Kj`gUo(MMay%sIP%kNi5Qh>uKHtBD7j zFyK6b5n>4(ETe0zn@H2J#ecK?1wMkKm%|t#_E_~SYV50o$Gab3a@Y@#mF(UvpG*-J z%K`3OlH$6ILd1F8ybCaDoAZ^aIRN*N$!VR@aA(x?S;`Ui=oui7c5Se;1C2S74pctG z%}ko7AQA>M6P5eqpALkr$MMk&;~mc8v~#a<%3k~S263J&ub=FAx2IanP00>Zo6>lt zdZqJnICCs>ojL%%E50Xj_1$*8AZHixX^t%7ze>NwnW!30cI&L`MLo7(U;|4%i&pnx z4-E*E_dK*c1cOb_u87>St>4w+g*`KE_B~$tCA?hmy2IK{NnxqqEq}3I#uD~$<51Xw z<|c`le091N6k9~P4D07lq<9SD2KI(h?|&Gc#_u*bqw$X8l~gu^|M(ucun5cooMvZz zX?;aVt78@2`wE9^QaglPn+w*``svm1qSJF^YW>N2)kD}QmgOvJy%gtm|KUliiz92D z%;Zw}ub|s;M#M88I31^?e2qi4}6qyZrb2JTTDExoKa!MLvX`L zjK@d-6pS?WgtZ0|uQ?A>fkU`d`*(+@!&Lr(09;yOX=P)>_D+kF**NW&-cUCDQHB+1 zIuUmVJqp9T_s>npPzDoDH8ZvhB zhr@(J`+e4G4l2bY>gd4Q1664e_V2i+{C`_`neO2Juvvo7R8sDz}^h-zy*EPCTSrx!*a{Z>;qG zi8O%}C(P7u5l^>DKkK81og)(weGWldO;j}B+$JOzN||d`*W^vSO8E0 zjYTtc9!AIGE2L1aD?dZPVi8CN>;I?|WY(_A<)PZv|_mWY?ft1#0!_1NS0)?ujrSb?f zRmVcD157e{cz`$R;N+`13V3$_i&`=ZPY2-Cu{2jM=1%hjbCz%EW4?E{#rC$1tJ3lb zcwvC?T7f?9yAahAm-??gM6*}k-ES%d;KU{3L>V7h{H3`u_blpV!yMjUib2hL2^X2a zQ6li(qdDkyj7&(x(Lt(XkW_9W&D|sOD8|)B)kZo3xo1n`*SW#kOx?m@mqQpawSzYF zg;)2lO7rI8qkTa+YS@LYB*f_P(Q(SjxJ4L9IPj&lryP*@8V4&}b|pt7WIvR&B1YL% z^M;axGx2KcfkKm`KLINg4mmodXKWSCLjyk@eV(z2Z*G@2^%wM)OkX)N-QXpcu)gh4 zdn6H;MqaYRUf5JL>Fp`dJ<}SEpnq--SdH1!ZY>_ZsjO5TDeZlbuNUe5yYDz2)_KsK zoXvK#cKX(M0;Tf#Gb-W!Zk7SxakxZjY>B1mzGayKBEUgf`ZEw8TRbEuYq<>GOy`c? zHPA@`NRJ4aB5+&PzFW?u9%;Poy;Ezfoz;G`k?|y>;-CZ(7YX%Tf_k`EeIsw?)hJP} zgk4-yI?G`5@-{}qo`%cq?#}-6F!Z->czRt1FbOQl5969+;Ze8o-6o)BE`8pYsNNzB z9x5#te4u`~<#RmcEw`i__T>VBj>cT%;r}f($dUY9?U;SA(`n7XGT;@Bf(C=cQ~cD{ zlL@k&zqDU6M;}S?Rg;A-7#)n7Ub)gK9w&O{LLBggo3skzOP>i$kBgFqy9-iS_g=`> zeJ}9BeHX8K;_XX?b8}KNYbN1aahtvfu81g+@OhzcXHntI>35IvIAPld#Rp0cOlpUR z)IaUXbmF2-WgA;elo=c9Ce?Le8w|J3q7G{dXS+d=3)grgm1JPGTK~59csj2~!m&<9 zNSe;=D|=y#;7?PYiiwC3^aW7)ru0&Fj`2uX??0J?ziWsq?5P;A_0)u@!>W)o8Xu<2 zO(>)?9h6}YJC>-7=|V}Kt>BsifL_X6dN&F1JmD?mq!#9Em;zaMUfhN=6aKlR9i zEkPTWeMQ-`e}{?y+Wfrt@Jy63XOV~)Zk`CtD<%^l#S5{`x}Ze?1Ec@k`kpxdCk2a{CHZxJTa*HMJq0iIhF|ZfCxhjS(u%mia=)zpV%gRj(k|?#_88gt!=};^ zlKJ=bEBZ*&sU+;WI*YqF1MWL{4(!6@&ne%(^#4V%4eVizyv8@!{c`E|%I>hfC8+fR z8c3)R>^j5qlpc4hfLHLSXGhgy^1XoK2%%N@HP+YW#KoIbUyu|mhGPj}Tk%%afF8x6 zhAtUUhh>=S@T(%Ef?qwIf3*3Eq-9V9iJbNM-|>)&@Js2_5CRahwOVJQ?tqgaFGx|! zNuFTGMF3~Q4wI1j)Kv*0mWU?OE017(i=ne5CjHi)ujHd10+n#+G9%zktxfcpdf2ow zB)OJ!*ay^5pLnLX+(eg*llvLlp7|4I6|0q{aY~P4nqs-OP^7TtOWA=N=K={?nwv9n zlGIq9Cy3$w9XWnE%lj@^%GIY zUt~vr$C0@K**IL)B-tlVuDyjBfC(Sz z_#Mx>&BM~Z#ekmuNe@=&aBhyUzT`L<4q9V3t9-``q^2@%5Ef2S^gfv@HFe*ALMx&Io~<+JA63q0vqsx z_@Wr@{I!BAoSzzITE(cv!yB?Vg-y0zG+A3_1ZrMMjnC=}W}*c|9w^yyTc7i%`RX?D z&8WWc-gKA$yU;K>7(>|@KO+%m*py}~If+E=u`W!qWTCUr-yJV$NIK||CFDWVo)YlMu6xCV@&atzBop*1l4j~y#L1e9ln!l@ z;&LOlY^N6$8_s8KDrIGfUqXD6BoF>k)KEYFuZ)a?d3i&&cP1V(|DGByBeQ=rAg1&v zq#g+3#_c5(U38b0R${wJa=DLAvNnR+Kl*raoiZ@Tb7&~pZZ}TPC3Y%yL;JFHV@(p8wUq?mrSS?(1>`#|O4v?R@(L|_?bh*jER**BC%Kp+l{Fq>{S=Q zAHs|_>!$XPI+-F^z%URLwwM{_$q zD*x}QF(h&>c<5m|1AU6Ie+R2EeWQZ#sG{1RyuHthH!IwI`41YVe?Ubf!DMP>#wrK&BO5gePJhv_(Ts+h5k-r03yE|w!n=ETZz&l*^(~4^zylhu`aM}sW zL7++S5e=8AATDi<>~WDi0R=p2$C$g|Vj0s$x9{G})UlRj5Q98)kc{*NlM=&kz4bsl`d`h34jZov(&RPb3_JTsoYagKq8Prz##s%SSQXO%rsr zWag$*O#)*l6vbJB*>OY}8vnIbCvV zW{q)2$R6aqmTvg&s`E<-hag>p!TY=AQ+OB&Q7${2CZArc+1n8CfVPJKO}23xJGC1A zu@-$G<=JMDqP`#KrQv!?h9uDW@2q6tBCUQCJ+#a2o(%2@G-tj?~dT)Ip*M@@Jl*#|h z{q(h%K-}Fw5xhuTvu@};yfxq#ZU_LLU8VElUx` zurqrjsu_5=b@Kb6FWY}}d`a4hxo^dZ?&BfTBN!e&lG21nZOTWv2T0o~RJK|tH2qZz z5Eb*b?WQAk3G+A&ToK_we6&0_j?>XtSLaNwLyl!9G?ija}Y&9${_|@a6514qR?w_ zCQ8H0j-Z1Sb$Mm#_Jlt20<2|}U}xL+Y3)hh_5A^utF8ol#j;-vJnD6%p(92^eEaB| zK80ar)XFi6lm`Rat*w6i4)UgOjoy#s{)rpL+{gC@qG2UtQ-X}Atlfc~@5kRi3i>VTm6pEr)pFCg3Go(_Q=AT9pY%O?TQ)1J$;^i&_6=>P5Tf%b3z{uIQT>L8NdA73yR zr;6=Pk#GL3wt=}eVrI(CTjr#50E!MG+yfk zec%*>S&2eqxCn){<}cX(KWCpbgPt+_2Tth1GgDjUnr>M@#g=g%Ao2~aia^hd8 zD1mD3!}EG}R$Y|~%-SDvB`gCnwz*Bfsd1|8$aa&mIpBIhoObxRzQm-HR|7h;Ia(PT z7)qT`GAjm|%eit|GIjahMlQ!=+n%~?Y{E^Pn~!R(ydd_d=GcWd+w>c*kY4J_y&BK%rwkS0+?-f3xu&;$0}q)Qf)4h( z(FNz8)maKja@VBKTLq;DAjVfC;lgC-o7w@FMdh8Vbokmbzzn;Je+VF$Roy9v3j!ZnznSh5_vf%Q zyQy(rawY3m<&Wo!d!#^!gxwDJy@4rcsv`MlQbsv;_OK8*m)dm|GnKjk?*WKkoWzLbf@I=J8d>D55g>klzySoZ z*t(TmTM`y;&p~6X3VTZY538iHEI&AG=t5&{K=)PZdqb9Tiu?`VMpakVRMaSwpBDqfj|J*8SS%-w zB;eyZ(lYr8nnr`Be8gYq{0H0_t4Y)*qyTGx*p_UqmKHnBdKO%CfBb{n?pmJNmKX+9 z)JQ~lMsdp$QLSiIq3;Ae6AtbEZ~>8;#~aQU%MOcqc$<(ARNQ#)dS~OOu8tK)E~K|~ zi$;L%iEJG=np`R0=IjVIzZ&*3e*&ci0SP=n)criKlFfR+D@OM27k7~HnauPBjSiC# z${@pi{bYiX&3b&-3nX|M?mwdL4}9iF{IJQWLW!=a2oUfqmuO=OANk7K=+7jo?oH(; zxERSeW+_fmPLpQaNuiY{CK(vqtR)q8381P{?05$XB(W<-h!TjuDW;qBj`3tHBNxw62hIm#J@CK=J?cIG_Fy#n;a9bEB}x%h#0~hOF%re z1MG{US2g`HT+bfz3MSW@A>!~cc9`?iV)-g>l#^-FsA56>uGaE4Z4gMx*kUA^{^0ty zii>5;B{@Et_QpeQWK#3vZ-qD}E6YIrk1U-CJ8WeqY(`O*1C)b-+CN-sxvYX;Js$65 ze*)Hd6af%`&2 z>;(U#j%>QmskwUK6Z#@c=lKao4;*p0Mf4pV%y8dRU~ynpO zMRC{eq@|Q%Q>P~(iA^Wg?S(rC97R%8P$5Bi6>|qM)+ZtnF>3Gqed9tGp4<&`p7x4c zZ!FEUzR75bmRu|YEI~syI5#9((SGk$YqqhIv%1Srn%Rq&KV=x*N zJ%KFZHa7yvnIh!_j8)%0(b!i|LJ{FN4`?m4MdF1gb(nma&8JNMq4{~BtIpb45)-Qx zpAt~LaOie?a#?nR7BgRre-{h`d6a7Ov&R!MT=*!rfJn-H z8hf|$T3(|AQB$X0ck^5ucZ5mZz4BB3PODm-9rpo_oLw7%u#MECq=&_*js22EP~K zRpF{ShXOMVSzhJ^Ai2GpcK6BKAf;?`NSs~T3AhgGA zavee%WV8H+%YkkMQ*}rd?b~f1>rcKS`*XSQXdS~`zy7?V{JS5kX73Z+z;S(KZJiUF z?eoqxaB3s5I87gk{l0VHr}snryLa7kd|Z=;v!{LOkOetaNfhNksbkRVQPyREwCHQgm4-;t~KG#PRg3<-hA!-Yh zKXRYef(<`eJ1Md(rp5W_# zqleQ@qVU@(-?>X6Md#=^7E}}W@~Po0C{+`kuCCjn&lF-NO9w27f|{cruoF)Ker)qT zNJ%+4&Q$m0zd(Ij@irzvEO!jps{ks0eaH+oq812TJT}OFdptkO^9U*7?UlXK7HjrzK?nV-F5sWxaR%c~u@xhDq=%9OB#& z#dam_<1syk`k63|j+4W0d`!$<}`My`uw+f^C82L}IGrzuL6qNH5P3D{qSVszrSxGS@ zr220=B!V`1Fw(LDtC_ytrUMP@d%vD-dNXXNkZcLml}?X0xsEC9)DX^IF8gx8y@M@E zjdfNlKb!0(6B~NSQj)!M$MZ*OS(7(Y*^4!-)6O$T`lf+eVn6i}kNvf+57!WIUhveNI|DGo6qMfi`6g3Ab}{aOt(lgI{M$qq)bB zgVLhh+x)m=fOrbVC0V*g$Yy_eeS^hbQ)(^>WMXzH!!q);1Hd$jtVEeh zSR}atIfXfxlV-IV&+uL00;@uD=^VJQJP#i|>-HVC<&;)4kjE1B6esIpzRR6}@6d|G z@@P~LU#>2%%thUXDeDtFjcrKh#m&=4$>qBb`S9Mv z=b&b;R4lvLezMDhhk&eHTek9N&`mKYG7qjgVO9A`XMb&x_d_&XV`0)bI4RtF5v(ED z`IC$c7XQ9R9W)ngekhsL;OaZOapz8-GrUUV-#_}y3i0#EIHoHc9PRu3&^iRmVQ?Uk zWO(*M%V#gD1e;yfTYXCyT8^TIij5`hF`8t3E$S>P|EI_0cCJo4)ybX_wL0in(Y6!Y zp0t`^JMjW8u7S2+zpgK7*7ONI4H~@G&VB3=gNW&?Ed_Um_pW<#!(vv~k9OKA4RUrSq`gm4IJq2subBC0>cIW$~^6L#GEUE4VC{OA(I`-%Fj{P>5sm=xKotbP*Li2bU>VYSkg z>=lVJvGCq$PZe1?barTVOnI|flaixnQYb9iBy)6UIpxu(9QE!^=Q8QAFZSU{q1dEQ z9W)a5;(!kq{rGX4pMj`CdzvYg6axs5C&XePLh;jXed0bC>J)^w1I z0a)5yZL-^!9K(~!zi?&;i8e(Tw9=PKxX-s_t=C4MNENZ~boL~5PH)Iq=EF;Q?U(Gv zG>%{H|E#l8^RMTz@zJA|v!4V> zJdU-vdve>nyjT*rI)8~8b zj`U;J_V+at2(OeXd65Tl1a-NI^>N25mwda8XOd9F8@6l=1huaiD| zCd+R<8m-i#JTMdI-l4=rcR1^yvrooyQ2q9cLmyQS49A!b^RK=hv~Zd&n}umRRIfg} zoeCRx8d08zy&O~P+LEGI{PbN@dp32=KmO}|E8$k_$}!B~ADInLB3 zIl%$N{;s+K2A2fp%eK)49kIg?_NEr@f@Oj@%Xx2}5VSS@_)o}e2ouW*A<#9EI;Y#0 zb3Cs)ddVUO^=TB0<_8!}?OnK7a@yQ?q*k(LdWTm?WbT~+Fg4+B?=cD~V6j$4WVij@ zL~ke4Sv`QKL}GaO6#){cu)hj>v6@Fg@HF7vmC!zy$%EKovRS4bDVEM_u#Qze1H3o@ z0e&*@D;l{71xJrwk}B)LD^n&nb6%72UfCzokbS8xSFVXjsIhzi8OwA*Dvse1r52dB z#9to&aDw7+_}d^5)bb=kPO_Bug4b}Ye`|^G?z7uX8h6gh0X2K;C1}%hrQ*@py<0+j zK`Kc-?K>l%VhQAVf7F7>xp`KS>>xX?$#D>%N?kIWv?O5Px=GGxFsLVf7yMAozLSOR zNPDxe9c{=U9u*Ane!p_#Ij0^+W+w%>eO`QaL?ZxUnMImMP zmW=A2X&`y=qqPxRRwm6y>Fls{ndB_iduR!)MH9vvSwUK6Fe zU`y}u8@S^m|5#Gy;2qz;IOIBD%d~98 z1e zvNA_f@m{&8uU9H;40X_EhW_kl<)u5oQ@xL)`eYvu+<=}cdcY=I{Ksbe-S>6_t&fF8 zPibAfM*TOG!c-Cni)M8s5NiWSU4qd{0r{qCZN)D1*M>5Q`5R&htEn3})}E{?HFTvc z{@p!%<=IJ)b-8oub31){O4;4D5t`)iK_r25;cjy6&Pvm>iRnIpjscF1R8~u36u-K| z*~^)c=`dmO$-W+i*;tsXq}7#AiL94!(WBx)u;>&<1X}o!;=V|6nQ1RW82XPZZUv?- zqER((N+$<`pxY2`*^9t-ole8`sE*0MW0#6AsIyJVgWCEFU*YDGNfog}&I(5^YLXN8 zZanf@IW(MBw)A@J&zghaJy*Le1>X$XR2g^r@q$Q1S+mT9*3lt|RQ~d~BO6RLbRuOgp^+7g(Q^=59C zCWToL6hKHhS34kQ=<;1Fv-d`|irFg^hGtgBKg>sgoRZlu0gZKxK{=gNzX0A}I-Wg@gI><4rGehSIzRp1!vmDi@E^A|$oJJh+!dG0@m<(ubTYx!J zAV-rHH|{r%$rj&0l-3Fe$A09Z(lI(jav|goCmjVpb!j6A;~FedAequmzYqHDHdqq_ z(fR6TGey1j?x;Q!W10>C$*#NJeoGdBF+K;Fm%!T#ZkHIP74;97?XRT~+T+A>5C|@q z-l$jrAq<<@UcWBDgU5;8dBHD1FhZzWdPv5xa2wWf_?A?C-|+$=*{sro<8cUIjTAp^ zR8@Fuj^zWc&z%W(!#g+9bnm(ggrP=u%bI=nH|=!L;YugdE(OFNCA+0^;3C@nu#eZt z&u>BA=;n(x#M7W#SN~OmemuKv2-mP7;S7@Dp&XeW2R_`0(Q2Hd&i$#VB-d6o_&yal zB}44$(I&LEztQSvp5B4x+F|!u9kd8Qay_L!q6HjsPu_=-oMU11@3W>D@DM%g^!=|| z0EbhX$hmbJh}|D=i^l$erw66BuTKVl<9Ijv@e2FL*xM~>qM-^-{OQ<;!4Zn;$Lf(E z;Rwii?f`wG$pOAUYtmghd9qAJHy|U~s((sJqy$lcC->x~M@sEZOf+8z(Itr>)=_xx z!Wh?YxH@;7w_!FA5AU^3l!JBj09h%upO4?x4Oqmnv`AfKWey0fI@*{K=*Kl+uQz9#=5>X10vO^PsmF{930*H4nnkuTmm?}@t$xoAz9&5CD^I=1TDsy$s`$F4S^93*PMXewhUS0Hg<2GLKt zeUkm#9FeOrNvk})uCN3f!+nARI=LsW!8(Y(S?n=FB#^3;(K--aZen%cH5*tgWen7v zk1y2?XoR^A-tH7vq1<~ceJ2~NEvf6@vJbUV^ z#J0ChHaxGA-93Sri7XFz3u%uDV18}#m%Hldca#QTE;S`1Uc$u%GDXgQFoG*ycD09b%4R@j+ zU=1Q2v^4o5G$k7nRpJ{oV?tjOGsIzd5 zmGOmN+N406n?O{pv_D5TI6>h(;Af#J;b#2XDZM2%AWMpd_x{?fGBg`H_{-^Pv0{Eb z+t4h3gyI25HYA|{WU3z^9RXN+cKB{@5d=px+!8@}=3uI_%o(DnRZj$Y3aK3cWvA4+ zk4M+fZsEs2g5@MhkuuGa3)3g-PEvRaPmUgY+zB|6E#2>xTq{Uk8#Zn z)JtJ&nt`*echL#33pcWrV(A~(K^u+`n=X1mCb2{dK$(M$W7J_b9O!}c53@1gGnI{Z``d{=Vm|tOsx&3@2+hwGlRFQ48;RdYdo$HSlQA`9q*AHXnX9 zBSG|F7#yvQy-2XqTiuiFD?9~(^{_IS>j4N;tTcQ0MJa2nE1^aEiv+XX{O2SXtbK`$U(tPIUEI{*QNDeRmM_2DgG z-&sfo5z&AsAzLY|zogl|>Pum6Z5^EmAu4rgpzcyI+R#gI(YU;M)qd>m$b-j5nie~j(^7{2NKCzd-qF`zR55Z%HY*u zAWwD9;%W6gYXYQKwqe>*9!%n`fHRW@7ka+18T%)t6q@*lQra8`$^}kHMry^pnh_7f zXEj75RP{V$&)t~%rmqJ`vA$Yn8c#@?`m8H;4k_}(%!l&fVA#nTqN|=CJGv9zvZX~} z^zCiipt$Ru)b@)WX`c(}$^<#89YH`7?{};5;>9gL>q`@q%}!70uZ$7UOiaA-F54a3 zaIx0+@2rW44iuFPW2*pCec-ZOzjLcYr9Je_vp{(tVltDG%Pp6#rsmbrl>(d|83(8? zmL9*gCG7wXj{TsXhTvMsZXX?BR)rT+XT4-T`>Mn4APFYkIX?c;GKEVbuR*66_%|I3 zR60li_8S&$(DWG{*>P=WISf)R8n^~zsWb_AaM9V`8$P)-B6_ z`_zJHjVIyQyx)aanCzZ=_Euk-X?1qwixda7hUyK9K$GV9MK5MPiZNRTOK@>fd< zLPl+z1=LRwzpjtq;@mz6{RBS#j!S6p^N_Ilwm+)Y-8ym#+NIvI)zoOt(kWx}>>O2= zH?D494q{~HN1$D0_I=(UfaI5GP;(^|42?y!^^cX67YS`Yj|D(>+1QW6lF0&?@0beUk+a&6sj( zudCmblp8O8V=l*i@~1hVSciB4E>9M3G555-ONg2moEUm`J2Pl-k6veuEh}(tmREIp zQ_$!xBEd#$+3`GbZdZ(&>Ngv1PN2|TP~ET#Ai(2szRqd26aim zC4+h<)`9Dc=h4{Qe7te7VrMTI2GHh20EUeVQpjk+*QN4eEs%dwX3K&IGp<_&oPhT2 z*Muk=0O4~0;1!`S>DV(DR#^0Zl4&VWU;`~iV?-l`)6=m1{~4b|AK$7!brwG9-0ks!Ad6$xp7MYSI7cX z?(0>&zaa4C9JuPO4XIp|Y1V>W^?hpVqJ)k6u7lUVm3(dM#&{iI0xg`pU`5_cfN<+2 zIXJLNu6s$kpwjjdC~UOqTq}l!?74ylT{3u4%A`8Ewax3zVtxSI6=#Wo7CKP*=ls9p zr97SK`$fRuV9G5@)jS&GqB7V=I!GLX3Q@VAt&flU`6sEjcH3^JgaL#_!YGFL8>5{r zh>OFe!||&@0!aCWcTQLq;1mwo2<5h;DDVNZ_xP2;Vm%vRs3iUiLj|aS$m4SDfQ-fo z0o<7X!`^#FHMw76tK||0*Guu0R=><3Ze+oq)CmT3JAC@pwi-2 zq=QJ85)}cJO_5#&jP%}1Nb=1)xcBos@AsZE&iQl3883fyXvn?FEZ4lQx$ZRsY$=fG zFUcuj_FSDcl1&IsslB|%P#2Z4949}PHhI{TDPtRPV^yosZCLVw3dTHA$lW(|h9zUe zD$bBk|EHv2m~NVBgA~}-Tx`I8K8X2)kIVkwP*w;kD9Bl}Zk3hS{QYIPALV#Agm|)V zM!^*1-3{k2ue;Ia1R;0LO4?Ye;H$%!dI0cj`YGG}WlJ8{7(BglLyTvu!B7H2Qwa6X z+5jU7ZbhGM*;PCySDRB*d0@F@%1FU`l{-rKAIwl{bziBlV5V8JsU9eYs~;_$`R}Kv zIFkKk@(wIljSO_1DB9=e_t%0sM9l45On$@m-OI(VkM)F&D1WLjNHR}3k@T5I?KIG? zG7t}HxKi)1O*n<0948%17ZAv{EMs`8dy~)TE6@~@Cmt>MCAfl7zjQI2Sb-d;fI2B4 zA>)y`?Ugkuqjv&a8pvtYq`d1qX^uaVLJfzaObDK3e@D}FU-YGiLhf6U1#kw!X*Wbn zo@;vB7%(Ec{J^qZc_C#6sRq-0rb3CvAXZIqYkcDckX@#BcOM)K86x@lHDK9C~C)nfcOlc;rqQIqkGC;uj$|PwS&4 z*Q_2Nj9NSMzg6Z-3#?pSSIiN?hqW;)9nk`-X}o|?7&K3I#hyYB3Cpp)j!S?o>jt80 z9SGUnfjV2nEkL6=`bE%hzkX+GPJWwIo>-6NC4k0FX))0wU2oW&R2qDE(!_qEK^yBX zA+0WE3Q{c$grTKYL|#Eo;Rr(j$YbGVCVo|H`{K=~-|*IK&t+iO5x!dk^)=Vf(Tqhs z1l6k4FscX@R>t7#rWsgl&@E~e%P)DSn^DUa8bPrdhKxJor4l=LM|aC;xuYw($Dr_z zLOYj2Xm*67pkbl-{q)qSlg5PW-bqjwZpXcc<9RzMk@}?dClE6ujR=7Z5FuM~Uq%Ty zQs52(pzt$(`k9%`7{s0Hu1zfPkL8cYLb_Gn^){FkPlVXk|RTH<9 zJv9eHI3h-62ft}{OQJC9fK`7*)RP$rq~et~W%ddvFJwUw@7fZXXv~f?bSySyviFJZ zVrqx94;hW)D}!%;5v3%c>SNVZdI5!?)j7?Zm+iFW{Qv{e9L(_p0vgCgFzS90wT9u2dM}|YDzf} zNvVo)N-4$FkGGnOw;0*KyD9f`!RDHbd-zc;v9M=G=GK#jd zzz~7lstS8MsG-H+$vEp426e`~@&zCSB$A z?Im3lI!BkI`vLi3$wGMVHwBmbnoZa4m;%KowMD!z^pU#Y6KEWmhN?9u3Zd4OwfOgO zuUjlsr@>kjXXCwS-W^crk%RM9uj(^~_N<$^@t~R)FCzSzA*Ct*9J00(VeklXOuaDz z#?q37P{z@jXeO$Ba6DNdwWl@LB7U*BNO9T9_aKlUHI8J8jFf8vUzKo4-0h}}uml@A zpu=|GLm@MoA-((eaaT3Ld-FK&R?}k#~G^=_c0$_+Vr$Gx6KsJhOez z*W(k}=wA+&KcuKqgv2D*p7hyS7b5pA`<083i2`22!9qH4?}BQ;NkyOyRKJ6Gv^KYJ z<|j~=q2a!TQ#Kj9Lx3qYX8NiYquB(Uvj&HY7QC!vqsy7JzPxt$KcwCoUPKM@PIk4k zV>4yF6;5^0mm0hdMTkJBXM#(!!dzOw4?!Iy+uxYnIb3R!dY+R~@4d2-p zc|Nnl32XY~M!P8zxi4!=F(CV#IjG9NS~b2^7^BsX9x*})k;%|ThR9ELy3Fh~?&YpW zO#%l&cwwOHPxUp#c1jeQc!JihT=xEOquY>FUd!mSHheLf;|;UAoh^PD`iCA!ZV?BH z8t6NxbYxwx3jUjBmECW)=kD8ogX4fzUr&!UOFrOzDOccFK63z=#Z>{7_;20-{)g`* znPj0YpjcYGKktC_V3>YOrnYA$pOvUM_S8n}SAw_yVB6a`){7K_2+{3sXNNWYciE~3 zIQ3pR7WOJG$RBqS*A>F7fDLIw0*Y-%De#vLR*t*lD@HqQhsI5)Udl`N5o^mH1rduqC*UeWcF-n+iqp!c$Lwzes!AzPV}GLD zY5qswt8DD-2Vq=!U-JrnMh3qzg+aZ44JSCfM~W?}U&p>GgBdo;Y*R7GyIakm<(WrszSdEFbjmSeQNL|_by%FdlaAXf7!gD#zGz8An8!`E;k=dJt z{RiFpeXO2rLk)y(*En2=zJ6D5yNiO~ zpZ;sz8%T8zy3A|9psqzm1gLKdr^uPOnew&z6*bvPxCDM0ke=<#My3_@>cX)Sqi0Qx z=1kDRGcb!aNn-}Y$k@wT`@ z_KqwDE6W%1Xx-yaq@k$2&nWT z1D+{UUf=y@sQR%pJ5hIi4`MC8)Y&&3T05o6Bep``>jyGjOX-JWB^#@H#h+;3;%6%8 z>#GfLp$e<|sLoEAOm$d-dft~sn=}9muB`~_P>r7Cl*g9%g_F7iDAckZ$Gbo^|I0h< zbC8Z8iuE)w#`-*V^BW-c1W@Z&$|>7WcVn;`9WKB3tC4gTy`+W)9?~Bq_5cxdb8qh^ zTki-;2BPeR6v6T(IlkF~+OsP-hg|4BBxz84Ko`s<0zr%{n;2PnE9!2Z)$G~b?!Q|py{al< zF=AB@bLC0n3v5_V4+RpDmM7hG zxP?MVi(;h))TohG-jrrZ0|^w5UKcsGb0j%L2!-0O#bNqU_+*bgkKMb6Zk{PbrQ?;J zHb_6+ldT3m3-NMV@V5Uscqt1t6;C_le8L3$@3CMq@C)bZKsJCTP!aalDkP*!2<) z2r9jp7v9ve6Hg~=c@niUagRovUm{&BBLO3B-?`xb(eSDSV-5IyrNrYc$4bg$x)_Et zKLNPAp?hNhq6Qs;6N(jH%`z`YueDm!um=-^g4S&~;8){EoiUMD&2QRlhV%!t#R~^E z`O&g@UoJa`Ti7p@I(Hr9N8PpEu5mn_`8n`{mHiu$=lMY)?_oA3#;M^|wxHgB#Jt$M zVMU*eQ+px_-%Kw0w3C7#@gmu}!INXfu=V7r?~FO}8WVsHc;aT#xvLD=_c1SeU5wfj z*a{Z-1}L$HS|cT!GWXpz$GiSejW zJ*y>~=8|WAgWEsCg%+`4?yH~7fim4|{=GlLn0RHc`Bym9-hf|-Q=?r&!zlrneBS%W z^Uk&qg-H<5J}MXo!SA*`@|!;!PoLGtk1c8H&|PkoBh`Tih%ALgpQ3Bl*68bx#Neiu zi?2l7UqHf9Nb;Tmz(Ws5`utjJyni3lM*bIq?DRrBq(>=afCi2UwKi6(xoX}gVcoxC zUa7MU zG8&0rdNd;jkr|~vdMsIoKMjetBs~a@L&D;w%<@MYi1j91a2ZvwkUODjaJFk9{|D*O z-hy}8k_NT0oraE;t0rn|w_y5F9Kq5HI?uBnu#tMlLHo6J0j0-xC%jvIUtm*6Y#Nel zmdBF4V?QL;EY5f16To~mVce}6P3_Q$#Y}u0LJW7UdGhCAAw88u8{^#tPrWD9I)=Nag1CO20Sm)Juj>4FF=th8MsKeV1n^Tlwz2r`F zjJy9nHn~qj!jd`e>xZk*7zol5Nk%5$tcb|aZd zOGBgHCrUF3K)uxBO|PReS;J83eHJ8i z-K7Z^g;feNJzb9Rg_^vjU7*kd;SzQH5_5-7zf2EudgNBDQ0vGN(w7NhI>b`XsjT`H z#5x|s$Xyi5J#XzZCP1h{WEb(?f{PJ9Y+cfK1wQWrES}%lEjnB~jt7uXDCF}2A0H~9U3G)tUxD5%WH;fFx zZq*xU&og4tixJ!)eQv0YB~{wTCX~QJD0udj_urGETjnO z$qXD(C<7f*H_*(4G`F_p0MGs0zU4C0*BN#cs^~1ocq>3Ukcue4KZ4Q)EMHj>TaHi6 zuiZP3WkEW&h0e;jPGrG4h}&*SExpj1cfd29#eGiz2JXGt73_0%3fsX@QPX2;7`3$W z$WaIo88|c?FDeHAXadQ=8~Vcxct+31!>c2SDt2IDus|mpG9_zUuEP)^7&Nr*D%K!% zWT3aJ10Y1Jr)e@OiVq_-P%h>aEn2rGNj}&E=}n3wSm^{KX-F7rw7!Y2hx)3C(HwAa zJ4EEIm=~6;n>w*;#v=|SU1EMKP)8X!G72b1)Emb@1DG0c;p90FtNZI|^&DXEu1(-;*_^>j zk28c)HIYv9kob>^Kd=uf zE@)kU91;#a^8eImOmzeHHgIrDiYr*!MIVHlp7t3jHeAS2uq!ai#MoY>t<@$I3Iix{ z?(8+^3ns>Lz&$`_zhOO|c5^y`g8ZEEYneE2)I-P)ol3Bt(20Y^Nm%`8Zvs``f$4Q2 zi~ARdtu_j;K2~jk$jTY)V-B1j^bn2Qg8h0e`2ay1J7BrZ^H~bMNaeBGq%CcQr$COl zk`Ij79o@-vNrUu1nKqx?4Hal(4F?nPhsUP>?exalZw$2F z-O$LUhwXb!+ii#7V<1sfLq{#``@uF4&*RI))j#Jaaf}xf^S-paz_jb$=EA{^6X!Pk|9S|N zOYM<8SG^cb;T7#O>bn57^$K9*un^@iNM;zY>Z*%0K80rz}T^6^aUxL<$UdF zb`UwI;X*oOjc31^lc+Pc)2@gmHVq_g+TDJBkSi9~pt+5?-|N=m>^Ei>t`!8C9K?Fq zt@%FdVl+)vlGP2I`z{<%y0*Rz=!=^~0NSm`WPs_EKiMT#m&L9FU<4&8m8!3)I`CXDkc6o9Cz(=b9ks-6)ciN5e^p%j*`5UfW!8!3pxXa^-vg`_yKJLZ@$ zNiq?CgKMZ=M3J$Ax(}e#DFb~5F%uNTCP0D~22A$IkrXHRJGiDTG);#P8QLlQDTdr? zDUahA=MGJN=Xi$*6Duz&mP1@T+?+#QfIe$*;Xp`R$Y01WAnpx4+3qZ2;Qol+3)Mqr&_TXz zGES&9-N;z+T@AEPG(!J2!z~~MLUoe#`)SBk2|}$eb_c={6olzEMp`Q)&ny4Rry3mN zN0y2ir%)uXj^u#?4d+sXe;4>=dx$4*(00S(f;h5i1*7PSO^mhAxr(1eh&<#&i& z1I&Ok5GU5DGa|%x!u#fpA)!ry5g;A6W<5YTvoLlH%vR39n0%S}! ze6Cf)pzb=hc4j08E$bNiU>KxF7Ipo38NgTozVr|R$25y&@zv@+m{Sx0lyF$_c4wXR z=GU+{&{#GYeVY+-H95vzq8KSFH5$$)q5iQ7U^T!ZR&PSMX#mu56w{>$&*m3_$OUo9 ztP>gI;%~r&pyYHo-WfRXjM9Koyx^QE31JK>1trI+>a-3}lrqpf);utZhcJo;P#Pfy zT_hw0cQC_D;A2_9>zlr2X$1lAk+=$D-FCu`8(ZFg_X8R&{L|o`bC-U^a-q^(G9v7U z_6kj;m4cDwEr$EpgyCP?d)b7Cc+zh3h^rytNeAGS8KV`ZMe#U9Mf3xK&EUH4wP$cy zEpVX51Pu7K)BVjsy)(0B&pF}CBhGFMp-&ck&8!=I+9n6$eNZftikG*;j)5!%j5#8) zLu7^X126_lh*q7w&{`pR$|9HLH@I$;5fbuY(_+)nQiX7g3fL8;&48Nv9k3o!58v!$ zd(pl8hcPjUbPjf23UM6I;2!91Jo$ocbNp{Ef(m*(_`{Ru8Mv4(whuKBw0n=i%1A-+ zv3?`Ho`dfY80;G)Lrqoe@$fkwT>eB7JQb^9f#^_R6~z|$EWfeChya)EKjZ{Zt=63< z?dI{|aRpzE%cVA#!I2PSl3KTJ4FzE3n0pBn9SAlMWy8j!T^MEgQ)+cu6u-b?!Blzx z0uR7)O*3(BB&7AM$}P9#fM+dIk06i|*eCl-%qGst`wbf(mL^e<9fq0Rnn5`5jDOD4 z!D7OP0eS+n)?M_1rIpbs@i^=h#9)}9=EUtc$ibb^=M6;`#zM#-`Gv6-b^yWm+`VuV z0AqNet^c%;sMsQpqQtVdHWc8|rs0isgg&S6zUGTUzd}Vjh{&*_?e^#NZBxA|lYT_l z_^W{i#ZbR;+|?QRuEjI@B~5A*YTNEXs-l|(UvSw|b&c{s>cg1mus9l>XHl za{Ei~qi>hnW+6W#)ixx7ekp(%a!{QZ@dXw^p1jt>n)y%d@`{DKSjvKRb4QyDyT$Rfl^ zH}aJJC&;F0j~pvWFEV2sEOl01KmT`x1T}1cb<;@s3A76gG#uGh28x2hOV)Z90e)z!0b! z$v7rl(phqJrRFyo#B0P~@efX0*?ypZQWE)3WWWPPWcdRogxM7mLF1OmP`6gd;B z|CY8H_IDZzk5&R`pW4i+{II1yKaZ7Y7bd1n0{jIQb^nbNAW|;x-L{D|p-2WI%&6yE zt-2uCbh#sd8U!f7V8NKHSksZ%n+b+*?xj2V;WF1?`u@A~WaKoBV;cI4CKx)@iY=Qo z!v2{2W^iUB)+?~ONCZ9q<|Y=`=NR<00qXxyI1Jlk$fT5b=vPsf+6SfMyhe-g%-}W# z0GMM9Fr3nRk{E{9o3}sj)+09ZBvFjr@z9`zJ;jA;RI>cY2m7_BvfN;;dn~JX!A;+a zHn2jX#O#6+J^r;wtBt5J(PeLMS`4su--`g04l2M$=4S9Kf}{sPX(A~Xc&+qp#PiT8 zosm#BRL^1geIb`l^PX|a!8EgrtV1`>qycU8({jD2?o4n#G<7~~)Uo@Z3P5sK*!nW`ii|D$7}$**!L_mzFR()1UmrPZ-3lH z0w0{F=-El~KE;y;)KdRibHCrJ=Li>+kMU4@mR#o<)rlA0m^`E7>^J7Dx-od55ei19 zCon5GxB)5S9m`^a8Gd0fb@&d%B9};*i@YV%dSdZmJbVy9lN6>9jxWe*-dWRZxsLVj z@!=W0(P$O09y{a=pNGuf4Xht)2aWM9Vk3Ao{3`{CV9-1y3@xg$nK-MB`4!cTuNz(v zMpgh@9Q!`}E}f;dVDCq5wUa-p(*)_r|I0WTseCsDuSKKCGzvk?rMS z8K>0IZN;(K4s0y+m6M zLpJICI4mcx5utKD41WW8!mV&Xl1t76OWLY3e$`72?;BJMV5v+DyY%$?F3Ju4BpE!V zESc_-S&U*N?Leu#{iC9)_n*&@KfT(0;MSO zdCxvQLt%nW{9M!16+e?d(r1OniNpZAG|$fc9;^FLqq zKWm2A!T*@X|L@(2{z+yJveiN_xzTvd*}k-XAN_Bu ze>&({coq5XwKzVya(?B4;HdzoSq0V(MNI#>1m)3#l!|KV#^IF3bzb_om>|aDqt>qo zqdHHm8hmMO5P2X1N0uIuK%e7H;wH>*sb5l2jyMycepqKSV0Bigt<_ttd+Ll8jw+tg zdelnk5DN;Zg3s#sGYgi{p5LH~G<}OflvHp3AG>D7HzVHr9O@TmT62#Cl|I>LRp8iV z(X@8?+ZmJc6%QqOQ2%I?p=Xq|taf#%*K9HNh-^~TqBo(#=vyGYEFY<_w$Vmtj5 zCS8)Y$bWFlL+(Cy;}p2gPG7p)J~KPrzNdImXpXdcW2MBSF+Cx_!_qCM|GC>tMZ0-& z;~uv0q>AXd4 zZRuGZxlaef0`pFIwsfkd&mQxR_H@suu2nWh^0~q#ZDWubPs!!o>wFe<@atzu;5b zX47N)wW_yRUm4kCEh1H`P$hZ6rkPfBPNZpQU3FG%Bc<_V;mC{xDMs>H0=tn)Tah{)eqLC%gzeQe1=ICwwaw_4XV zVUDR#Dfv(YF0LnFAO^hg>91K2mU@*BeS6%TDidRSj#HfX?uE9zpA%u&6N7E%Tasqf zR<-HPBdQNC?@vhF{Ee*dZZmi4s>&?Z&rT~0@OFXnyx1D$JM&r$8!4~sHfRHb7fu9#7LI&nBPq3&3rljvfq~uHWz`Y@PKISPf{G6 zOUrb}+6$K=aa=Wft&B!XwpA5GoT2ncA4FTMFRLxbsjcKqUU_rmmjmcD`t_Ji_dUS> zY%9!FKtCA~$Q2YZSj)TExbnm`X?2=TU66_1$-?@}@-i3xDy|snD$t!NG516P+-5i-?(ARJB9YQ_Qj6G|d3Bk-$Ct-& zxJ@}o_U95G0ZqQAp4GiIW#udbs$GgmUTZJzE$s-di9N2!68uqf(Cx-4;*U#Z&uT6F zJX+^On})iRSCdF0%y~{Qi4Uckb$|B)z#6<^QCrA%_J$Ybeam!^>g(qw43l8Bb_^j~ zVtksY>r77~&9B92%ZEN;+#`>=TTMa6N0vz8ZGI+VFeYao&@iXPCZgr(zorG_Gga*; zVBJe+dPpX0e{%g=Hao^s?iBa|E(SB4WT-9&yus*U@{^zqavVU!=PHh1Dk~ zDEI_kf(AJj#*#3nC8dhyiLu?tD^1>3K(Dnv`#d1qFCfm7ogRZw^7Rq|CX_<$c ztyU|XD;aiB7>?sotxYwC09e$6b@#rNtS=F+?*40Qc8{duXX35SN}QY@f7c*Dxa}NX zM6c~M>$0`1IDSdfGMCeC+U&!V+CJr#GRo0W3hnuxQ>0(Ec|Ks>?EA(oow2++*%0e` z+G~-fVAmWcWok*LYOUBp2p252HAnofKomLG(my|(YN%7(fjovu{*KDxcw+3)vGF1Z z(H{@h>|~>SU7;4@*JekrHT?m;pU;SlE-Y$GQqGl+F8B-=rXM^_Y?f;H{mAFj5r4fm zi^5em&OKAAy(!vs;OM<`jO*A@ck?Of&fW`;ZpNwlc8aCm!tPKZq*TKDsa7>8~uFE8%M#L|BiXL*ldWWTB#=WbFD9G zC7B?P8W5mu$m6@}A2;_=(|LIb&jX_MGoKca9FsZiYRo>^*7Q{@w)U@@z;gZavys~} z%zeM}aEhec#($MCZ zD(E%Wb{^&s7gMoVum|(&qo!(W=d6~kb*lE9kVo70v*f&SltYJDRu>KR?+&<@Xf%-gz~Pe1OiMBEs?}SmJ7ZjOs?=}$9Bbac*S(`>lNvya&_8-E zf8p{Tak<9DY&TMQ$LF0MZzq;meT&yUW%?eZ^Eu4dgwSPgU+cWs;XkUF=(Qz*tk6R9 zF$+j;P$?SByXMq>EG=tgA-UaNshV^5@v$?snvzY?pQ8lkU6wyZGUruD*HE8-U# z1=g?EQM2m7wI3s!R{s4~@_oGEW6B18?U58VzNvBU(*uDX#% z>h_cTY@5!D7_>Cb-Q;<+Ts(CgElW`$R_q9^P2^wc4ia4D!Y^2~t;lx`@GGZzGsKe)atdUFs-S2P53MhttkX(n%~K4BOfs zA==cu)nFH4x)J}Uk|?^q^8zL!$|qyuG$umN&7YJ(<|h20gyROo37Y-aWKthHu{o{Z zsN5SCV=Iaa=yj;NhfCk%uqrjBvp+9mbM(}N~YGx1E72D zm%I$%Uo9qwmba>?%2g{7)piqd3E3AqAD42I_X+MO(cuWxOQiDhk`xmkV++1A?4kbK zb#4N@E`soUKi~v`RO<_zb{~%b?z}1he|bKvN`2v`My;_45a7hd{%i~&$6KD2=zGpj z5IJwFa2AO}Q*w~^MrNIUxRucFc=ujzB<;bd2XeSubCL>H>&IT5A{w9TPr|yN5NWFB zJ4Kwui5T=r#x8r~1}(IR`2sh_713>&qDjQ7B5=4AL3)jRUzs|+^M$iC=ji){sG2j? zm-6YgZKsKKuKkp)cr&&@adqs)vzYEAV=W@n;nd8!{NdM4=zF*u=9=#%M4G~t9$`=1 zSbk)lyWou07xd`kOzRri!o>T{0b|d5o~0}TmoiikiIY`}+sgSlSMf+=44xdHq*vxn z8E?pp##Iw#X-~24c7J_r9GqM$U)DZ~y}m2>itQ<)qeQYjryb$nt@;k}*=4b!6j(VA z8hRo}pHtkPb|~pJJ*A`#Ys7M-V}JVE_x=m;dL;JXjn$ce7K)*ce#(cH*$wQG&VtL3 zS3OU1ic>DS1VL0#G~e&F(VGmo&uQ)x`^FT0;m7KI9K25YkPzB2^6w2p9GIC?{Di@+ zot&dhNg_>zt7aA}Vp!aVo1vN>{DgVm2;7r}c9s58{+i<>nE8MWFVa|pbPBuRx~j_R zRN-r^(Nh~I3`ub#J16-X=Dl&gT*dcs0S5x#!kHjvA4rR5 zGqFZoT%k4=eRA}mOBl(p@-EJ_JF2yU74uK`V0K_N-U$8UzK5c5y6m_!n0IRQ@bUZD z6E?b>;&S8ZVDjQh^-EL`a`_>Hbwg1Qo-ZHgFuX|NyhiPu@gY|M?2;}HKXun3W{I0% zU$Z^inTvCD{+pPpII}vSt%PTP`&UD6yhferdT^9-1nv;LGB+RFy66{yla0T=;*Vnwl?J^1M#W zWlks1)eScS$bG8|i_7e^MEt`1YQ$Z5-*3afB*|)(X#_ES=@ZjYb52k)(ZbG}2ah+mYK_PT6{VS(00UX7y? z-0AE0aUUABd?@sdG5jHBb(=sAfpBcW$;=2G>m@ytxEuB7UNCVG8cIU%8X^hhAg5i! zq=Rg82*}SiZLD7)y=tSoIzM_zR};d zh^v0v;JJr;(lK&c#Gr~4Gfet%b6uo}58j_L+$}2GPZ4RFebHP0^W)Qi!oU}TYoYQ; zy*b$g*>ZB#)uq3)#NrguSC!P05{93hCQ*A=GYEWv97d3qwJ@eb|M57xOwKeXMG*s6 zfC$v1=q3Ubs*#Rc#jG$9^=9%TH0EdgHKlnXgJ&>-FIWG7Mb*BbQ=A*^4=HwC`5>KI zsWuIzCtqqR)<`9p9MeEGe|3lwpnBjaHu@Y#;9iI@=_QFS`$Y`Qer2?$<@eSyc?j2U zc}HN~-#U2kbB+pJy>=uQs=l<6JnZAdKTq89+;L+KGI4mvZo)=4(+c&oeEA$zB1O$$ zA>!eO*CGbDdOwz0K`Q87Y}>Oa43E;|2n>fuaS|?;276uq^)ylB%Rf6UZyFa8L=OEw;k^Q(f)asiahB!{;~^Y8e0AL_Ld3xPRhRlf z_vzxjgou7K!U*LOULGf-I=|$62f-;XX8y=NMSQ->$?s*zIof*unWa^|cipaW z>$?c8ZzeA0k*P6e*WGR|LiA~ft6;kOf5&8)eP~u?7cbAmy2p~wp428je}54DB(C5E zmU}%Zw88Hutncxu<{PgA>Ix!oFI)^)HN+2wTB7dig=*U;+AF(ETjkVZ?M;bnLlM^<0vnJk=$VH7`__?7;Xm1-Cl(?E_sPC`-2 z56_R@_i&Dm2hfSar~{m%v<rSv)f9dcUS!PqlA<{ob7j|NV{W_EOzMXxRG zn5N8jR19`KZnl9y%zaNV&-J+QjULX?hkG!r!q{(25abvsBaug&*tsLi@ig&(N-{)L zAqYD>Ql!3-nwUw2LD=1UKsDZe^;9134Ml+>Y-{#W^cpofY7O~*(K3s7{@$&C;pW`@ zUN;D%qwbq=-L9dlew{M&vD|rhCPi@F*P7#Sh|nkd@c)NCy5jkdd%C>j6rVrYGfLra zA8k~b3x(1RFT@QX|AS3R@{CCgw0bY_%bY-Hxhq%UZNx*9bnz9l4`;%0na?XvLUKGs zjFi2H8~mULsDnpGgPpl%`(#A{Fq1RSz5guQMQCtMNOuYHEpfCPxJ;2!L-Wvh6jvx} z|MEv=&uJ~8rxRgGtIf(1DXEq{)W0~>6!cz#9hqQs7NUnr)fQH0eTmd_goRzfmkP8t zf_j~q#0oR81$T$;;p&9ZiLN`g{90!wBpv}9aloCAVDI$a`2f02r5{2-$NQoe$^36L z)D}O*sU`uNIJxra6YfFR)Bx`(qUMO3ANkVfFLeLMl*>IrXp8BU-Y|M2UWWMtdb`Hq zXn-L@hEixLm+e!nz1*hX=UMq9aU-`OsQ=mU8@m3P1twz3^r`#wuIK*y4O}=KB5-wd z72?KshiIJf)l(SB>0YOkYpi2-oS$bx-N(cB)0@K#b!1-c&?4S8+8ZO7uf{I^q+w*W z=Foj8@g=J~#B`SUpC&#NzVR`^mwjrc zOt;bh=S-yfn`?m_H$?wCplZT7daWa4(>Vow^t6bY{EacVHQ@7(`|of1{t394A-5C$ zJzdU<+YYUy3euYqrYmK_5~Fm&X}DjvdO?w9H`%5V36oQu{ewiGN&YU#atU5?33%uK z#4ojo18E~MxDl*qkT>ss0$`^wlTUi*oL?N+(?dis ztDE0`gK-6PTlrA$Gg|33?WI&fN;9vQMBlrFmr$s^#6$5O^>6;kr;RXQS@(oKo&RqW zXu)1B;ySFIB3Hc`0n6Pl>m_PU+jWX~M)xT#?nm#)iMRdNMGZ!K^+|J21+_7fPM22q zhi_O2q1AhneI|92&q|d;@eN|*(3I5rTIIH^sn?K()5ZTYVr!(dZ)pm zad7dGk@(Gz&a>#Q zSkb0^z~AxoW4{uP5pJ(n`>t>QH!E^~W4;pif5D2V=wdR~C;>oY4X^Dcd@YlUz*XCX ztI#7j53Rh&tyo(OV9VIf9Au#!g{vAkR_O}%v_^`#$gv4ApFmg;r0-XIHlMzmu)8GK z^H*+h2}C@!U>w_e%q}>TlOUP$e^e6P49ENjr`S{RX0)%(qdHhQleMsmYEy5iyZcz|qe^JW|#!U)IKk-q4k{;vo( z4Zz61aHjL9A`fAwqly}O2pEEfMWoJyO!lPl+oI!0<&b$D_GicW_Q`Fe<>8l5idmk- zaHg%g{kGzjjdic*Qd?(-J4eW(Xa^x|-eFps|FKNUk~YTPp_42;3a?6jXa=TEzJsnw)lTtX^W>vq&<7tpT$R&Z-HXV=Xpu z^OKt?bYbpg2iAy9u}iUbCCXpUa8%LnM=ed}DAosFS{*=p;eU+5upm)T`=tT0u-3zr~Oj09y5C${8!cl6x+XC=LIoJ~$ zHe)m0otfT{QpXP?d5tI<$dNi?)rPpsf5E$dyX)(1qG+bt^ruFc=SPs*_?_!6{yXgf z@xXBczw+7`_?5JhtAoD3&3h5Bn2~(lF(;j|({q#o45!^{g&b|6K;T5qhMCLkz^Y&| zA3}oje)lT&{ZUK*=6p}RiBtVv%WUrWe_H@%{+9yKZL4yb^PtrqA_hH*xfa?j`WMC? zL)dCRLJRq^wpe!f(APke}haP zm7k8D*`D=>(5Jc8u!S?(l4z+biWU}0vhpFjaTp~sA9^=0LC-^!WQ`yg$gBimvm6V| z^ZD7)P)M;i0Up^WIdi6!JG=xBd!KL+y;dDNL>cJlUA+X-05v2>0&Q!h_-MYrs+8nl zlRMmX9mA)%;!MwnM_cX}+;ZuV`aSZj^YF_<$=3hD%!u8?iH)CSy^rHD+kfb>(O)eN zn2a(Y)Y8^+?>wi)S(n|r(CJYP)l~8}BUxu~YHo9pi7)Jj(bbhVuHIB#m6cCACs9Fe zS~BNSyB#wGGA#J-t$0rH;{F%1KRe_DdQ1ITM=aR_qk)JN`NzQiPP2K6fC+$z*%s>P z(U&ZQVoKe+v&|9nbq4A<1}!uuj(&n~uyty$PslHr0_O1=>GT%6Bl>N8(F-eF0xjD} z!!<2{<4y(~SP>xDYc#A@rX&}d&@Xu%j*JBPv63oA%iDuF$rXHM@NbqOZ4*enAiRsf ziIrU}2JFdsnt1`}uCNGz8(k7QRo6RQVjH)1$KQcM)-U?C^C9$yV;f)ky~%nyW9dOq z(}E!J^vE%%>-`^B-e8T^1oZH%q{h_8`+0(h_&|=s2EX_rQ&)_s4+`W9>YBb02yA=J zB5--<^*tc{eY=@6W8#qjXiAOK4*%mKJgCY5!#CL>j@EK&kL@@@U2hG$l%ck!?5t9% zJNB$2miL|@lpfZr7;G5FB(#)pQ34Jm|vSMnf8#UvO1h8^tBwngS$$D44bwE;=9l1 zg9pOxI$T`;H>e!9afyC?My`mD^n8aeS47NF%ZR_a9zQum{T0+IwM8r`h`S_)vd-~ zUTS>zizEMPz%Ig-*ctkG2Oe5@J})_V%yjn&u1<2M9sGHJ#%%raAvDhlR}e}aYj4!6 zr@+pc1|=rLInP?2%EY)7+&o1bW%)l=DGmc*ke|CKYOp47uD=L!TY0*YZ$lgPbZw0v zGC!yvl`kC4C2P|c)hoX5?#hKwS1t&2eY<|LD{9Fn^$w50oyLpuRSpI3N)My=^-{z+M~ynpO*8-4 zIB@GAL*w}F3T4mIix;1P2$*aMV_i?) z-x#y=R)`RW3t6-nWW@c6!{510?{=QcY7y-Fc3q|G+>)G61o-=n%=kKxg%F3&c1mco zNN#Zgz6L^VSW?Rx@B3aG3m;6xWCs|oB+vsqf=cxxTlTGf%m5YYngTR!x5P zrb30A+F$TB#&FJUjSYZR1<##I8;B+YpZl5C+#dHU?7nilr-4B|6@XO*NJ2Nwdk`qd%OpKD++youI(f5+mW*v>mk+I9xMFJFjYHlH^Ew1j809W zSn}7zl-6G0yuEujVcwZ3?sns&Js5%CuzB7gR{e1vK8y$^pMhwndGVK0)!x0Vzw
    dp+d^||_3*RGrK3)Z++m7emXzoRXBW@w-Dz~oput1l|HG~ zw>NnooIkr)FG0@_xJsY3dVl-fx^Wt!W&LADXTXd^(bdcm^+)|D5ViKNGdUe=@`ThF zB|O2S~scB2>PwLHHkYx@}mo z4@4b4TIro{8n5odPYzPCO?xsuCtm6TP?;`{z{ zc90q6UKuxX=`cc4feYIsb7>*zi}vgP5g$cXP6C=2DWQC!2_^nT{>ZI6hdcEAulD8y zNLcSkTF;OvZOg%VImrgGUy)bI~j_UE|m9L|v4R12XRWzxcz{e)EQ%J@(WW zBknY&BVMJz3#Yxg_Z+B$nO1D;JQ&S@`Q5!Lx8DjKpP`VP8Zy~;JGB=+&v(f`N^;DU zjbiVe=Tq@wAf8-d7fsLQ1VaC)4*9whi&gS*Wm_wfOrCY~T3niytXh5&fjrdx}-?&hQX@!#yAbwX$6!%W}XZ)b`T*hws)?u1|xqbg%D| z5~G9TQJ<0XOGG>KD?*agj^*8i(+IBqk6>@&W0v0JGfeZhQaP~Tyz7ScGrzx=KB$yO zHsQG2|7!2eSMM_GPtw^@A4asi0kX^2nvR4-=MM8Ee zSt^XB>`U2(WM2kj`5osuuIv7OpZmUl&mYe}&mZ6Ut5?qDvmBpec^~iNICHXdNyRb| z<|m`ew@-r~m=LwUP~*2FnDdvHPy7h_{Tn&OKR7bv_u34;$Xfc-`n+~js@mxqQ(APs zQ~0t;j~z~A)1&MaZF-B+*;Jc@n>U<;Z@I;+xqrZ}Rr(GcbfYQOLY8qmQ*nsf(lf=5 zaKYjiJwbRDUNMAl66JQ{kV}77V_JL2(t3X3U#4(#FBw|ve%(mva9kv$PiEB=p7lc@ z9NP!H&-;UC@iB5V~*RL$RM}|)oDtA^18rYj%K33wSuasPv{8K7*(|;8s+*N(I$Vy%Ccp`;UvQ?*N0h`_%R$J7@MHT+XoZHWGdb#r}wW}uU@`wLb*&A-KOHzZRIL9>2j@r#99=Qj# zQY6^{tWF#+nV+=Tp}zW#&dB!1@&c^}HoE7%cJ-j6i53Yk~J*hGi=m7STd_8)Z|Ib?jj6IjI4@^NKjUHJ+2 zb0R4plnm_gUH9s|pWLob(@Y8F?5L2Jiqfd6>n^Fw#H7*7dZ#OQ18G;z)l|c*lx-0- zhAzAH@&pCd{W8GarI*pH*OJ%xH*YZD5n4F`-TE+?VDvs&cj3|m{UYbW8E_Tl^}{oL z-UOUZNTdTh&;FM%c5F;=^9J49fhYrz>jPx1Xci6M3iNi#_isr1^<4=;pdgUYFtfT8 zc?zK|zw2Ektu2>(-*6@RLpXrEh=bmfwcO{G1u=@>1wwkRqxj1hY;Buwst+3%SzLJv zxxPeBL6W#m$K2^NVdy&*COqa~$~`4S5ZdDsO5*7O1koi5GEuCmyT$iVcRA8OQNoTB zAwiG4LVCK?e6h$Yd2ZSWP|jx6XPP*U@%(bf)fxXxM^n$FGw`B(pFXzL-o$-4X$Cc& zxUqMJHOosO)s^n@7i2RVI%_tW)k$$Z9|abBvIUcq^zInn^bN@4Jdgqyr5NZX^aytcJFBpAuG{ z`Gx0ibtFu>=?4hu{Q5f{GTjy}?y@uv zA*Q~6*m-Nf!;6k=pdf=F`hG|6O1wGENqa=<#iVxJOT(FKn=g}ap(PO}<1_x7J2$t+ zcOT2|S;Ei0+){EBFZV>k<7R%^c+>E zwKX4=)Y(ai<*;t5Cfk;VM}`aY3nD4W$?F9sV17U%z#|`Ye%oy{t@Oy*>crx=wD#{O3XcStI1I{YQ@eb3_n1`2Va%3MD{UHDpBj zw08373U`+%m2|HxN>PvxCo+jFQuj@>e`z{^xSkpDWOe zgVqM_V4YjCVtMLK03aVO_D9wh(w?gbG<;W8iPrZ#B6R>tXn^xxJO6dUbFwk)-pp|2 zS~q<{D>ITUjJI%$MoM311izlx`hr{m|XfY*Z?IZG`b^7sYtCkI6s*jzh1!y#SH5=n&mtUUpkf+546l?II;?cLjz zqRa!5IG^Apm+pRi_s15ty=1iy2j3?TW&duhK!KcoS3b6p|@m;@kI4r6m z3wc|wM7E*6X?NC;5wJU^s~_`PuewQK^MFr2Spc{?l@o*HpZz1f`;^%}Skvq#J*Im^ zz2>7FZjWAH(#`lS7tPu6$4>Qs+(Iac2^@kTy3k1Kk$Yc4sxwR-s2jVhi;AG6MqK%9 zw`Ph!Wx(_zm!B&nhyiII%X-0eziMr@OB*LruH1fmlUyZr!_J|08=OLqyok~{ekKe8 z@V)=yJ*~XEbm^i)G5rHIyY(XPwxhs(_$MdHvTb*z%;|E-D{YiLm(xGM_U#vtO3$|l zVpAc{!$?W)EREBGoZp#i^&`C##*pr#3<=kJSapr)rrN%`1FFXXl|JAp1k>At@W-dW$Iy2qtnc zH~B8_Q<7V)hD=BXW#hJgcbllaNn++3)KfP0*L#Z=RP>v9{I;PEFB48OV=qM=V0Z@Xl`robFgNwt4{6g*SgU) zra2)jgp$F% z0rLtR%Z9e+4(0PNlNF1*A5a#A<-Bm)>I&CV@E5xB&M|Tr{CYwyJBE+`kmr_3V7=IxtM;G@pL3=_D}s|w>ixB-VgTiJkZZ+X`SjdDbr$^W zkrT;_P=w-IBu|rNB7dRUEWP8`bFB}m=EoXz`}0P+Atj8Z?ReL}3}a#tVjXzyuT^&2 z_~{NlI)Hu9n{;E@!6(De@y0Q%jHhUUWn}RzUV0xJ;~)f{?Jjc@Oznnzr^!LAOwxHE zKzYUF-^nnmm>tc5MJ&2SlFiK-{VI|EebK}X_mchjx#i%9;=2Fs%ngFFMvt6TF(Lh@ zTMQ?>Xv-a@HkLpYmX%Ll(&VBq`l@Rk_qYKT)KV}MV6Iu zr10&SH=6Lat;t0`qrf0oVOw(-aNq8F>mEF9R~I1s&5k&c#6Q~#d3hmQnTw#|FXh)u zV52!F1-=%x-2yKBUY_auLzZ=`nd>J`6#Jk&|7hn>@4T3wp(##b^7)9a2JR(S{?HQa zmf~^za0{E+h8Twjp=6YnBYO`JcsQ<8MrWAF7WQq|0l^cJ&_qkufIw*{bH;8TP;)Y6 zu@CsQ2NdG`#NZsJ{8RAV=*%ghHt^Gp| zHf+`G=3od5zr)*oKUJ}kf5Es!UOyQsqWJXa&ld{afJp{#X@^a?K(M!4pQ$~R*JVsE zj~Tn)$|~L2l?vJj5&xPl$@&O`qR$W8Z`C1Lb*$`{ER`1cKHt!YFxH@}fv5hlhuBe+ zHZm~e;_CrL%|Ou7tzqw#b>Y4Vc6~mcuC%k7Ko060l-*Go_j?)G0JRHCE)}mtv0K$K z#3syd>~^kMF5aY6O}xza%ySRIgAua9K0IIVqech zKCmB?A`7pLEcHel^==iT7E~$n#r%O*M-!74Rg(TD;Gb_->nzd&f z4uPlhk`jigxH{D9&wHu9^4(|zQHG(svph6D#|h}w5=1jxffK&UQdP8*>AI5`>`^~GaWns8WDW4@9?2aYe~l+ z*KcRwS++~2-lPWJZ$oGV+s%X3!{A#NPb>4FhF!Q`enny1rblN4^n|)t%I<9kmK$d! zur&Lrt6ZQpT&BVC9z6+mfYoH1^4V6)re%a$nOoLW&@TY)oiiJ+y*eMp|2`a~XNuQx zFT;*BJ6^V;CG=d_r6jlV>H@d@&~-}(D&+1;l9o;1Edv<$8VanyH_#8=+lm@YhmoP1 zNR_dML&EO6wlZivy)h)ynCHv&c-%crfISeHRPjE;Bd9-oqPQLEMMVort1UOA<-Ufz z&O^&Y@Nkyfat-f27{XzOAqmV?S(^VxXR50NPS;bhpt+Rax{@Gt)EYIVF=h82lYpo? z*l9aRWg`cX&Xh;0ZAjzC?l?9kjSZ}_MYPyFJNc#BnOpUxch%v{*OrfylJjGH#J6>V ze;-#CC!qKoA0uL+Tj%DQ>m0>G=I>>O4;<{rZ>Ur9qqp=I$EdUbp%Bj4AGJICyNo~_ zz~?SF=R22OBa;uMUCt-G09JK~{k=mkJqa5JY%zTl?`19b^h!2p>ca3d=5?QS>$@;ha4I@Kcy+oWy z^0N_Sw4t&mtSRl2MxLO-s8TK)edSudLkQAW04Mu1I4bb%Zl$|$8s(q+mB*TYm-M}B zjN|Y<*l;1PiUSbhx%S^TarRZ4Fh&4L;k`gnLK;uyPyM2mKpzG>bq{&h1h8`gKb~;j z3Epjy3veR0DWwQa32txH)#f{#Q=&Fh{Ejid#2)yz5i%3}q!W);= zx}i+w9Hc|Z#o`eiz@f8&J`-xcpFtm&IkMjmxZ`2O#g)yZz3;d?vvMac3N&P^xcU_U z!|-;OXcRYM1O}@`%#OF%m|*;qU_D!&JMFO&JQ#YmT(+kIeEj=n4p{UXX;pZY3weDFecAmd{&c(jGxp40B_KtZ#&VFnixfXpyE zH^hgR0#^cNuk~R5$kjDa;cZK4%6I8eS_sr@4QKF8+49b@DaEdA%=wOssJGeRloB_Z z)82_c#wAO?2d#EpPcmV}RXAa}Qb6#a5s3nTP5r!ZU^?j8j?9YOkL1 zfo+x#lcEJBvf#F>&O)Pr`6p6N>kcPsalb>k4{}24eW3m*3(HZPGYKg|BbV&!k`tfg zb^2i(52_2-13+-souw##Q(y-* zqiwZ3++}abc@+0X-R)D56O@*N>cfg#PVVw7ww|~i)9== zuW8kBg{_vhUB8o%aK@hxm)HSl5A+5|Xm#MzRXvq@o*&D7xnhAWlqyA1gYdflp@WSz zcx@NH&a{KO!*DT>R|h2YCETSc<_4k30U3~{<%a;U1Q`dJ)kP%Ou3!iyN{p05J&*BuVwMvz!ng%HJ!POq(g+^A9pS%QV`b-oMW(FP_EF>v-!2f zN2k(M=T>Gif3$_<>7k_^fhDLJy>S4`+7es-MA_F}o}po6vLVm2>jKH=m>1`Vp#JN; zmx+i7L6e}1zhSDLuK7B=I#9ap!lDe;qi(Pe$q@pZI}bjA?jho^6h^!|lz?ddaQwGh z2|-#`5EF0fwBmY@G={?v!Rz(f57 zt$2!OL1OP#)hVqZwIAuAC(4O6?2$4nK<)1+^|UOw>1#f491OOB$Jr9rSLV$aOuS(B|9K!fVLLDE1ZUil80l0a)WK{1-R%n#1KVV&HK$4*QEx)%^6@EegpL2%VTWP*yKyB#aw$aI(tZi3E;- zy2*AWOCe?yVl_9?F@?QQ`1a@`6by@E$5i)v?6NmI$B*6lAd^xEfXS7rdC@VbROm=n z_B)~I#|F`+Nqw( zC@oBgho%lnS_9tK&kTb|3}|{x1>HiNKWNwlg-d^9HQ?=>tO2C!cKHeW8s&Enkm49> zy`!x$#BWx^-?`f5X{!K8?i-S8ZEUO>6MX%J84Y`ypvJVdUe?l}%a38^>1MG!tH{Wziz!KDTS@uMf~}H19l*Z42?UqLbndW@kE3G z5I~@w${&hYTPb`1td0$x!{0e8Zq9JJbCT7nU0#tc+0q8Ydsl~k<5Gmt6OkY2-rRLEM&ExPYQxYTA$-xe;l&Am9Pw&@hrjS%aS^T2M~%Akj;wAX;4y96 zj^ob^Gsh+~=Ry~RA|$4S8rTL;h}dZ~00F9YnpnC4g2h^m!aN-K&3`x_gCsy!PZ(N3 zV>j^xq`IcF=DX5ae!cdteEF~}sMCok4l>Glig@(7zmup%Dr`(-epPF5&VV=0yzr?Q zwKDQ!erFm2yABJ0_}`p5H1}z42RKa^dZ80T*M-+{IgQ!i)m=`aEFx$ipiM@%YtAaj z9Qtcz;mB>LbL13DV-mh?SgbPd=cs=)JbK9<|XtjRmWl;5bC+RPv zoJM?Z@F-~$;iLcx^L~i-?(5#IoTTsh(`EMO>v&Cqjpup!$sgc;=_Ww;gLOOmPb)Tv ztKeJU)!?^U?)BYey^adqkiu%H)jL5rm5+BF&Q=1a##60-T=`Zm36MlyuOILI@*a_v z3fdvkTYj{q9NKt6YcH-3f{+*K1{4-B5OVxX_K!W6D4NjLMt2PVV?sno%gys73`$*>xjA#4d_XPRyy(ori1)@DWMe+&2M@ znhgADc@s3JQ6w{28juXZJ518EA?~WK*0D`ety)UHIFVhCi?1q?>YLuhhY$@m0Q(rs zSGrS#0phpW!UgwkK;%F*sLRpaeW9}9U`7ME;!~X3I zFolowkAB?=bq>{s)nl%=M&onW0-NLkeU>_o=U8|E?}m02eWiw*x_NH`gpy$~^-TH^ zLZEDhZc0x{$CUOG(tmAUc6yb8w6}tg3rNC$c|&s!fQ#+s5Vng*^#OtqOu8{cEvOSP zmB7eBBdQI6?zh{dEOmc_L7Pqp1Q-E}so4{d(v(#~f1)_@-Eh-uL99U?YIVODe=x|p zx-{2*6DMN&H#!9QkxT{b_wfG*LUeFa>UlF5f9oDM^KCZ@kpx@I6GIXUwdCkHc*g*k z?abIM+TFg7u-YVcuWHt4TJm7;YLf^D=0-1l?$YoHH2J9;nl5 zi2D+Ci9^;Y0{mnUJ!tx)-LLK-PQBG_g9}ZhEF;ikFp-p;gJdHANt+;kb>g!T_eStO z{p?(ocddS#Rrn=^&08^x_l<<6k#LT7luwUufo~T3!1-}7RybG~A69X*8k{;v7$WJD zGf)9@?l6VAyxt}UNuAVH$E|>~fu3eV=tk&h^=@akKa|-mJ1>diBU$ZX>m%KKj`?tY z(CoiXQ-XrI*^5qt@@)Ia>in1#sXI)#mFZ%h657j@>a^c^Acvmunc$iHPpB?%mI6QO z{@niL(KiH=Grfol4NO?3d70+sc!=^{ZXzE!R8d8c8DrT zZ;;QVK*9O@nVl$*eR>wna6$yM&s88_OU!rR{{r$lKnsx5ZEI>CCP*2`W+c$m!f7{h zzRB5$nDKOPv1)~X@jD#8C(J-AhWcp44G4i^fMuAgHv)~dJ%qj^|8|i5V4MX2J61wC z4T1#~B6&!L5$gFY31n>~c>Wvn0S)Ew`#P0{tgrFvMPX#*F+gJ%K29D1r(3DDDjE#G zFJ4V=5}6iM-9={@*F_%L!T@$zx1Qxj2x!~7gvytUo?)aPA>BLvC-`Tm8Ufe&m}1JT z1<+(%QIWYS(p7Di>NP$S<273J)3d6Y{gwMqBtQB$BJ@!91%#R4H*O=Ow!0m`j`=+q z0^bCKf%1Z)+hGM~%~iy)5lY9T{u^bu6p#`mmz(JT^(NKI5N3kpKq-jf6c?C;p@h{H z9>fkC?60^<4u72a16DXA3HlqW}TnRl8vV7bea3bB3^~&!6n|>tl zF6n*5^ooxLXz^4=qVts;*1%-@lVFa*!i3H|XraT*JWZ7p(i{caY#_Fcz-ozw50!17 zpU+Tu2%f`xHynC^x}uIpJva5d`r8Bu@I%Tc*3*v-Kcavj0RHq5{cA|5i&P~7r5axe z6u1#8zXrtf>7WW2EZCVWFDNQo((aFp0xJm3Enh)Np@tdj+u+fh47~ITmkhmU4;elX z${f&EV(v*@p=|F^-3>C+_HWS8F?3)xi?70<%O}_ZP$cp%bECG>p?FIa8>nW6WD5`{ zXxr%aZvRAX6w9hJJJ;X@T0&0W)G1!oVg3oUtC(h-+r~XG18Y&t`zGjp(jieg^C2oV zrpMW1SL7aYntMV+-J+2bux+KN&|&Ute)AWK1a>DCjXF}UKe|n|qpn4%x>wxxYi?Bi^v;xoz(ycw8Bw}Bh_+wXs|RW=qn*$4lFiz? z*SOwzsl@6R73U99ZxwfU|8!t(c~d@8+b<5Sakx2TXO`L48-)aeo&2Y$01`P6NDt0w zw7iLiGE z$fa}(Y-<-3#jY0wh=vlqqDo_K6~{{WE|$^!B-Y&5I@f5^tK%5>y?4FC6hA%XuCjn| z9$O<9cO-9#QBSF$1HUyI*ytYr0J+>oy*f~uJ+ad3M=$rCuUr;E?)Se4^&0*C6W){1 zN@sf(55TH=S0dXy)5^84z4<5asdx^zv^?%Rx!9J`NHtU)eE=U@1n&w|Q~V_I?rR-m zDxPyjKor(?Y-aWPUYGmd4v--?IS9URuQ9vWHnH}d;wz@Q9eIWmcxc`91^3c1C_H@( zuK%NJzJDj->oV$oMGpSpHv^(5bRli;onTc(->ZFx$rQb3#8mri1b2TEba2YQqxc4( zV4I!bfqB#$Xr*{%EqfeGosFi2pf@$_JRa=e^Siib-c^C=4~wiK_TKs5;7BJ>S=L!9 zbGKX(q|!cW^>RlkhhGvj%0u1;`O{$WvFa2!5ZUDcJxLBd#`UnrGQfn+r~~9K7OMNp zCl)DXj}lQ{?{Fxey1O`Zo6haVU%1@6EN=*VU5F=|Z9p5-!q*5JA4Hk?SV5?CLD)gj zFX?vz^wW@Wly?uMYz)o1s)4q`*5#rVhT#XK{E;E}8!GD+wQsebYMk)wOw84xgde7f zfs|PK^@zG&hHe(ly>Re~plspm2!8`r0=|nk{S3JgV?4;J=KAwl@8UZ};hmOxb)Bx2 zJ)VbUM^@i~CWp8^9Y5Pq0HsNZH08DSs6j21*E_jwzrtkWgm>qC+G_7$bTF|3N`lY? z&5T_RVp5SO`+GnKmoenYTIaQsleo!4WvnJw`{N9UZydx9g0aXgE1JwL!n;natsHmU zvIV*48&iPM>+*#}M=$7>^w_YKw?MueFh~)|kiPI#Q~*6fwfDO%o;tgV42KdCg|3)n z1ck|>^w!Au_dJQiSXR2u@Yu*u=^z6$dc0(pbBr+DWBgHhwT!Cj9UsZ^ACoW%f+EVT`_hd1vp9+0Sp^~0h9WT@C`^GvOwS4MbTMy>EefhRnWR!mK`B?)i1Dbrss({qmMLhbE zjJ?pLYRY$d(3%!MzUDC_&&Ep@f5T!js&YT+YAH;_|Kne@qr+<_*RQVr(^;(JY?*hi zV?#JWXwf{GSz0}%{o$RjJnr%Yn~B$^cz3g0EtKp2hIof5Z0^2**#LaocjsGRaCR(_Tt@r?wgQ}D^P+$lclNHq*6|`g^V(5PQ??}#RQuHeW!L> zmpZP)YfOUDiKBx*eI1}7 z0Q|0))-qXyWXAr8+haWxO7z%p$PK}dmXf4OW8KtKIL$q#s1rTAkxMb6Q0yqAy3`~^ zw<>^a+G&7y?qBB*A%1oiNS^S&blNeHX}sjxMaGg?JPfxy;yasat-_c~ z_=Hs{!DfvZbplT*oeiVaZbSF;<&_|&u*nJum6;Kk=Df;R0E#c(KB@8tKE}jCe7ZbZ zHf&^Gw%2cjZK8Y3557eRiev7`iQrVZ?pJ=l^_>b^p~J_K^ZjWSb)S_5cDpX(T}jI% z^OZ`k-F;`bA(y{Vxx>UpL*Af<|9M_UBW1QnX+*$Wn1p_xMh{w9gtZ5Di{{fZg|Mkfj?2o{-V%A5DOZ!J*5&g{ zUXHH3=;Ei}=li6wT+OE9LEA$R5>+~o{G=W)JyyEId|bj&xcD<+Sh99J$B$+XO_`9v zydQ!oREe8NunA(_x=CrYqs_j=_I_~*Z1=LzW>jpUakTR-)rDn2bNqhqSEFUrVB$!r z$C4IDvG?U)WdK@yzI3{{Ci_#KU`4J)ll4R>BK~&r z_7I|M8PsMV?}ksAJ6}W|JQ2X8Vqg#ZaUN%<^35dKnj+U*M*m8i5DY>uOi$wbbZP9? z&%kdh7L5l^cjz2a_!A#vv@LV-D9owGm-yN`n3IX@P;!eFJJGAN12rsfw%%c)&dZw8 zI&a{#>;IBpJu<}}LadhP^<0dd5bPH~XAd7COsFegn-e@+mQt>c(>`n+;g@n@#Ged<%Kp)Xoo>-T4SoaYREx$@E#vDFIyAx zMFsTzJCoG1Z$a|Qom7=6MEBG^f!+1^`a&iugxFkFxH3ieTg#wLXr4h;NZSFa0J+%C z!M?PygUzI$0fWu@G*dU6b_u2A(&={kf~yEvE9!X9;!>6h(;vuCFbXj6O7Q^d+41wX zh#;HbzHqo36NVQmXI`UD6sF)1-dQ}k(DlETm71WlalT}twQRL&i{D8l_@FfG|MjhE zEVL|&U!UiYW_|1`C`sjhR;yM&q3jsbYx8GD+54b*d!+eg5mXNO)R>+Yw758Li47)Z zW4;v~lfOT-Q2hyrxh=2WB+$5T{Ty^uTK;j)g0Wz_%mH$DJNa0`h#?oHuJ%5@2@%Hn zvToN%;fyMun*76%IUn8RHqfI_R|gl*dVA(?=T$7N4&`q+t@FVuiZet6G}=aMrEZ-r zbP!i&?(nJG7Mm8#G#(DpNU^2Yt6S*S7w|V+eND}T=tum_z5k1=vQ$likpJ`2g zV$-y}0mwy|&3gib#-wEX&vv>)+gtHXY%fBq3NaX-cSv7=D!-&=3;mg{KEm)&*WKRb zxo29@S{squegyNWAEB*HQ^vs&s(h$!Ush}U-E69p9(<94(mIy_e=8%Q+))jwIafOdzUA)c3V);?R_tNJlJIyeG6zBjo3Rn$d^5s zpI+7_3=db|Ek)mnX*k97^buIYqN=3B*t%R6lX+yD!k^1O>%IC)_UT4++70}8=e?HJ zfw^XoO?unoZvUtdnL;Ii#CK4GK|FLk*aAWw>!qqPI3T?_<-Y0ydM?6>(9iYJY}DF} z5u>`P<^bOLn1_^YoPa;+pt1UrAjLh6sBRkkYn^>j1HtuNnRQDY2l-*Kj=!8z(F z-}aEQPZE5}7B&v5KWM%x0(9)E&z@yf*6-Gft*Ss$1X%4OqYnPMi)a{enKL(TUFfSY zKM7za{I2jH57r-tcBfW{1zI_-XFmF-4V0y&nw=eODyqSo;di983 zIzVHWEcIJvc198T;oFdK;-v2|X~4GWaz6JMpQLdoavPk(H8BJ=jSwL8bmHqOV3!yD zAKUUK^I^Fo2bIkGbD}nV48Mo!H6qXP;69f-z}lQTDx+w34GzBb2Exf*3@JVf6Rp%p ziPrg$nzWz$ek6r^wM>?iyeGNzlp6AOOg~;Nh7iA#c~A7yMPj3}oqEcp>d&4kkN|<- zmBYCGq2LIDWXEy{9#a%Krv~INqI%AO3Hj zs>jxTH}{LEqZgltcQlS4A8Q4vd=`6WbV1|dX=nW>7Y9qA=ZxbhW-;;Xs4K`1RcBP#h6VBGYJcFRU4#qjNjVlxQ?RNoU7xJ|l2GyyyeE7= zh~r%AJSW&NAMc}6RlV6t+0hEij<}T*do3T22 z$bf^~q*FUr9{Y`oUiRJz1OpaW{#>f^nHfMtxeb<7>5cRaf#0a@elBNlc6GB1A(T8G zoRcntjWFFNt~@@e?D~#{{QDr|96%4$BbKqO_K6(v2lseA#_tA&UJ#9sSyrM)X(r3= zUDTI)fxc~@I!KC-5feE`srNKN=m_L((TBq~U4!`@%0HDm;k3v5rDl2f^(Y1G`vs@v z2WtO9uiyhQXTK{kY1!MaMcZg+k`TGQy1#`P*$0`Z=ku-X#Zl*PsHV)$95as$BYL7* z1Qq&OA9DFDK8DLWZ6R8A9L#5c97CcL_|%;nA&>vCrftPPP69fZ!NNo&)-fmVlsSg| z%vi;KSm*2qczg#+bAwOnTHv&!!wwqx~HNu&x&v(@sYx0HHVR%;!{@O#v zddq=9IlXoB^J>q#Bm3NeOn2n|A;&}Cr`*o>gfYhQh6Tpb<$Je04IdNC`wVn?i|$(E zYxR_b^8LstFpIeTU*x=>s2bzG1oL|IJ4j&Rwupch%PyzjQB02&V2lw zT{YUnHX2FHPW=&A-JIjGSzMrXp|V3j&(2X8ecTf4AFvGu1Me>A_GhPgj5JE+?wT(L zfVB>sWfJl?UB^^;2(^O8)2)uT&HJ^vKdmTiRl60#Kn1ltL#Bzz3(G((&D=OEf_ zp1y1+&=7M^%7MLb=<8wd_>wN5BZU(k;@D12AO2rCY3Yj zHP;XYH7xcgtXGNEKpaJCurxfOF6TY|8jwuj_x?7lu89J6u&yX1IYAaqSKQ&QyoU*+ zyyy-h-3fAnwH~N_4ZR61UeN_$3n9K_+`A7p57uQcFhTfhjf`28uf&{s%DnPr!`(&b z-Ix_vgf>5C-Y_DmUMPf8G@=UahlK3e3)SdyNO}N%)Ptbg#@rY98$Qwav2Mx?p8xq*!x+GvDCKkmVHZBW%zGp$3zEeb3tuA zez=bux9));>IxYpSVHe4;Ry|#HZV>$An&d{&eSJnab&;B=pkR1o*O&_A=WEPnL4J5 zgA*~#9Lnky3I`%8I?P%AO#U&0Pv>Wx3T}I8!N7|a&YP6SX`dcZgA}(Zw{Bb zAzUydS7$%Rhdjd{nci>|?)-Jg@6}mrM@f0J7iRlCCu#8M{$pSGf%|nm;f2eRH*+5# zx6WrzG5#cWJXkF)AR!yJXBT)aR2}byDIf1X3a7HH3nbE-0?<)vf{=ilXx>_6-Pct% zst-q9Bn)dGK^6Kw z4S13cP)ja^YyAo!-d&YASnKM7r6wJ#td#>hR3IecSaR>N{_)7 z_PV{W2f7ptNsUBFzCBlX5~m-CUV8{+>LsY`p7`f$Nn_Tb5%-ys-Vw+^h=m_2(~m6W z3li=%^H?t&bpb1qEw?@pQ)D0-PqpFuCjiseyr2D+%Vn`68nPn3N1P2m$ILpFKU=vyjL#&y|MfKeIyn3rr>ih_Y7=Dr=$d!$j z@QflBlm38Vu=(bn<~RN-nO|u8B5>~z<0|mb2q$9yh!@4CGKTxu0zR1mr!k^aRllVm zl%Wf3KuW?RplPhX8aS+Ax*zSiqEF2f#oDT&^9GMNp%T9L3FzJme+o0qLlE^ytJvsUs#eS%SLCkfHbbh5qF=ld*#HQFHLG-!`xbDv! zS;`b;Wkb4~!{{UYH{Y^v1uFtp5ngHdzt-m_fIp{h@Ly{Z3T+yZyWcB;sGuViww^!d zH%A~Vn5AAHfHh(0cd-Ys@Wt%#b~B_h&k&=nYF;n(N)el?!gzZh++SdO6p$js9gt}L znluMzHhm@j8=Ys(49ADO#9tnU*vNLrs_r4B_&f zQDocM=Qn=w3sMl!`&EkEj*&#Xr0AR8PYFV94#5ec*gU^zcZvrHiIVS8hsP9DQvH2l z^Mi>ek|bmt)=o0E3L}rqj+@*kT5<59;AqxX1YFI;$M{NEsR*Eto<{dlDdeyp=uyBc z3|~B!YV^uf#8yJ31pH8kFuo-x_n)~VDmC{L3gjbxQ)oemVm9K+qB9RgFiGX))kAY- zI+bx2C;x^X;HGU zeb+O~N)-XdiT=?AZwemY!eSRmj0R0H<3sHtC9U`?L?wqqNyat%{m5V$9uo zm<9+8`A>`v8v3{|z$ib)VD5t`#_d50ecWz-&RMIP22OUMj8F9)1SuoNz6xhV_mbRW$S)eA5F5iAh)svkB-mdC@Qh@ZVwR&+JbKbC2M zxOqJ!LY#T$NPJAb?Ac$8t%s`GhH$C!O#bidfykq~0QvZepmC_hFA_13HMh*#ff=-?C~u7 z!Iz&y1^zaU2to;ck}rA99GLKs9-mA*YX9mIu$rA!Q?mO}OM=SlC2)M9bKA|XO`qa) zB2XlUC=2!y!q~J;ubt@|blD9V0SO-xNn~^le&z?i(>I#UV5og}`pm*-gm9PbFW|acqW_76q=x*+$=S{fqzfYfY~GeH@dqC&q-|s9G(^+?0PlJa zpiDNHFTQ1MlJK3yP5k%P6*VZ<{g9s~0Ug+>>#~5}^v$S*<7jMx2C3J^>h6b&XyvE} z$vzl^ZvPMOh$@Ujzi-Ao0qc^7k2YO8E^66j0Mpb;3HM_BB^-^Yr|$YSs#1K3iPdMJ zxbmrGy}U!;MpnkA)oa0-=#-e%NZHW;DM*;b{^DM;{u9(bp~t~f@NF$Kxrsg&9tO}2 zE4f2Jce_JK7&@zcVD#~Xbo+!h$(4=paS3d{8Q;GKk8gYMEIWzq6gEyxoLv;BPRP2q zZ3KIIP5Qwi6eP%vL)*%5ubJ=&84qx1(NPQOGWFd6$7tm0HXyMxv~fKsr2iVFnK+3V2IXfP3dWEc!a-LQZ_9*WQVrlO+Mvi|>_p!+XGL#5sYVOD#X zUPWh@Kg~xvOxSw;93Ur@zNri^ZQF%lwuVw*u{dNst>BPD=@$G>^TQ#3-!2TFp~yZs zbSR>@5g&6o@(dL5!*3q~M8VcuWT!pFOSk$G$6_mJ8^3V0R;eL>#ys1qmZ0&PAmr$n z^ey{mHh2ps_b_e*33voIo&u)1-3mXLYnoIz*ZQG&gm@5%M{Gv2uU{nyO(cZ`^RI(7 z;GAA!ijxXBdqwfS1&}s98sQ;)0P=)dk@h`KesPyRK+0@?L$k3+OZLel%>hK zHswc;k~qY}EXLb1=j=fD>Gx}9nE?6wE;{BaaMK(hLB%a`HpY{05LmKm4&T^Q+#lezKVVDmQXOv{ z7Jc@k$FQV65h?4l7FjH#Qz9UvMtyu_e38GwcO;*Fw_Vjy&;hl4?{~liiy^84W04Yh zM6i42*U$Z{O2JX+vxvfotJS?by?<~d8;l+pW4m6&B6alltmc|8jeXB>a_enk?8n#r zfILGQ;nI_9RnE`u{t6>zjcsfYE%%tdyYK*AZ<9Yku(Lq`qZn(W@03_w-92-)U>nVR zvF<)S`X_ps5g!sM0J#D_Ii5~u*Njwj#CeuL2Lfd}HUF&G3aYo>xPXtJ>!qjT;_52=))8X83<2;?e> zO|<3{%h|J>=)m(4q+}yxR%Gi9XBi6igAVQ!tAEIVwAEoWT?NWT9*3 zZ_5=g=`h>yR-mCjBV&>;z=^WHm;+$!`fRCCxliBV#S0nBb#^uL|J0$ipxL~sIP1vWM_E}gMQ4%%F&}@`_?B;;GS;tzdC5HHfs?;{7xR%J zbWSOv*Suc@KU)KOLyiztyD6)S^%F@Y1YUOZZ{j*g9EFRsS52A!ibzdqNs*^ufRjYP z5P;iCRfoG1(@tEFRz)z$~=8H z?<_+wF{6k|Zcrv~{uI}fqotYRo~d@*O?Bh2V)6RIT>S!l8ka~34#yc|}!hqAoYurw|_C&vsc1K)gPNY7GFJg>_1 zDO7siTbYdAQshP1Sr}sF>L*^*mBFMSpSVVTMEKqZ`VapvTh-8iU>^M4drsu<-g6iJ z?md_OcN06kf123A(L!(g&x6(*{rzW+{v$`oiTMBX5xKrUU~S9Yb4(IRd@a9_!Jg7M Lqn@dD<<9>B*e~+` literal 0 HcmV?d00001 diff --git a/requirements.txt b/requirements.txt index 6760075434..69eacc5a4b 100644 --- a/requirements.txt +++ b/requirements.txt @@ -17,7 +17,7 @@ Flask-Compress==1.13 Flask-RESTful==0.3.9 fprime-fpp==1.2.0 fprime-gds==3.1.5a4 -fprime-tools==3.1.2a2 +fprime-tools==3.1.2a4 gcovr==5.2 idna==3.4 importlib-metadata==4.13.0 From cc368c2849eca048e4cb592ab7eb1fa6d4aae73f Mon Sep 17 00:00:00 2001 From: Thomas Boyer Chammard <49786685+thomas-bc@users.noreply.github.com> Date: Wed, 19 Apr 2023 17:21:22 -0700 Subject: [PATCH 168/169] Bump tooling and GDS to 3.2.0 (#1972) * Bump tooling and GDS to 3.2.0 * update FALLBACK_VERSION * Adding CMake User API to user guide --- Autocoders/Python/src/fprime_ac/utils/version.py | 2 +- docs/UsersGuide/guide.md | 1 + requirements.txt | 4 ++-- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Autocoders/Python/src/fprime_ac/utils/version.py b/Autocoders/Python/src/fprime_ac/utils/version.py index 425ec97d78..b8e8ed567e 100644 --- a/Autocoders/Python/src/fprime_ac/utils/version.py +++ b/Autocoders/Python/src/fprime_ac/utils/version.py @@ -2,7 +2,7 @@ import os import subprocess -FALLBACK_VERSION = "v3.1.1" # Keep up-to-date on release tag +FALLBACK_VERSION = "v3.2.0" # Keep up-to-date on release tag def get_version_str(working_dir, fallback=FALLBACK_VERSION): diff --git a/docs/UsersGuide/guide.md b/docs/UsersGuide/guide.md index d7ddc0bee7..121b89bdff 100644 --- a/docs/UsersGuide/guide.md +++ b/docs/UsersGuide/guide.md @@ -83,6 +83,7 @@ This section is divided into three sub-sections: - API Documentation - [GDS CLI Design](./dev/gds-cli-dev.md) - [C++ Documentation](./api/c++/html/index.html) + - [CMake User API](./api/cmake/API.html) diff --git a/requirements.txt b/requirements.txt index 69eacc5a4b..3d4b312cbf 100644 --- a/requirements.txt +++ b/requirements.txt @@ -16,8 +16,8 @@ Flask==2.2.2 Flask-Compress==1.13 Flask-RESTful==0.3.9 fprime-fpp==1.2.0 -fprime-gds==3.1.5a4 -fprime-tools==3.1.2a4 +fprime-gds==3.2.0 +fprime-tools==3.2.0 gcovr==5.2 idna==3.4 importlib-metadata==4.13.0 From c87fd5eb7a4af72fb5abc3566331691094a9cc34 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 20 Apr 2023 09:57:32 -0700 Subject: [PATCH 169/169] Delete CHANGELOG.md (#1975) --- CHANGELOG.md | 125 --------------------------------------------------- 1 file changed, 125 deletions(-) delete mode 100644 CHANGELOG.md diff --git a/CHANGELOG.md b/CHANGELOG.md deleted file mode 100644 index ec5172994b..0000000000 --- a/CHANGELOG.md +++ /dev/null @@ -1,125 +0,0 @@ -### Release 3.0: Release and Migration Notes - -Version 3.0.0 of F´ comes with several major enhancements to the framework. This release contains an update to use the FPP modeling language and the C++ standard has been updated to C++11. These are fairly substantial changes and users should consult the version 3 [migration guide](https://nasa.github.io/fprime/UsersGuide/user/v3-migration-guide.html) when adopting F´ version 3. - -### Release 2.1.0: Release Notes - -This is the final release of the F´ version 2 releases. This should be the chosen release for projects unable to upgrade to C++11 and/or adopt FPP. - -### Release 2.0.1: Release Notes - -This is a point release that repaired some compilation issues with VxWorks 6. This will be the last release supporting VxWorks 6. - -### Release 2.0: Release and Migration Notes - -Version 2.0.0 of F´ represents major improvements across the F´ framework. As such, some work may be required to migrate from other versions of F´ to the new -functionality. This section will offer recommendations to migrate to version 2.0.0 of F´. - -Features and Functionality: - -* New ground interface change improves stability and flexibility - * `Svc::Framer` and `Svc::Deframer` components may be used in place of `Svc::GroundInterface` - * `Svc::Framer` and `Svc::Deframer` delegate to a user instantiated framing class allowing use of non-fprime framing protocols -* `Drv::ByteStreamDriverModel` allows implementing drivers reading/writing streams of bytes using a single model -* New IPv4 drivers implement `Drv::ByteStreamDriverModel` allowing choice or combination of uplink and downlink communications - * `Drv::TcpClient` is a tcp client that connects to a remote server - * `Drv::TcpServer` is a tcp server that allows connections from remote clients - * `Drv::Udp` allows UDP communications - * `Drv::SocketIpDriver` may be replaced using a choice of an above component. -* `Svc::FileDownlink` now supports a queue of files to downlink and a port to trigger file downlinks -* `Svc::FileDownlink` may now be configured to turn off certain errors -* `Svc/GenericHub` is a basic instantiation of the hub pattern -* Bug fixes and stability improvements - -Migration considerations: - -* F´ tooling (fprime-util and fprime-gds) should be installed using `pip install fprime-tools fprime-gds` -* `Os::File::open` with the mode CREATE will now properly respect O_EXCL and error if the file exists. Pass in `false` as the final argument to override. -* Revise uses of `Fw::Buffer` to correct usage of member functions using camel case. E.g. `Fw::Buffer::getsize` is now `Fw::Buffer::getSize` -* The ground interface chain has been refactored. Projects may switch to using `Svc::Framer`, `Svc::Deframer`, and any implementor of `Drv::ByteStreamDriverModel` to supply the data. To continue using the old interface with the GDS run `fprime-gds --comm-checksum-type fixed`. -* `Svc::BufferManager` has been reworked to remove errors. When instantiating it please supply a memory allocator as shown in `Ref`. -* Dictionaries, binaries, and other build outputs now are written to a deployments `build_artifacts` folder. - -**Deprecated Functionality:** The following features are or will be deprecated soon and may be removed in future releases. - -* `Svc::GroundInterface` and `Drv::SocketIpDriver` should be replaced by the new ground system components. -* Inline enumerations (enumerations defined inside the definition of a command/event/channel) should be replaced by EnumAi.xml implementations -* `fprime-util generate --ut -DFPRIME_ENABLE_FRAMEWORK_UTS=OFF` will be removed in favor of future `fprime-util check` variants -* `Autocoders/MagicDrawCompPlugin` will be removed in a near-term release - -### Release 1.5 - -* Documentation improvements - * New user's guide containing considerable content: [https://nasa.github.io/fprime/UsersGuide/guide.html](https://nasa.github.io/fprime/UsersGuide/guide.html) - * Auto-generated API documentation - * Rewrites, edits, improvements across the board -* F´ Project restructuring - * Projects may now link to F´ and F´ library packages, without needing to keep the framework code in the same source tree - * Usage of framework can be out-of-source - * `settings.ini` Introduced - * Example: [https://github.com/fprime-community/fprime-arduino](https://github.com/fprime-community/fprime-arduino) -* Refactored `fprime-util` - * Replaced redundant targets with flags e.g. build-ut is now build --ut - * Added `info` command - * Bug and usability fixes -* GDS Improvements - * Prototype GDS CLI tool - * Project custom dashboard support -* Array, Enum type support and examples -* Code linting and bug fixes - -### Release 1.4 - -* Ref app no longer hangs on Linux exit -* GDS improvements: - * File Uplink and Downlink implemented - * GDS supports multiple active windows - * Usability improvements for EVRs and commands -* CMake improvements: - * Baremetal compilation supported - * Random rebuilding fixed - * Missing Cheetah templates properly rebuild - * Separate projects supported without additional tweaks -* Updated MemAllocator to have: - * "recoverable" flag to indicate if memory was recoverable across boots - * size variable is now modifiable by allocator to indicate actual size - * This will break existing code that uses MemAllocator -* Updated CmdSequencer - * Uses new MemAllocator interface - -### Release 1.3 - -* New prototype HTML GUI -* Python packages Fw/Python and Gds -* Refined CMake and fprime-util helper script -* Better ground interface component -* Integration test API -* Baremetal components - -### Release 1.2 - -* Better MagicDraw Plugin -* Prototype CMake build system. See: [CMake Documentation](./docs/UsersGuide/cmake/cmake-intro.md) -* Mars Helicopter Project fixes migrated in -* Python 3 support added -* Gse refactored and renamed to Gds -* Wx frontend to Gds -* UdpSender and UdpReceiver components added -* Purged inaccurate ITAR and Copyright notices -* Misc. bug fixes - -### Release 1.1 - -* Created a Raspberry Pi demo. Read about it [here](RPI/README.md) -* Added a tutorial [here](docs/Tutorials/README.md) -* Updated Svc/BufferManager with bug fix -* Fixed a bunch of shell permissions - -### Release 1.0.1 - -* Updated contributor list. No code changes. - -### Release 1.0 - -* This is the initial release of the software to open source. See the license file for terms of use. -

    x$XCqwP{a&H4|Mgjag4F}~1vqo;r~&OzKwS>n&I@jmz|Mcn!cRW2E@K~ftM;UkbAA?wsR}ky-mC=2|_$@~DhSNMX%w!_*w2NY88A;lJbOaSH zZF$e?LoT=X)Xa}2=Z)AE{*1P7S$)Tj^psdxKhNLAY=jEhTqK)*%u7^N7kc=cr5(Hx zCy*QfgRDt2eivgVY=l(#>cZY%16+?F?sDXNqY!P(K-la466aD_%?eDNpUUGW0b%wW zKT1~t8z7iC+PQseR>#GCES0sdO!|Onp^p%9H5KD&=$esynR^@MYIF*hdceC~wciZo z>UzsXYUWFRa%2Jtmgc(bhICihiX7xOZ$0s4rO)xso{<;QfUu6s!&pr*=jfg}uqHhc zY=xHA#4Fh{rCuvrO}hi8s}Et7wvl0oIBk`aq=O6Apd5%NSe+p$V`9(2mt7#01chU$ z&QxaJn^(9|RY{(1_V#;I(rlYJ!LCeAUY5ainQ6N-yC!4+R%SV>F;(f%4tN6i%o65x z$t~?^ang_nc-Xh|7_&j$*;b7gG8g$&sdI&q{Wufhq%TIKn}%I3-gW>dS1^^R?_`f8 zm!5%b<>;oigP^+`5!7fpXfSLnnk>g)(H%fGK)x~G?89p*c+?4nzW7b*eY|OZ|9-7K zX}QV#@Js562Yna~eN}Z8ag&R~mnY)t{$avjyZXEw1+wA7mm)OU$Jq@$kI}o+@@(G%at7vB;Xs}ai-XKCDr zD-y}*&ir6pqR_NIKCVG} zkkG88e_uffGG=xtXuU14<{Dnt*-el2Vs6D5mh@Ma;4OC0JP8!6Gwc&sjV8R-J?0JO z4aSWbk&(oBW;)%*?<(g?r>G`6HL_>FJn4#iDL5iGqG!VAdY5%}txPRzq29-BqzgQi zD1ENjS|T^8$azWIGL~QIG%P2!jC#VB`bkCn;95D-)$VnQwc=Kj!H) z>g#993x(IL>rQ|Nu`EtX>X*!l%4wJT*C_CbIFjq;E;;cjNTo;TQDw}^W9k^W)g=0N z;5MjghwRi4{U}G0`fAYQR|uTp-s<}X;%6H6Rmz1#kQmp@{nKwJn{0Nr>q^VZBbIsf z&gS$=2Ne5ox71bQxEL#I0H0FJVgyw1P$!U--MHQ*?A?Xh9GV&LLZVEyTrbj~3Y7}R z)ej3~k6Yb}&ZC}BC^MZ@1`wI_y{?yyq$rNm)ZY!n{3oVwZ$)UJYUTOY6+7yJ47PN|w z>gSw$4kL(l$?R*xNNNs@lZW{3f|YHOU1IGQ11@ck1Il$X2eVMOln*e0o9)U*X<<|3B9JS%fa!1k5Q1_B5k)ia`dlyr+y=_u1wjyS^W;0Y!+Q8n(dNNo( zkuT}xe|Jk7{EVy|?Oqep`y4?b zlW1e>cX7NEej4H-Ns-uk*S;(|nTa&&2Rq#-cS7)*L8&E#+A^J3@Wzz+!>fntd8Dlu zunTXx!ZgUbtUZzz@5scH76);s;5|4v274Z1+^nq{f*(KVJQke_%1=fbC@(I<`y&IR za4fjvTb7Rssgn$pou-z@rVkJI(Y#t+>XLvW>Khzyth~}x6s1mdS>?j{A4N?iQ8ouL zK<X*}sMAvYkf*vP9W7 zzcr49fs#J<)^4(W;}?MpdcuR~*2yk=Ir%DF1uXCS<=*!al)fhWtr6b9=osE_j)-%5 zkKH7}{vc|`_;3�|gxQPB*>@P*yAJ_lqqi#Zj_^st+%fVN@+mE~-OmZbj`(tR|7R zYi85g>0(&w&W~|ZzIbR!m}j&mDG##83$f?hP-y!{d0RfS^{jd;;UY;$b}4nl94hEa2}hro6nTTR&FLJNs$8nkyl-7Ep-x5nb|?_*4g1WaQqquB z55=MCi7BnVvI%6zno-R`B~p#v3?cJ-By_T;8MZ>YGR)>c7!NZ5He9Ye*D!{ULK*4> z)}M)^5e8hKXzA86!|g>2VMhz2?Ez}U_E|?Smf<7ZHgU-MhdHDrK#^2Of)eIyzO&yI z&LX*TM99pX=OY$#J!L8X4%=v-ZncCRY1zFkyrp!;s?7d<-b6lCXF6k4Y$ccF0kf}v zDFAN*$2<#}VVEnc61?Y`UC4JzE!vlfI)UJ{+P+FL=iF~-G43keGJy?Zo=$;r?;fUb zLbh0#t?q4|xtlACzJ`PPH6ciO&=3q+b)RQH8W?T@naRufI5@~vH z>nps3zBcZ-!0)Pbqh+gOE2?r$#@EEYPIS*SB+tvZV-hGcv&vMuD{p&Zwrls}T`$b0 zd?yh*8*cYE^MobN_dX6c7|Pl-mMC)2D0Gl0;A)t({s>b{2CZ7j)^X=j$G9uSi30MB z)0o;*OgF{s@=3KrD)jse-6sC@QZ?-+-Zq}L_11o`N%zU8nj?Y}tTLiOJC%yc zpGr~`Pu?BsREI29{*0%CWlM1Do2Kb^BXSxg@*|hv%Kla+^*tIg6{_J?5aqt11iET~ zLshRzpnY(XHY#VE@yDdukru{cXUvy2rW0{~Ku&D}7IiiFcb?i-zi+TSZ1c`8^%L*z ztlxdhC#FU=-hwGLnD25IN-A5fM!94+@;lN{+5BzRVPrX>J>dq20dRGW$#iK#YPp%U z0z@-r;PGN{>xI{*qwzuV9E;^xDMHr1CnCZJCqi7v08YGrg9Ckp+%a9C$>X<;VBTNt zQi>?5aF|pzQClDl&K5PdZk*vgnrxIf9LSwS%!mpMpo*Kz_A~0;+OB*$eHRy|{gPLl2H$ZFxV%cLkW65AyW08%VyYA`Ge|N^w&!c(j z0jX{=(rG(ZE%3xtMCX(;Ji6Ckzubn_EgZEbKGEFvB!!o~)U7&$zQ_-%?$x?{HvIvsZI(+#6(V zlrySJK1g0jWlFiAdG97q@gvNg(Wg}nr;HoOxTs<^X{}utN|*fp)yCGxnlgvM4&0O_TSx%-q`MJ z?e!bnkMNN}Qcnd3)Jrt~_b-yP( zYw56*P%-Z9?FX2NS6kP1EX_ujgdM)>O=0;Sd?&~kQG8kE-W88 zE<>HzeuKGv$0L11C6nA04Rcthn#MeqLC;JsRFV636$OKEs|p|eGaK8qLa-^@pt47*-1= z`lQwF59?c3lRPO%Otx+riKMP7Kpv=InbCg2%fNO}k_@d&j)b&Xjt@iO^8RqmSvrcQ zg*~QNf%TDQ_|Qax`m*JuUO2d=yp)S5SOo=PPI-pG6J9rCPViUD#Ya-sZ_IF-(U8me zh=OR|wGToh)a_p>its$6wP{ZFax$U=#alu@flkHr^8ZyD6bTKAo?2Jr@QBNWf8 zAht1N=V}v{dTe_@*J3qSON(xbiE&Ca{ffH7ayhwrE~1t=m>ubh!)>)Lmy@{ ziy$oVYWE@OUi-l;EChA2#Dn$R2|D_k!b1&n0rBKyn3`VX{;lv}{1H=mR9h>E!}7tp zh&h4~ro^E$)TZM6YI$VzeL(#ff=JZU^z>GJUq?2$=mho7k|WqgNb(Z|vI8)mvV+EN z$#2VU!7;V=LZ4zH+z_2xPvp@SPJa$u%|e_*vw$@CRRtO3*s|k$swvUyMdFXx8Y{iX z6Vh;BPy0>i@AdBQQ;g|ZOgW=bS4}_}DpR|Qw)}K(ngXQ8MK<-FIfJlSkKePd7|yDC zr7PeH7aq@%Mo@72awaUa;kqO2RU4g<^)#wI2QKHibU%`NgY|Y4hFo7}o+(C!_N=1m zVAdlLk)R0lJaQOx9%AJ|IOp|Tj%=XxTqhwhL;-bfJU$LcTj1cKVe7}I&ESj#Jx>+=AijXET z7TI6sMh|;@D@ey^vps;1PY@9|5zwPu^{t&K@6IVQC$~&MJea$WQZ~FU&OVnzOHw0n zU4!~D(2Ofn=ge1pD;=sd+3F$>YWPNZd5zk%6A&H*ACrcjA`8xMpM zY@WKo_v;X&+{W0@fn4#HkJvrg{o?G&vgMM!%Yemn_SVerJjsH$6xIya_t*!#vWJkA z47Phr_pc@31UJ<8tYyGhk5mSVr398i+vX}dT3a1cZW$Mzj-6KoCt~Yd${Tl{q+TVj zvsc9@XiGHXG~*0ooMUUd5ok&%3_E9Y=cbianyOYyaM^2XJD;z8CWX-3uspuO#E`D^@dwl2Na(JD zN$5Xf(7usN3?AJy8VV1U!&!#&cd{eyl^Cu-Sd%vjexbYmMn9H}MXD50p2$37GXh*j z94YcT)~3H7ipHe5R5L1&F-4{IPJhRA%z5`Bbb1rYVt27_cN-(7nE1NylFkz*&v)Zw z<6%Z=JYew+s;zV-LDo$@@?_`!Ya{!Y`3J$m6ZAQb&F)j-MzrX;qRrv3AdZU2 z2Z%F}E&-ka96c1aXyf3ef}r4t%Rn1Puqp!T@lO?=@4iMqvAD9@Ql0|O44@aNmTQi# z^V6`J@gt!SRMEdYpXfSOSNtW{SQ;jSq}Y{ zi59ixe6BJ!^W)!U^^&Xs8pKRTMv==Fti)Kion>Bq4;61sS7>7kgmMi8EBV~KO$fCV zhBh20t~~_SGwlvH~OJ)bHPdr+R;fl)&evCxPH0E|;wA8Ap zKI`U)q)5Rtn$ZaRICxNJj?v9h^o#B3t1h6>5L2{Dfg!_!6zKJ~vyn2}#A3pw$>cQO z-1$)jz4W&-y9+9q+eNc$$4kR&HUZ#H_i9jaDN!rY6q!8OKz&giIkDwsagJ@0*_99@ zu_ANUwR>D1v2VX{7Uc!`@n=bL$wlHZ^GkaefA<|W=4{saX+aCcK-II?VCh?uL$QNb~ZD~w}9&*k-oiZ@_JS#SjE&chETs8X>ak~B;n`|l%qIDg3> zWlAfn01_;&sV_>~E;FA_ZG>>FXw&})jVJ)DUD+XJ_>o=Ua`OPm{IlYV13qxyl`N6=kb9O0bxd;WF@Wr#CGn6`UC=lH%0;?#}96v zFHrdgxPkA;TxC;`Yo3QE#IVle_pb+Bhgr)?RNQM(-(u669x_(me@%EOFOq`k*;dg? z@)tv=(){keg7-#UG(Ko(qExU{QDj!y)zYjZZ^`*;8&>Cn&$KZ&>(L2G>+0{rVf~$X zj2zuRXLB?3*IxRxU^}~5Y7>UPypJhqPqRT_YEZ3Xued7Jd#cEC4 zPGW(tO@$23@8nAZST2{%3a28UCohkSC8#L$mK?`TNxIfOr6|t(8zNUM5TG{%Rx@Fc}+%U|P zlsMKO=?*+I3<)I4fjwAf$ zOScZ86#@e-4iIZU&y&xgG7u)~PZ*C~V{jm9K!w}@9ccvaLcsH&S!2kzMg=G67wH}k z?X%mG4`(97#V`~MvE-5pv3Ue~xg2aNLRp;);XD&rP`|;-(m33=n&|Gf{-)tmqv3;^ z;sbiLI)8ZkIiX()?~KOuB&vt{irLgAtYzb9W8vfg{0xxJq^*VUQTL2h zg|+Benw=mMu`@RRN9vDdgX@Uxv+bU3ylK8`zSN+)CvW4VTwQt6#4v`wWm>t~Me?KU zxNhpXV}f>=0{~Ew_(z$-Uq9!%fC`v`Ur$Z@s1i)f057Q=laq0HTOsx=8MCU-1K|+U zCJJDUEHs%V%TZ{If3^S}n^uc5nr#70&S$Dg@IEEvQPOXp2C>zLmH7&ed2luD2YaEe zD6WR2i6ZBn=QkFti+eagwLKUew#-TeQsrWqOK^k~bY_jQlpKhWY}-L_A)h3EZ_02M zf5P24Unai8k_-#4yxqH!iCGot<@E^# z3>e6oX3d%c^1{C}D5jNTld-YM{scQwDT8a3 zP?4Uq%q9CJ{8}bb{ZNa`vNWicBC)cyBDg;DcsXesK_(&$Ah=>QHD^;4F3<@jUC&)C zR3tD+7K})|LlvBW*d}wST7B9&Hk8%vq=w7k4?knL9SV$c`H?) z@=OnuXeuKIvpdp@4O5b1G9A-Wwlf1vl%9`cvtnG z?~-BTUJ3cBz^Ia|*msG#BWO6hRYL(0=LKdB1qh?O!s?M%(I_26$uA};qU%y;_O<4YA9S|9nJ)K`tW~XfGVWpPU=G+1%1}lZ= z2c8tigFG~Q$Mcb*auSb`))t}(S_5Y~LGLLF(op)e;I&uP#Mt={&)p09MAy5Utb&g7 z>|f6n&HL+amCgH{iEeBOZn9KfSHEYW(xzLzI^3Kt@LHX2t}Mkg2-c&nRCTi0^TII? zlDD<*lcn`aYn_q3NeIck@UI-&uI%H%Ep=Dg>GNX+hy~nygNY% zPoP4^OUQz1MQ0zGmYo)tc%KEIIiG1-jT>XZ5u3*Kwad_81O+`BS^!crWO%dvGK~)C zEIN*UFd&p-~$+3{MT*5_y88s>#yXf~Zi*qir@r8u*lCBt29UKlRG1d)GbzJ&F z)Q{?%*I)AOH=W|1iGI8OOh8)!pq{0rrE*+SX?z)@=1JRleTA{b71Bb% zc98mSB(98S`^8y_i|f^MkE#cyzL4)r@U~>x)}!V6J7~g8uir?$@)>7iy_7gdl-gLT z-MO3$Nic=i62Gfz@{Wia4;4u_C#aH{2+tYgq$mWFrhJ4$_I=J-xWBQuBhM>8Zbp@f zo2}LLe6kJIZ;;IwEs!s;L>x0#S_>9zxPO5qT{4YF0q?$Or|cni3MWkN(% zeVN_Zo$NB~;;QJ#gtE|30m5f`ZRIpx&3^m3%emGe}F=bM=HI*0h+{CqFRU{*!)i*d*8=W)#s8^s$m@+vUgy;-YH!=bskN6CfR*|;Qg=l9&-URudd%MDcy1}@ZW zyjfw5o{xQQJ$2-)ZkjrdDwBJ43{vUu+7mHsjS(r#B%3f%wgyyb^X@BB8=~5XAk$e@ zt@%RLL~RuaAQ0kA9x(=OE~zY*QxEFBWK9~qdQM$vmPV4ti1w)M{osBfq)6LGclhkQ zY+cwdMbt8J)|fhYhj^5pJJ1~%xjae*RCsyel>YIXg67#u!Oo{Q>JH-=;~tXPYfERV z=j{9JXYs)^$6r}TGH_Q_7w$7}1{sM;aEJ(toY>Qkc+M~Pktko*=BX5*kSX~*$3yj; zioQ1t!$CDhbf-Jm#&s_Dg!IFHG2bc~E^$X|^_-NB)}S71eIP>C(9)Y+vxmP6i^-l{ zP0L+UxjhR+rEcE3>X?OpsGp@iVrucwzvvii zB0n-fh`P#uVcYE-1cGJLyxB(O`>Zneo!0Q}T|jKogr&6f*e5Y_UiK_%&JXJtG=*Zn zZ8?1kW|{W90vr^APUg-&d{0KF{~?#GV$}}r4#aRlLPbH`gKeLp!+gS{jA;+!IGNh+ z41yIr4sfSeLd-n^0S7cSzbTK`OGUf~i`L8d5eT&Zij#XT8RBVR0P}k>IZB;s`_z}P zh$WED@yZE;{J}UEgb4x zc>WH9gnjBhKo8S36RJiB$`rzh-nR3rzD?j8h>Tl|X9dav6=LPQmYCJ-2HtuhOP-g| zOWa%8I({%}vazN5FS2>1P=_Z%nS*ZViL0j{Ph@wky+*xCcSige=bq{3wQi5%m=|_F z59-pb;SDH=HcW`Wl~}qc)XTkDuvnGlQN^GZFJy+c$HO4t3hZbL;`IG=@*e7Zu8X#L zs&RPnSBc{EMSPL6=Z?Mtk0+JJ+2%*C1c6!%h|j>xM2k>Eu%{_>|8T6=J;}poO>C~GO94Ho+T2I(k zWvtIqO=*EtUHVW}0fKG%7ZDvkxL^y715^9MpqRbtF+dAL{mH{~(>L8{o$$Z65Ew8wjrQjmAh3Yj}jcez5<#;{>MU!bI?S&dvhUh|A! zOAx~nfZ|s?do{@p}Zz%aQ=)?apVazY8Bq<~R7h(M0 z!Nq?CkD&S&O8oyDF8+W^|Cey_CxrW%J~7|Fz}OZ6Wkp8jfkK`l&Y2Rnv-|1id|H=Jhg#VM|&wTwK)crqd`g7yK6OjHd8|=TZ(byksG$X?Y8%@jbHycgOr~&zZ!A4{MgN++kcSJA2j`+7%YDkKgeiiX6BFI z!2gbn9&LBgj_-Tr;-s6XZk^Daz+7TmS~GWquldFOJ(3$AR)|~RoX?lv*V{HYJ;xa| zfsbE6?W$~3#%km{AZTxF$(*aSalL9asbZa}z@xIL!sz*LhFY}VhR%uK&j(Z^=o9QW z=yVr)>kI5<%8pCwx_B1+xc#RBwTa)Zke9{4HK^V8LY3bZF|qkG+^1s0koTfEk~SZv z!>CjoWZsx}$`09CT+KfLeWe$Lj+cUn*pfiSzU_CXp#VUEaZ3G;6 zbe2EsW+YoM*9E`509VjK4@DC6I9$IrTvX2f4**L*w7>ID;%9pP2JR-4rHUP?K=j~V zsTVnn#H3#B>Eh^asaz^<9~?D0rNj<*QH^tGZz+a5R*O7_d@<5CqoSpABDBrDbUB3B@VfnJWDqp&jHEp>04$WTEHPk2hFi0O>d?3j=JIv=Cc_Y#mqy1c^{RO$s-ovooL+)gUP&>p9<+|9L?E~s-c8f~7 zx=@KG3l)F3P;vWeI@urFzv~5zN&(WqsOO|oGKADhrR~YS(M~DQ-Y`Gf$v)l@OGmd3 z?Ze(886<``c?(Z|i^Pz|BefzeK~hnB8@0Dd8`37EtwR~9DaKwydIRZg(g(>v z8joaV2ix(OPIjO@H7q*R$9~UVA%4vGe)c<2zQJA=IEN0~dC8|q^FFoRL#)kuv<y#qC#rEc7a8qZQ!u11Y# zsY_O(#w(X^D6KUH+v~4bJyOy@Crfm(h?E>1Crfm`0Rzlkh z+V&hBh^c6!M#oPM>x}?ydyTd|L)(_qwiInk(zY_%7NY}4kXLP zaX%6<^Y%ItVNao~X^%|BWzP0gRdf$^@T+!3zl$7+eje#$sD2iCF8WTaQ>N|FKcVHR zUD3B9H$`8q?lhxiZ>p1`*b@_7cSiwnwk!#jfZzkx|iw5piN}{=@~# zab!576I0WpXW@P$A{R!D<+$grXk+ApXhXhNKYq=wXdk>nI$y2C%l3+hhbBtI4W|s~ zr1Oj_(`M5&(>POqQ;n(06gNdp#ip>yYj&G;v%_pNYi6@qHOppZCT4GE?y!;OtDaXC zi=PUFrbHHX9UO*oHiMinYG&jdlJQ8R+2~2b=;%z>Y%==7Smwl}L?_iIOwTBZVKn0& zO-4^1mKm5H-D%2A%nV46&X~rZKW#guw>G0S!`63FGI?4j&GDu+;f#CuwB3YK*P2_x zysTJrOLH>`_*OOs8r?%&^&?08m#kGZwvI^u_!s!GnhvCkGn+?GnwEL8xH(h9E4kw4 z(V3r3ip`j|n|?!&HI3L!|A!aN({@Wk=r>IhdAl@ZM04}#PC8ZeBQg3v=m(5JfqrHz z%)B3onM?Bh?#=g0;(GKe;|2OzEF>xVB`p@wPo})z_T^S?oDn>uq{`NlKQIEZ(Y zq*EPvTLW*iSPC8g6Boogp&7HY8-m7jJE&1YSCHk+Ql@0|WCm6+c{-+H#`I}>AWQK@ zVtF$LxSXcx@}9f#afmv}w-5|_c~4q#S)o>#ixq`ZbX}e%>E%6B(sR2spDdAyxmuA1 zYg6`+AW}$qj0EKrf&P>G8`5XI%+Ak!#?SMTeE~+-SxAIDPM)Fj$undhd4V3oRolpJ z(m}WgG=khut|mVx>#(d%N6SrQB7O?me@=tB4rnG1V!?cn>_^}8$hBk-@zFr;b8;P7 zBfW{M)(|@>B}2)0vY6aL&&^#%W{?l%8^{21F1eH}p>4Toxm$C05VJyB=?XH=^d7x#K2S9(DN5$8M#+#k!kMY-1m5cIJq3}Ad@j< zKkZ^^+*hqRMj z_;r%!$suY}j^!T79V0_&7mz3>Zoo&RtDVU{Rq#kD$lV6ip$U&N*zhR3N zn^L0~%9Xjdh?n#wQ}DKr;mS|xzu2|-T_?RPkIW5&lDCH3&S#tamV87*w3?2iQ&}&z zm^~mZBW66YFMe~#e9ZUVxcdh{qg~9#4oDBnPsu0M;_Ts^0}x4(`^YcIZ>Sw3jnU=w zdipl~mg(3WK z5h%fyLBjkwyPqAv?;!h*M(q*c;pDI>ihy)XS$IwAdlUryHKs9Y+i zT^ zm`rQvw^9yb@K|8c0O@0L16j!aOpbz%*OR;G9Qk5$E2*VdlfRKiK^47}OVvuXh`!3^ z%Nv-7b`T~%fzj2|GAb!vawBb#?p42L?~=>N0a+s-NKfPK53pZJW8`DXL^=-?a1B{Y zmgZKIRmwE^kMv?9(WxXU9|m{3TB?!bD6a!onE{@*3)H;_d|;?F1}y<#&bh#gDc}(I z;&(UrgbWOt4;nuYT^VQT$;Os^aejzm%AEw ze4KnjZX=J=HQB4k5~z~zg0|09MzRCS$Xsu>fxXKnvCTh)FJ?PQ1LO<*eg()3QJy0k z-mA!5HZiwCnwy=EdAJR;U|_Z`1OK_n7(Qk4P@{3knGJ&n z)ejududcSHZ=dQjdRL_@dsURDl4Xg~cr02{90`Yl0l%-v>v6kur^9ZuY8JCeRb+`# zQq`0g*&55FS~GGgan@PA`Eg!i~sOhf&a5sBtl=BTKT5%o=?Zbv;H#|5#bz`PN$3~h}y zWk#-?x1p(ZMDHrP-Kq^w44u1GXBJp?bJVniVE{L4cg9#*^VJ*LWvPg znP38!;x=H68qI(&BG!VKY(Qd)E&!^LAV>hO$7JSH|DGERov z9NS*iwP9nYPA+Us+vX(Z%$hMRBhA7+nli35o;xDrzw$`n$3xs4GTFM*&xWN9O@a9_ z-g(1@b+OFW3DZuyHXP@7Xl}+ma4k!YY~3&tkKPDKjpnj=hOKFymZ59#NC=imF{=Fd z@=|ZIbwMm+NeoNO+pwS&pb2frkcq3}?V*sdJ9n6bnqnI!PfNrzjp0P|tPzpzUb120 zsvSWi7X0a%-c{RmSAJr*JDi1z&3<}iE+##HPSiwqUK>5})XY-;j)}7&31(umV|bHk z35;nV&*ly!8)gp#0PxpLaaCpxATmE=8Q!`@+M4C~OdLp*rp9C0?IQr#JTV@qn z)TI7T!cTHMIfZH&I;*FiNvAWFl^jJ(!vRyg;}CJ&uXokTPL@b4(V;(crGbpc+|Ftq zRE_D6$2ov+?lj1SILNe3n3g||kqg7^#HfaB&06`HuAVbRQ}~&-o-?N|Z%qJ`JGeee ziZbTZseex0=V_WZC_{b!%jvoK^P?vvMng1?HEn1uVD0G1KRL>u=M#!~!?{8&;~73p z3Ny6v8VgI}Y+gd{=>lThGep&00KOpqc;MMV+~0 z{3=oWcv)c>nL+8oi{@WDGx#URKY2ad25IzUup9=-e!~XsC+C1_`L{f~Pypkh=*MHj zGh_-VGl_ptIR^679L^Y+GMt$VDiY1j;lklhI))1uHRF$CXYZ-&&}b?$c@dIv3Yb5$b*q#+Y@yCgzW}hKWX~3 z-7s;))=!?+&L|t+I;?qn8O}}H9V5gLt&F$wM&2dH56EbWLAEoq=pWu~5Yi^j%A!FW z&xUnFwBs4MS_>_8Jj#(sqjAoIav0J&`U+W(bL&ywfcvfE zZAc?{iT7NCbB*XPZU~2v&b0q z75;}yp>6PKF+nr1pr#?^|ExU~QQDwuIfzr#b>bp!)I5+;ictEXpAkqhToOM0FN_23 zl`2MpVHvY@K_M03w=P>;){VP|( zHN~~q{b$cB-Uo}W@=f>4{vQIr51tkJdDtDPEVdVaRdO&oDPA7mUAjJTSMrV22NhaH zwpVMfE<64CIMz7?uxsT$Y5zCKg6W29}I<@BrzFXDY-g3fwd}c!pC=}p_Mz~ zzHyt(y531^caSX(GfKl{+Tyr?NV*i0BiFtV_sN6J8#X`pd^Vbm{p9&` z4O<1P(3wTkDREo)8)#c3in0U#wF?~Js2#e_rl9g|htnx4M>_0wQTftvY8sp3bVMD@ z@wB_}j@(l5Z|~_z5LaD!3cp$(WJR5IucqmA>6ztMuHHL+%z^9#dYFE+clYKE)Bkv~ z`_Na}Z?a~*<&)VD=nc^CH8OUmhDm)&?WE(46qOnnqZ(}>8k}cR15pQ>291O6vlx>6 zRsdkD^})L_TgO|DAJLCC=nbTi=lW5-`zUp}>-+Yp?N?jmRZZpn`w!T)fBbnh_5G#& z`L*Qs}#HtVkj4zah@x2^9vL#GD5++xHNb$u+9Sab`sY>K*;6D*U4 z1FbPA9gJ)$dF5t-;%Q)b%hEKTT0V5zvJ~c7cmLWNpU(|6QWK@+DUa@} zt?BR5Q;AZOI%VOTTUWNP7`EWe2j5zC`|c;MzWRwLuD$x47WO8U>6uT@+>y;4%4V}K zK6Cf8^cUH?zCH$<$bzrtujN$vApm$1u+zvkBPJPkSKUJSI(8eo#|$StwGdTdl0~65 zMqks!+iQGGgmQ|4lR?l4Dqk2b0nms5s6zl0vup%8xO!kB;1jYbhTU1G^vpybg~nh< zVoK1uhc?hPB#<7fAHigR^b7Vs95jsS21+;j>!}O4Oj}4xI-YQ;s;M9Fxt5*m82aYq zyZ&0eLcVIq)zM##dTk~jTLYF96UJ6TUn$^{#iiQ=9*;W3-kCez;c|(}SB6E`Q7iE( zB^*WlyhBL|KU)%U;7kb+6nQ6m&ag4f?}yLc#aJu~x~hI_KhO7*>ZAN+8+rZ`l*Vv@ z4EO_WZZ{JTG%QXRYWe3JHmq(Bn^NNCZT#NtxHTsgtCdYb`Pkqkxiuu)u>1|o9yTRrN^vOi?x||d(DqmJA92?=Hi8`=1-2Z0S%2AGufLS8 z;R(oMR48_zy~)1TE;qT(bFB8z`}M3=o82Ls zD4t6>SPTr{Ihaj)5j*YIVY3yj(a;(j?JSBKj zijtI`VtC`@&+;>=O}zu1bYOe%O}d8;gekqtu>Q!csygW%1sJA}3Mg`(bv!MW1i%qs z#Nc!R&pbFms$gNDR=Tv=Gr-4rmH?b-z^Q5v3^@=@KI9}(nwr`Xy>sDp+a9{6_FS*q zy1aAkg83W09q})Ib;WB7FPd}xrtD{L|0YLo2;8$SbN$s1dLLj{Tr>On8*hy5eC6Wy zIWzA+qvZKpyR!fM6cfYOrnvGbc)-*=WZ{j(sO%iJG~&=oii#p`PT5wcESE&=4oXY` z@H4SuiHg7izAkYna{i1#cE1G3alrL*3*O)q`RLH9;tj={J&$=_w7qS6FKo7W0*=a% zWa*>yvF-t#Nr0a2(Tdz2&ub2+*WvLxoOXcF@bDKg99tn$IGjciExgpTPMN;R!3(N0 zV*K@7Gxf##b^2|(tOJMv0mJ|$0X@L*vUwl|HpSd~X+K2X+zE^r*zVZ*-+&2+`02p> z5u7btb^r{;KwDh()h$5VBkRm(q!kb*5yFI^NxHNpo&E_}0ZUK3C@x{GB1K*kR;tvL z=Zo&ShZ5{9}lD+328S(6{&gu{vRHL$im=zAxg8d2X}VRi+53n6Ve{*%ze{QsC+A=3$z?J znz=k-vGH6Hd9~h0zt}v_(yFhQHtDY_FRNYpG2Lobn&H?Oug|k)^ncj?VgHB2BHLuU z?2up_RAd=6YgSDr8|r3Q@F6%ux-^_(y^NV`UYueQ==)ovh_^{G+2+MnmJ&rVm#C83 z$(9%v#JPQLK(l3gsFhG^HQcrsnQM|Jj)$Y*Ls{A+QyGy1hIPEH%k-g5+GL|Peylr9 z2TbfbQ=5sIe&&4p9U&<$4IXb{7G4%sQ0O?$AMkleSNZ#UCr9836Lg4WW6 z6qh`4DOIkTBv$(eHtqeVy6=1NUHU)wj4X}RDto>kN%v+)u<3O3?#pkvnQIlBv4(#R zNV%Z5RZ`DxA_FF)xO6AWBNI~-7bTWkZnUWLLzgK_EX%DoC^uNua-T&ClvkGciY*q8 zyQH$RS1%GNF2TG-v8)qwAf?*4e6K=`G-|orqPjVit16#))y(gXDj=?UIagFCCsVcv zzrv>Rem0I5MZA|SR8?FO6T(o8p9f4&2+koYye}%>gD0P=KpNt55$=OpOM37OF8}2x zs0FLxSaC20Of~;kSR-);T&F?rZm6$z)dRaJ*2;n$RO^aEGVI}=4wj(tn*0KpN_tKdGNIS-!?k@ zg}>0M!TV}o_}LR5&sg;7+K2zjSl_Qt{)S%q$4{UQ9e%y{);k``etr9M+0QrZ<$Ub{ z@Sf?wXeZ|G6Qep7rNhm6>~!fRPGZI@TWC}W9~OaB7LB8*1xq(_fqH@^g`&m!|1;|S z3pgl1^KB36mHa#E70{3`=3Fd8>f2}dDx<#?HX*J^L1dAv1_Pl0Q>_~4K$FxWpV#N{ zNorW~$En+aEMShrsZVpo;rEBKTZzBbw1s1+A3CtR$jgAA$#_jcf-47BK0v>FYWlU! zE0&MF^7j2}vfF9>?Z52XH0G{L#y*pML)lYQeC~zW11~+6%|0=!=9&I|n?8T^(|=X+ zh}%WLz}>*WB=s1fus2-9TFdDLW)F2sWo0Dp_Om1b&2!-`#s^QS>MwCf@epvt@1Nw7fVK)2JqtOf8t2ef}wg8l$%e zI&Ntg12W~3P>-;X##G{%Q!NtL#WAfTi+hW5ywH^-H>bg2O()=?n%W z<~9?rTLu~ra7pK~MYm-SZvAt1OUDj6{=F@f-jUiCzi`*$H7{HqAGnUP+pj$~gf%`* zyALm0zMEd~=eOzdj*B~g-e*bMmpvE+XF{>GP6f>E?c)t?!jmkHMl~1@Tgl8NdHUgYlRm$gFZE3SpJG18T zoP$!sP09blYYnSlwt|O))1HR+zC6pd#q2a@A8&89FR{ymn*-^Vr9BK73;>`iz!4e> zS2;ll^)1zc7-+iI1yn{#Ab;cq_WcVlbgRmq?nl}5??&Xzg z8rFmHP~DFa#T`TACL#%aTFfMb!Td_}WzS0Vm9Sm$CCL!8Ok#phKP116;r9%_1ulyA zHV73h%}bXxbQc!wbegN(F!x~8`(EG+G{%TES((ToO|wRcR63yEY#CIp^;7$6qqOs+ zwbDD1X{GkA^e$Kgryjw$DwK`#2IWcl3$vohw4eO8%)rYI8y0uGPKxmiEPaQq9_F~* z;T7_>@Y8~a2+Q8AO0f^PW7j-UXag7&cAT6T;qiBP< z0YX&(LRA<-6_r@us>5%_dV?T9O*uB3}n%Zz0>`xAMR$Kevw5Oosi@zfi((Q zWY{PJXHbYa#syaPnBg=rAo%~|Y@hg##Z3K=#q86T{4$nD-FOjR?~g#=e>{UXxf?D9 zC*DM7M|yNZGiXC_4zt4!dknZfhz1qR&{swUui4z3u_#WPgl#6wY_U3s*}^od%Bjr? z+aq$wdb@Zps}5rOw8u7|EM*ok-$5f8$6^0y_F59oL`a9yxVtaW@aEkEKO zLi+e$*tm``r`gNGW_hJ;t?hT1O554Cvz<~eIccwQOq0%+SK6;|th1Y~OflEn`#Z+5 z(b5Q$VIE^2=FskD_eh&fo6V0)kC{|Ab2=P-6b5Q%W@z7i6f>%3+eGI?YCu6Un=P6Z z{LtaR<{%4eb+@^hdk=dY8gbutB?fmxUqiE5w3uPL&PuI&Fh~cr;tcDAT4jNIBIaD8 zQ`o(xJ{wb7l{N(|mOZ}1#g~jAx3jl21h7~L%?b6;se>ae(4#=yoYZ@MA!t{e(AQlf z)F~8w`yg(!M{RnZ*m5Ufg?k&S>DxkU8lAC$`YQzW+jHM;cW7Lf5+RxP+*`Zi^^U4| zJ&c%d?HW+;s2L!tJA0$GcY$1+p?85s!OfeoW>KHN{{R}t!iC^H*WHLDI=_!E*bgya z%5&MN+p^P?Jtx1p{jBl#Nk4o)QhxnpKl$*<7-ZGikg?uZ-h!_!OkOj_hn&=_d%aVfhLFF2~Cb$?p$@S*+M_jq{B28=+~+G|PGV6xU48bpOo2)X;h1oBj7N zJy;@1?h>n|C>1kNVCH9nNKnbIQK%dfJQbBM1RkPtTwpIM-y3m`k)}{vF)encIJZ#6 zN|r~+V5CRB&kOi@c?_61CNJd!A-Q}HA>X5uc#X`(Q6c3I&gnX{UfcYsk{LXmISLVHtiDuC4xbn<=yTnYi~C$~6vBE5 zR2>$NyCAr8gPoAmS+6_BTyjVASJ_vy>*-Z{A80wZ?~U1;lsyjj++B;F%XW7^EzynF z&A6e+&b6EeAtOMQ#2l2;AB?!$>Y(oak?GNk%!{H>(F8vdxk=<@SltESg<+oaP_AT) z7I4*k#od|v>kfCQ4&|{OrR8-leq3B$rx!|Rp~U$=?2ThbvfGq^ z#p3gaf+aA~cjaAAem{wq3U~$rPN&0Ml5*USD`=}f?O8LlCm5*L+iIpuW zYb%q=N(29|FwSH9Po&y{AtAxV4X)be|Dc4N5@dr%0$ioztf&C%G|s`005(mb`Ervx zx9oB77cS2ioNIHb(9q0=v)-u>a=8bgshKVne8>TTAr!24L8fpcIgCiX4&gyBjUt_r z8aVgqF;74T^dzJ+7|DV2vS-}yR^9)0ak6aeW!a^)?~NM=T20-TNwou3jhZKXSTkVb{W~>Hf7=xfSuNZw)J?A%;bQgBxFj;Gw=RLGL*MG>FSE991I z`lb-<&4|7Cs_;!=7Eb!?y-UiIG^zL?s2n%)R?3pzmXZ>mB-GC|G|ra1^2v)9D3yNL z=<~m@(K}h@uv?Wl>=!mPn5@fEGoH22{M|K+pPV#)#^CHF6Xsuh z?KeMv_`9{r9_KSpWFD*^NZ*~-cIDcWzj!74k9+7l`lYv=H*EQcri&B)S?K`}&t3eR zIrHCG?YQ~Y)#s0^tzB3#c<0K?4lG~sIl-{{z?!)ST+xJBQ@g@SFyTZ5j#@g|@*P4L zru11gMp-qy{IJ~aq(UeLH!-Y2tuqTZE5}Sep%B9UD&|i}mwa(VB`elT!tZF_bJqj#P`9cml>JJUk|qr7OGs>d&`(?L zn=X{A|MCbL?+5+7Uz~Pim%sZiy(K&UPPLprBll4j@zmMBLo)|jQ@9R73U-bRA1eIK z`lqCN3_R}=rXngok)412^?VgOC-<2gk%u5MXaMVNR9Wnn%Ah?|*~?y83GuXOKzLB) z*_AE!mdXY8`IW7GHrUtpy4QDK=m~pKMUOcYi~&&(Tuga1_+-Vd;Byr(1rJpGvFQB@ z^9Ub>!}+-3;(&95vU*$${rFljg&#-#(LlPYvaVjPuR2>kt7@vbIen3NetM;Co$XcI zclPhnt^supD(lr{b^e;TH!!o;;$Ey*q}tKwxXrP}k#i_p9NQdUJ0!&W6mNBD9F;J%DrEl(I8X_zkUb>5)SJjU`60OzM>+p&!0$1s>uOi zi<_0vNott0d%?E7qn4l5Z{eYfX>HT`>sA$K0+$}VY5kMqb&J1rZ^VD$ON(dJESf*> zp;Yk=Q${|uX6)**UWYwYmeeloeP;90z|xyX8?(+iL5>puOW1<@7z#} zxy3%s+2Xq(w7`6ceV+4D-=(3h=)1N<{zJjPdcO338T`2Ta5NVU#*}JjwYQJb=rojb zo#T~@ltab;l)u+)dXYm`83{*J6V-|$4r`$7pq1)Y!`fgK3Ig*1&G-=Zr_$GoeLKbiuckbC(fXs~3|fYYTeK)(gH zGuVG2hhcFNcp@5w0ssYq^ z!fi{9>^INvUC8RD+`jVZUtYHIX_!|2dE2<#UR$31I{Wr7=;nP>Zr=a;!I$@gkB-lM zCLIO83eo9>IEFgMbx!KEQf@F@0^TRPBUV!&B4htjk;%+QZxW+7L3ThLdI)l^(5Lsm z^|BBl^p{!?r_dte6h>KWG#VN18SbCtndEQvwEFL3_euBKAJHEP+06E!wt&r-7ATk5 zme||ukJ@%xc4<3pHXoGzkD25so#|Zcyv`{(5w`H8v8s=-Vz%P7Ho>fU7}iV+aXJy` zdFmY_c=a-enNPN(G>q|;S<_L9kW%jA1V@EqlSAh$0h5q`$=Q*jvI8a>H8sN3>ENAA z8t-Hh?A6paT=!C8Mda4Fyv2T5Avjlr1`KRIy6kxR=&~N`JsjYA%Mtt&as}Yl4CfGN z8~UP%$vP!NaL7pw+l#;c)uHUamVJKHGk=M03tl&U{gaQ}xZqa0#{cXAT1>U4DO+O2$U0i+JtyPj*tRuVp%eY)yEVpsT+S9rL`;_bMzE-aiSA}jtxgR%n(r2*zhBr zaVto?ALqqj#(98oqorWDc{-B@&VA{+KV7!qts7c5SMTVKJ$>2AUp{`-6%Vd`VB^V$ zw@_)rgrUp<`@Z{)*M9Tzp*LRQa=~bD(Gt*E5nwjS@JC6c2rl~;rNuJEI#*h#EVj(G znv3`M zFdo>Kdq^yAnDLt8B6Ntxxh0}hl`hy*_0{grvtLv1U;cz$m_K}`wXd1IvHK94U>i8~ zrmLTzQ~eKj&?uO_jaFno$bP5Cw(Xfm?_4{4-lO0m9)Pe7`l6rOjS{bgI)l~0K0zb6 zBzT|ge)|)4bI4v{&jh=Ia*)qQMJQTVY_>}_XGEh#EbaBk_^yq%#Y??8k0JY$GWPb} z0k*^^vG2e-UK;60v~CljL4%V?(6EC{h*wDP6}*L%a>5~1LXr}M!`UzKa?Ho|Tt*X> zPvOH6mG7VBlT02C1ozTCBu-9Xha2KD3ZVm>U#BsvknkaKLt8ou^EY=e@c23eZ3vg6 zS9hrvlWK;9q{FB|T&gpSU5aoRA}|?rvWyGPwfzuVjU@?e4KrO-R11NgynnC8 zs*%=_@upsrv^c zUF0B?t4?-}QKLj6POYglV$*y@waHp783-KoQ{8X)Tm5Z*xe9hOHl<4V+5Lj835im$ zHNRkMeqgi+#rz`A)_5;Sn>}m|l^=|AI8pgmIBAlUM$7g&4>&(`=A3fW+2|aHg-%e6 z6Fdw7mLA*VE&_W)Jl4N)xb7n-pi3PE;fUa@Bl&1} z7&MpqxpQ3zkmX=>JZOOf5PA^8BEk4Pr!l*WwpnY2uefG?z(H4L-aB^bA8y%u<)d@o z+xqJ-?s@c@s~>;n$}1k97MhT(nKOMr=4RUP{@s*ryu0m(1>YXH;wh=}4_*7-c=6>I zxyH5*!8v@7y_e3~jUei-9Yucbk~++zR@Esb7%UL$^{DjJ}(avCdiWUhm)~IqX5QJ8U@xRt^{+HqQ@?m zr&AH=&DSX`Q?Oa&snel4Oi71o3sbupbcs;Zbb2)bQRm&xfG7+UFyM>0SGCBsuH)LS zmA@L@aoNK0w=_T`{N|39NAB;Q$sSyH)udam>3$A0xgLPRDM)=LvfsGC(w~oDoMn?` zt0iOUvV3ScW-$><)Uw3VX4z6`I&8^Vv?yZMvDX=q->P&ibbJNzcB(0<5P6HdRnEv= z@?lx+l8?!Z$T9gKj$}D6E3+x66y^=lYXF%HHw<#Y*>En;*-*(_DNy-=YxM}{8f*Ud z*@GKeSScFw0e#%U!xxEVOVc8(59|2)j*brb?*|T?ERs_v4{^N2n5AzqW-FUzgw?zZ zp-xq&TO_CbAIb?8E+-CMSYz`>W%#-B6(CW*0+jvC5Ju@K(&ZX+t1*x8MjzYZF0Vtc zV;v~nu(zQhE*gv*(W1(-BC7)|qhJ~YQw3mDez?{^S*5Ox08AQ zwg$k+aMux8QB7uGCeaZ0=QI#p$mdcig@4Ow#A8AV7OJi(vS`8#uBEV63$wJE>uQhJ1BhMiK3;s#t_$Zj3UOo;#dd3t zpNzX)`J>$L%hc@k;b~rPgUIl#6YT+h@t51f`R;J1<+c1Y6oI_^yOzSGW&$SCCqK_F zp!+_^K6st7=ZC#ClU><8hefZe?}2U_RiZu3x_F(>Gt1 z<^w{EB-pA`iQ?lAA1d-VWXBXKsw{y!GN<5MS9~{6o{{l835HgL6?_Y!T~Mdk>0FI# zvVbtBPNDP`l;u3E^Ku7vV*$!Nq=`ySh>EBbXq1eVe@deO)iPn}gS5d(lOORv9vE-~ z40;F`!Pv1@s42(>3Hl0;49ffSxU)-$q#&t38)K~Yx};0KyK@edLrw2rWOFv~bWpwrTE& zPho=)ktmIMA_lph7NO>_c|9qw%@w9@dr{AVBzE2i_!bEhx}UF0`DIDSi>EJ857s=o zVC7xWYhQcd$sLIqLzeu!W7?c^R}Yd?caEKT;j}&5c6FDtUtBVC(4CKT-^JRmxMKXh zw|Bo=z!&LL;ERu5V|Wxv^{~hFPW@x)Z=Pe)36F|3eWdR{i1cYp16;g#&NEI*}6{HHQSfZ?@9GJqGB%}(fkScKeT^^uT zAywe`1mdlMDpn!5SZNM{17i_(k5D%*VFZo^*pk53Kqk-?kOPQsF7gT5Jb{fydCL2d z1Wy+%@+A19U;z;nWSAE$^0qAg2=~7WDr5a(&zPV$o(W^PuwQ~To&J~K4%mRm_#dSW zpX#z`X3c~UEjI9}H}Di@x$ z{4qIo*S4l5V`{GHUe4BDx@hPfZ*+?|*AdW>%K=3@3DSkTieMv9r+BzkoLAtB{mfX- zYe8|sZPJ3aQR-RdscN(NVs*aRT&E9m5AyX3H0h(=qkT<*8OjXHM7_n`;+q&)q%5+` z(HFTF`Q`*Jr$rW3v7awZRwirb+b)sjDs#0m5+f$v6ocua?}y+Ky!~vhGNbM&BQ^(D z??gN~5jHh~mq3e9l?zlW_z&Ow2sj(KC1(eW^bK*LD4Si>?&nPj<8xzHl>wTXB1=mP*W?7t9Js?&x45s%#T+xMvNs=wd-VfN_m_H}F9 zcdS|0j!(>#-?}pUQTP78Ur$S@{f*b(_``2se+@6R4jz*@An3;KnG20uZF+D0OntO2 zH^wqC7LE0?C5mf`YKn&yFNtl6nFsj?h0pPy6K*!2Z=2zt5nfOLtwvj3&m|MdE6?{Hqa2DXlu0Yevg)fimup}I^Ha-BRJAHBLr zULmU%m)T;r*gYI+hnF$GS)L*kT2OgKafn$!a;i42C>0JAAu|unrOZ)pZULG}W?<$CKwLDsQ7e zJhN-fLqp~_o`1oRVZ#Pr;4P6;4=z1x&|~GJ8e5ljzr|;v5jNKCn1w!)-?&OH^_C8@ zoMRbLHnnta>D887EjN}u>UpZ_1<7vlhXVdSqpRNbD`7+dGQEasff?o*mKoX%>kQir z`vUU<%K~kIb%AYxy(868?krE0m6!GEUp8H9w$4e-saTO%fuN3`Y4_XisJN@@&OVQ5 zPuLzVe*|Be{%y(!r(j;@Deb8wdMaf-714(ytLVckq7Sc#KD<&4vDR>x)K52;CvBP> zilvHV>lwu%ZdNZ1R`JP?1{;Ipf-{5Lf(L@CGZ+mn4t^MvqruyPEciTNQv|#a)r6V_ku)Dx;64|0U=#);9x zX-$rtVT~eQpe$&30(CX~@@ioL6Ot6?^{|GCUEjeNzcLu(R|SQN5)>B1ARL12rm{+0 zx-(LLu#%$oDI_#D1(keEji~T>K;?^FoboC|;!$zfGh1uAYFJ}UTMet>me4XHo>|x& z9?Q=%eAT?dUw~KgyOd*PPC@EU@p{gfFxPN#8L!Cq`|}4D3^%18_9#%nz6En9Owt7< zpKk%y5wfssY@FS5aI8*)M}Xpyg8BbW+Rl zSZf(n=<4FZ4PN+gk3%hC8(_ z#FJ8>u`DK4cwFX6!T_&DC3Fa~$z*l{M9N1~qXxmMOh&IUH(3Wx+A*&_ssxW~Fobi$ zY2ScQl%;CDIFSOlv~L}1u2{&kmGol1T1-s2NIUE&a~qdg9!Ffu$n3nixx-vYKV%YZ z-CCT|PI4Tu>Du#82eDnw*H6S%;<=lJ@tK|oSv`nZv|>Aq44$S26@#8}HhyS3C;QyQ zMy^QcoQPP2o^^NerWT;u+uFsy$dw-+(6+?=gEw`m?dSs4h6IS4Qu|1!-=LZ zDWD;k@|%t%M0bDBBrqnz2ZGR;!<54^W+qvO-IcV<7UkR{I_U1Pt=(;cC|@_6p-OEK z+$YylzlHrZYnM*>C-2pA1EDfJzYw9C%W{S@xB}GHFldZQV^HYEc`vzM^GBOKOQP_D2y69$t|KS9zr*xm2^0?a&9V2`$!=4M$s^#}KWTsC2U9 zn!7Rr2ny+sn0w6Zycv3EJk>6JvQ)JKDrX|qaYz%nQTA8Lg_EbJv#Toz^Xr937~ma~ zH_G_<)>D?rt&2)`7?e~_=Bc02p9Apmy2H6bQGD2mv98~=MsVH~EQ}?1e+aB-$X^TU z$!=auLm3Tvc|CEnhx{yOG|U3&0lEd_JHVLmJrU~`_m(|aOS<-?a!OUTW@Sa**|Pcx z*_`_w_!#~0M&epS(TL#c-M-qK^M%r_#>LNiV|NMHORd#*d zw6dMY1$djF6*p5}zb*$fuUQG%Z`2Sgq~t7>8M;rO=901V zKTbZ(zD z>uwCqAOp0|`Obj0*_kd^_b2m9R_MIP%+Uciw`sI$2>9iRx(4EGv3idBA0Qo;;RiJ8 zB?9lEAmZ_yBiG>3PS~lR?I14VVFY+5bnGvQ#{OA-v3Gft=UDLC8we+_GCaFm6i1b- znF8iox3`;`1YvtBfWC}FC`05ZJfppV0xB>6^S+CZY&+l@iTo!52)hr8rlS3jslVnh zmZC<_1zjm48LmxQ$aqC_*(_&-4v~ETx5j^_rTX-ItE#I*$4Amq;K%0;1t%jXFM|xM z-tX)r<e5UHHlTu4w@AltBt?V3R_DOS}S@t;93aeU^?h{T1F(urNU zzQk;eo}ySKYG56ONieH$yHCE?4TEeiXWz^lP5AqvjO zNh_dpWy~kr&;flUDw;{n3JT#q3zS5{5H#HBf;>*%Tlep{FyZD8_1aaDE%m?UT94@b&6==3jMX0wXJJYsI z(S`WevDZ&^+e#3+47f0dpO0{^^A*_8UG|n<2At?D)#vo>|N8XgV_Fh-IraH{U|qV) z2Y~`_UG9h+80WXcLMr>GF4y&7hHaDM@tIITy(a-29UohGWC5cMvgez#SL0f1wYXC} zGiSIA$#0R(+6GC^TOY69&NCx|=cgHbINh9qHhJP-AToJ#T_}q=MC1*n%T5qaRk#=@ zC`c`JSZU7eGWMqkd}odd@Nd9>KnQmGu znKN6e$v~L(Q>r~lJvEe(_DN~C)N_wjZGZmqB{BBF)Q-xR_TN#SrKu+Ad$NKUMYc*$ zYn^J;v7lZ^uTvar2o6rzQ4_?iY7C8{g=NEGJW*HXgm-XjJTuQJZp4|QM^mM~m%aYL zsu`leSDA9SJT;}%wSeKqeOJJIkU8S4>z?)ej8)5~=OzHlKeh!8JJVC|KWy7|*C^@I z7T6uK)z{qvW^G4Xn45L&0NZ&0R)}VSxx+auD!_!1q20gz1Od0@3sjWJxF0;{!RPT5 z$){@B%Q(NdKYT)f8}*)~GJR~5^9o+b9A9nqk)1M|Y}D1Xdp_?1jto5Rf@YU5cguJ# zb|5)+EK^=EXx`~zwX6ZI1TCA(c@p&dVCcRRpg7TAfxNQa^|{*)P(>-Jx|VUWp1Y=` z1o;uFbYC*(7L1_N?Dgo|wythX-SpJ-(DdZ6zE`WUpl(dK@AzeB@gy;a3$vSH{g=#lM;?_%TCWm7XhA0p2a&w_-8OO)Lv zaE!WaH^Bk(P8hS2K0_hrP?lXw>fdnW}-n28dzJ*4v_?*O?5WfMz zC&_C6F>-1#qX_0t|cOQA^me>UYj}Sl3!{b9YOHAk)Y`hQhm5;N^DK zdBj;xK}kZW+lay$EW?@|o4*4~aJ>uyZXCuN-30ox5%MN_tb?8^cNP*EZddTvjFvcw zqVbZ4+k(Y zxU=)4`W^Ibl$BNAbt@zA*(5Qj3hIX2H@XgqmMk7aV0#t5_1$NUgf)!#46bi#B{T#; zoUYs8vxkm8Gq!mu5xLZTy>E-VollI5DLk2cpYQ5^Z0~QbH5Eej(>y}g3N}+#Ia)8h&0CW;DDPlq&4fA7fa4k!_LVtl{9U zwut)0LpcjFlMoAW9*B;&+7kw$lTN>Jt|@Z@T+|3!ZWd>292j-{YaNFRNPZHh@sERc zt2z+=vFbQYKQ%+M>q|sPk_!&x&x{Nvw~Lc+?}X zT}3K_sh9Yi32)}z&0tT6s&yI-T@8G`$1DS2Mp)Nb1NHVGXA|PDN-4!cad4pHmeu&q zpD(86<&jlX)*yAftq`aOO6DR4{x`&EZXVrpZ? zqZ(Aw4vocqCie)z8jPXMl-Yc^7KM4&3)mC3^{kT5V8`_ffFSeb<9mWpGce{MG*h~Q z>r(;ZOz(9egle#S7N#bmzsI@C%O*M}v@ovS?m{TBGlOv&#GFy%BVRipuW7kY^z0m!)(t}{jS5TZ8c zs}Jue2GroojmapYJ)@+bXXVN3B(YPp%F*t@R2Soe*HPb{)PX_nB_Z%d=jpq6EPcw( zj%W>aotT|rt*N`YF+$-vA|Pt;z|+VH#KKUMz;FG4dh{s%$$|KW8qet(u; z#mvyr)PX>QfSHl?{~$+x*ATFzM59-+lfwf0l2rk)8FQ+<(0O8G(hFTOpM>|=RfH`YjzVqw^ zY;24Ktc>51=eN`OU+v3(-QfRM`|`hEvHuOggw~*CWcXG}Y1x?B2pCzvcat+RvNCBA z{GSBO@22$sthv$mQ$fr0eaq+t^=!qA%uGxjq1l+etxE+*BP(SBMuz{&UNV16l>d~A zeP7ytVJ~R`-^=lz?&bIB|A>{}57oC?X~gsmnttCOd4m6RFaK5W@9Y1!d->0j$P>{2 zPxq360l@x$cP~3Up*$6Z8(lI=+wM1;n$Af!%o2YE_yzs~mP;kYV2$uiEsn`PA4LKZ zHpB+dASUoLK<*wp^d*pGgR)H%!j2zf4<7kX{%r$}OwmIFi*fAq*|-!MHaKM4y6U)U zJ5e}Vv_DhM;5?cyQE;l;P7G2=iL21{SJGs5+XNVE=OHkXEv~bB+_npGyKr4=ux+*y zB>!on`D;cmoyO+nOmw+5m0V~0I?+U)g@CVD{??DFKrSo3Usu-+VoX4YSoGPgWiqZ^ zO@WB;0pj{J;b0?m7=ljVy>UJg9(!ft^NX9^rIRMa!chfO@^FLc z`#T90ro*{z;5_d+>!EQHGcIGmgOLkEq4z0`kk82YlGxh({`(q<%ZW>TsP)cj$9qzh zgy-{K_lQDM=7?i(`QFcl)B_{%(*>OfmF%gNB5NL&bFV>TnI)zkRHsk|^f^(l~rlh-Dj zY!5LdqJ?24%%|qevqwcVc$s*uxZO`-H~N50%XTu6TIe4pa&oh#E(zyWYxH5*S|e#% z%A(=}zuS)c#O_f)7=RH!5k6gvfj)C@obb$ceU=|yQSKAIyj8mRNs-usJ%-h7_ny+& z@LACkNo?G;;@hEu;@C<~MzE8H+Bs&Ad*F0>&_@p8BCf&8fxG!v&DWLoCMSn#rMjhm z_$_1f4>C+b*aa0-<7mU4gVAk&kkq(skxW8Nio6Q9>lir8R6`A?$=4>y%%DdQ>0@K% z`!M8oO=le_%*Xa`k=}cp>9|C%5`2W-4D=lrSjIpApO}0vrQP!ji~P_ zzy2iI{B@QR4B-P`4zdM7qvJ|nA)55`?V>Jo2T~h?Yi%_1hXQ5-2eTv{-3$VRK%8mO z5gAm)^Vlj3ixXPq+3MuL-K5HeAhN(-WK_}*XR4T)BpNMIV?r9KVk+Pohd+w1jO@n%3Ac-NTnBa>nPtc>LuCBS-{{AaJYjlGoiR(&KLeonv;>O{Ws}% z5u~a(E1!g|QJXleohH(@UJK;!bht8EFMg?BMSae+F0Dbhe%n+#e+HQ$>#Sw$gc7JJh_tC=(829DJR8D|ZXOcH z-&g->!WGB@+XE8&6OY#lj_9n}aGGI(d#H}(WgZmETv@C-K~h2HhdU9XSUI4N z{#`!QFI=@zcm`1*&LBc-MfZkz^uBu89;O*Dy=`&Lc&fDzN)ct*WXGd}sKBQBdsL{V zo_pq@m8P1+a>9F9DK2UT8A1jJzgXn#zKdU3F5^O5LWNZ3BgdKfsABMqavDG6)?8v4 zyNYDH$T1r(VGR?6x`4;VmW8>}FOlj2t!?@)6PIpnD(9PBZ^M_eE?MhV8yyA`lQ#wu zhE^STC0!cfke#D>sltEH*j!;SEs)NL1Nhu8?xRPTc2{ginnC7uc5KGyoEXOyRSR-5TQ`h?%ftzVyv}~$%emny40u@iM%dmo0;}EFA4-m4Q zxUwQ!-R4aGu;pCc0m1k|{tM(MweX6(dxUn8m+O{{dA?RR{WN?S5I*=PoWm@A%oc1r z{)-JT{vdM~=y}oCgj({?xI6~6eo)rxcjx(&M@d^hJqT1vPcekF_Yq=dW6f$Cuu5D!T526{si zkOs*kmgW=gll&A2G{V?`R}O7zVTJ&o1qTHd2D16`ZDZJ`fK+`0tM3Gg!Pi9xYkjgk zc(8p6Yjzi1Z_!g(s^;PvLLIkjgNy1juj2x2?EVZp{ZW7`CFF&vN9M_qIy^dJhhRtV z5}uunW7o1wz8V-Su9a@)9?Yzp&)E^S)xsO+p7cmHL4BdU+5l(*sHSSAs--GpQ9LBJ zN>&u8mrxiLpa!AbMd}%l!H2&KRJKK}JTQ3Jvy`qb@05lC(BKmoRn~hA#If z*A|9?xP|CASQ#M~jGecRchqjxFtRv3DPHVbs{UQh-KG;Vx{~_k^pVZvAJ_mCw)@+i_c1CjEPX(%$kTOvj39^w9Z1^%gJ zxXC8zPR{Yj>`cA+8=8-w)uHLY*JgCBuyJFvvEqWoHUQ^?JWjI)p{8hMssxC(*-vYz za@R&rkKDikvFkflAl<$pLf&O=KlWN*zGA45=52HP>RJ&=Npd`GJ(FDnoOM?oTynB( zjo^7w`H1C|pe0C|3H7fKuMa9ySd8#3bNmWLe0MJHd_ zzK}b0fHBRD5zH(lX$(>CbETzFl^2#loPh!hBkTXQ0(l zFaK`D+Iwc)Hvl(ug{Js~2V>;z3P5X{X2E>G>nR>bofEQ;r&ol zyv~l@^#cieMMt|oOY@P-+KkcWxpQ~CT4YJbhCVcO85tcHla-W)diK(e+HvNFIqh;M1?8;Y1+y%Wb$P}y+ERe#u z3D+ez+-q~cza5_}=jUjcOqr)&o+~e)uy!;cW;l>T6}U%juyP@noQrO{uPrwJDKpXj z_cS6S@_vU{f4nP>gEy+im&Um^Sq~9yEWm7iqB}zkdn_vE%ZBlGfPw*Di}MThwnjFb z{#QUPWnHh4g0X+Dg1L9@$q1;hV9%@W$Fqd2o-u_XD^}t#Y690qNhPu2Jxw-9~nP-YQG$lt8tb;|-Q(sHh(s(R*){5aIhyN5+iY zi4^_6$J>eTG8nB~rDOp_?96BxI0h~dE{~f!UGQjMa4d*J@z?PqOG<N6ps#*ie|LtYmHj_f9Y_0(~K9&e94ksw(-OBpnD(96c!ib^Gz+%gS$xM7$V; z#igVXGMP;OMaj|aBzObd2{9o8F2{KX`0?{7!{#+K~ z(o(}BB#@tTZ57J&&=6-v1@2ABeENa#1U5cdn+Ag_i4oE3p|PH>2LrTbDYVT)0#!UI zv%d>@yM&R%52YZZT8MhUm`S`0e={=@c4w>G@5=$yHp?F_>c^XI&WEpuQ(s?WcD9FK zQ(s4^r)Hxv8Hm)NDAezd zN(}czxC*bJF#CGyri?Kc=i zHX_0^WHV%~HT4EHP$71BY&rt1jOUPISf-)$d-Dg_c5A_+Gn?AyQ*Sv!A2q2YD z$#Z&+NJU!XL-gX-!m0DsKeT-dRtb}$3*U}3fp#+q*Oj1%C=eNkAeGK0J&Ult7GpOS z(m%Z({YWWL;_m|i6UQBoE|;qo@A#o4vPt66zgrPTVW$cfKXQS%;Ks#~~3Po4wj7=E?ZD1g8>8LbL zO5T=yrosH{h$%z`JSUi-Q6-tJr*<2b+wCtXhyY=P8-YctDEEi%EK3d8uE-aV6Y~mGQ*gQ1%=b zHgN*S51q)~$cE$|dgroqb6a}kHDQN}BkpgiJbwH*AJ_&HBU9m`%0Yk*xuSqhuM%>Y za2XSqb&;|XoB)r?nEN$k*pf<4u-XWg??nE)GD_(=4|r;+hcIdUMHr&)J)(Tz%*ID_ z=|}BQEwK_Vt#EkKq?Bai3s!wgDf(@d^gOV(mLFB=>6uXmGF6}M-RtYP`#mvcNJx=` z03c<$f1mi+RSmhKxV!F`-W)FlOh|9+trGEd>DjL*XWF2SAs^|TGp^MLa`K#pr8Jbv z7oFVeeV>qCws#Gb&YHY}BRN;-RnNTq>vliA()GckCp8nu%oWWCw%zmkz^4`yGYmTNS0J zq-fjB@QdjMEm;uyJH4FiPM6@0#uqL0*5b_U9Ys5&Rj0K4^W&Efinb?wP)&{aUju14 z_WbS;qg~*~;8SC2CAJ3$Z*W^s2IOmyTRw%eWYLx0#}d0nS?%E9*?5-Nua?u;S!=}J`Sj36)r{cdnAEqOhHL)8gxaI?Al6hCC5aZd;XJj*BMLj&)?Q0gC5s^-04E18b)!BhT5)l!KAt=%wv zs*x$^hJ=Y@z2(&U8>%jg0S7gis&yi&SBBm{%a#+)2_Jc-^C4{iZeugbdzKnfTg>Y} z7(L`0&y6-a+s?cn#(zlw|`2MaqZ>Lp4z;J{Lt(Qr;H- zegE4Nzp+uq&m1Q2v8cvj=xP_crX%>oTjh!OKpErLj9Aj|7xl9M<;!YgH4hEp;OaxL z+0hC&Wl@gDKCFi1QXz-71ZplPvL*^GWfzV)7gM=3t+kmZn?R=7zjm~5#3GV`2Th(^ zvsE@EOee3Wr(*f7t15tPeQ0!4@V|mAEJeF-A|`mZS?+wDqK#I>ODGUq{+%s4hE>Qa zlw0h7uwEY?P=kQ62Z$=I)+ye6dutK=jYKjS8v5byWsUecRy_-U(sMYT#-GHJK8m~- z7Y9|zR8!~0tbr9=UwWbrRcn$qKZC_!8;s#%5jIA}aQpo1@9_J~SkJq~%)U{K%m~=k zPh>R|>*_39u!~ucM2J3L%s(|(zQ_}B4}fTF{G{|&QcE3av6Y+T*K?A z2oZ2& zDe`WJ0`qZkq#HWKof5X$8X!+es+HC#&EaaOwU%w3R-n)LIzc^!a~YOR+%TvwM<)^z z80XHIHn*!fSqkh{|e^u$0G*artS*!5!RAP&!)SfS1%^{OncVYs780E zbp~XG>Y(}%eg1wwjqrrZnrp3W(7sLK1}Xe2vQ<&ewCYlEn_a8IQBD!2_Y@Bk^o>0! zO;nke7M|57s5PFsP}lQ7J`QeH84iBXzs!zuG_7%O#=eU=SxNF+z=$;H4&(E`iS@I0 z6E)=IMvKy(9zuZ?^BoLC&1O;B@Vq0m))b<{f zEXr^k%@zb-c+-CL+J74?y04xw!(O53jK3A;glqg;V=KwPlDED)c6YOhW)E5m?D+$K zq$MJbl$16IUz#Jc*NW;xohR>BiAu|SdI6lHvGsz(*}6%i$sLd+Q-V+nsMw5aWi>ak zmW>Q)pIkbd2d?5VQY1p3OSJ9?e)eV9KHU*p#3D@NrglP^_1{ zFSgU0%^&*<)dAGP0wx^XF%G`=a!0en^p_rxr(S9rfCt6(kZRVPZ?)cj>?(DO+ur%* z&OoE}hAWG2ovGnvg7j(gQQ)D--bwQGJC9k%u zHYihkNPfgT9^*am1|%5rtkhJ*-1z0Oz7W7W*08K}g=BP^aH^3ENrjvfAZ7MiLDS%EX*E636Pn zDv5M+!}l=Il{xm*~Y1z&BK|cg$@ytMqB<-5v^<+y)^rkOz7?kN|aJr zle_$E{1`K28YTE1izS{0LeErHrB@SYLp~`VAK$F}L~wnl&W8UFiP7%}J%NVvG7|D= zLW9v_NRkqgwFop4lr$K>4Fh|HK>{*Azav=vL{PeUPO!ani_|(2{9^9r zs84@{N$yhUrZDQnsCB)to4k$2pLdbJ=CKU18WicvR}wuZvv=_XJwP9*zks8$7(n#< z4a=ci!8Aj-?{;jo!dftTxQcbNiq5sI;D22w?rK;q@^`0uEt-Z~} zH^d?nMb;(Cc9}+F!+OVky0WGM#mRk?ao*2yiN`slPe#3iO?`*7iEW5$iF$qWt-b5P zd-o$;#VHJM<&nO#-w%zXO*r*(ej2MmcOwa($DObll%3)rCope5;rEmnzkeji(b$Ra z=M8G7j^K}4nKWMvu9Qs?r=PUS``N-7FEfm62-Jl%`myub3MV@d{+e{1xcIS57B={W z5j8cZACP5{ZO6%XtLbU?K7Nz8m16LLi82?r+!uTIwBV7fPr)xtVJz5|D2a1{DMqh? zr@Uc3n&a6Eg&XF4qAnvxGS?@iB7_^RUS3{lkV{MHSIFSO0$SXvqr-6r)on6yixduz z*I(9Sg0~Fsz@Uwj{`l+uwW$0)TL7Uru&xRX+ibcston5@Kr3;r+&gVzRB2)tJ4&#g z+A&;biI$<2b-XWBQj=4SRsfkbXK8tHt$9Mf0g4SSXGRQ9Cqq3sQD@>- z0VV_mE!9#*l_161Y2UZT=j*iok*j2LJpBCUX*8q(E9z91)d4>Ds{52d*S>DU>Z7S~rOHG6n?hc{{MFSOn+Hg+H3)Wo)Z&>_ z4i|G$$!39a6U)%3k6wY|5fhq|27QQYShf@0R1c!k_*^oGR3uGtC5!qd7`4Bn?#Lag zVnaG5i3*bgbX9_K!bt8yQ07m^u9C=l+o)b(2bn*=V-(dt1b4jZclQ#X5nE68k90&L zBUE25CVTq6!JaM#ZJzp%o#!o^6znh8r?a(I*mcLH$kqoJ@Az%ZX%(;Td1*>ZQAf|v zsKr;AXV;P>oXr~TPUw(O%|6ZbQjL@3hxmjf4eAQ!a%trO>jJsNjzoN#+_Ioo4bx;+ z?Y#{}`2}C~Le??{@OS7YzXQIAN6-hW%b80x>*}^O=A}L!b!bS_t?s`Ct+@3Pb4R!H zpfRfvnBpmcqu~4)jt%Ju6O=W|NZ?G=Cpr0r-O*4^Fkley*BCr>xsVrmHebIkv77j5 z@FRWrWuWO^S8naDe6HKwkAs8ghobtg!lzanAE45c<=M2jaNOYmKTUptP-CNASg&N4 zO7ZU{Ym6;5ryV(5qNNThQLmaEIka4)JEOTu+|F?S%_~ux)&)S93ik3cHaGZLR1~{w ztS_&s6I-E`dztcVCRAI2As3@GUev;yiAvYT3QV0{k>vZXj_SPu(wG=nSDT7D`X`yo zJIVvfca5mEDyG99pU#tiRkzT3TO+jEjsE2VJsG2sOEQ8-$t5v8;};j=z|M8{_w$3| zCz;39HVU*)L(^(9o#ndmBi^H>e^PxbKjpi7a!mrYiig~+sQo=JC}7E;QBHl=>YSl*z~Sn9LU7O3hU)TP#{PGDy`jra2l zIo7dW0wvS>t^^TuwSI+V)HW3wSp_Ha#Co1micguCB|9oe{%zteAze~QgSI^ZQh1}~ zna+9bu8T2e6{jQ5C(&U1(1(YQGr{+#y(giB*k$%c*2%_uwQI0{OVKxaisFh7<%>Lx zRuH}|2C;}h&xLV626ZYl+hF-@5J7jNyU{#E%+#04->}o1=INebx#`$mWMV6zxR007 zaBSV=8fqJ-E;mayb5!k9#(I?&q z2VRtphc0ME_*JJQ&;4oT^9*T)!82{elYTAcGiotk!Nt=qsO2I9>Xi{M#UXCW%E6Y= z?hld-vf9G@qH6>NnS5J?EP9zL*&{zX#igLi$wKW&3mngAgL;ERgPOd}9NuKX&GdB~ z@3=UojDQSodZ|Q)6TI3(Gu5IQyMW5k0!fDx)5{x8-bItCnfRlRJG90%z7 zdbIO!<4HB^7g4=vw{IKzu|_RHve2{$c4M`_<9B`-1$BF_(E^fOP}#D$v=mh&k;!KD z`o#JcLA*gM#DOKTBtZ=Z6=M%8q@?$S=GXC{#ILq^vgmSiKUD?t!K;&}fj{GMdd<75 zrcKf!v)mlT`y!m?wAb9-zv`-dn0+2Qm`_bEws5|3*QSYKlqXx=Z<2f1t~5T+@g*O1 znzHThX_JyBy&Wd7x5O|*ri4QS*qofz>cs@J>{LZq=8Ibeg1*HQttx0GhdrUUgLmG_ zX2f^@ydq5vk!r_d@{K3f=dwjtY+N9d9e^)Dxq$3|qryj})9RxQYo+mG+@nx?1#InJ zuzjxY@~?JM(KH0O*HxjMDk!IE_}&)+rD~@fYulG{YD>_?rJPPAQGI%Ri! z2eZ;GF8iAqFj#ZUE%gjdbV>MU5+xgvPJ0m5y3xqj#k$Sw{A!N4p>;yGQ8;M$(3zF@ zitJBrUM;+O6D#d~63WzjcrGB^@XkB-0N20w^TFlumk8G=iFy;2W01`xT-eSoE!3Jt zz3~}6ck^brbbmm8|Da7qDj?2%ATY*`hDwJ%WKn4zG2@C=-Idr)fflIjXf@kezZCvx z3x*DVbt$*!@m^*x8Ai;+BdbG0yS{Sf?Zm>@lr#TKL+E%eL)Uiq4rbn9c@KNt>HFN9 zj=$wP#rJqMiFmv8tT?Qp#`EF5^ifa2B|$H^<0{mok_AFaTXU8=2kHPhzc`jE%PY$3 zCxj0G$hd0Orn7P3+w&fIj+M~vD-Ka6%vpJ|92Ec(T~&f!sjsMXsHR12>mq-*Y)OZ$ zU1jcW9(%8Qb$=iF#S_bWF}sB^P_9;5>=1#F@{2hD5f>p}t;AuRx9q8r8`)QMgq{OGH*EC>M zQX+q5t;)uUwrAbn0P8X%KiZMd70m#m$ubAqT2ont@kQP~++ZS+Cl~GUI`Hb}@W_#HO`HOEOD=Fx`-%-Q1CSeH+DQOF6kmhiWv;<_llU0L_ zF7$bGVD@m23~euH@rgP`68A=d9*`eL`s;Zd!1@uP>piuen0~{p+H`(umt5!QbrfRB z^5tg5wXaTPdf%igzq~86a5qA7(tGZ4!^lFI?8E*+v}&j+)zJo=c-|l~sWaYM4nLg? z*!$gQmk^UkCER|4gok*RK3DU0FYWsm1k%{7@z(4uq%%4O^mZCmmydm;6IB-$HjD4w z2ZqU0rf&p&Dd$3t`MJ^hIj{kf81XR@Ch{doF40L(68Q0xHRj&)O>Fn|W7Pk?uxe zuI38pZV-Q58?_y3MAxRMA$g%C?g*k;;*pw$ z|N5SJF_9GMbAz~Ys|9EB)w9*=USJf3G8 zv&}`@(ns9n&b{A_C5_RT9f6&g9dtzT0zDKgTWZ{`Y73}FS<+Iz(z5R}A!GIQj@`Or z^JJ(QS(#|x=lsD3TPziOx5~Hjl;S}230LrWKp&6A_u16nDa(l(LlE&g;DgPF{l)8T zNSs)B4K-wEkI`Dq(fNA?7)zXMrzq6zS^=D;08iq;0<@rLTB-#= z?HtebEXjImgl&i&0T!v8pJ3K|W_5py=Y6_Mem)6U&aAz`$Eja(SnfNkpx1C?vp@vy z5Tl<9n%fxI7@|F&6^iSGb18-NrBAn(4d4kfdcCaePJ%rYYZ~7-(~Z1uCA?_U2Lp?h zDzuK{ga^cG#@>tczFEk;ievdnEOdf?d4PZ;96gGWmmD$polJahB{lv+O*^AJJ4asI zg<0sc@xuIicYL?GL1$~s+rsI$4E@dq%)&5YJ^2CvClWwrV|O|92bz@IJvTdtwt4JIpbtZX1njp=CEf6 zOtFoYjaSgtPOVHVPgRGUB1z$AuzNTGtjUP`L24wmo@zVg*majv@=7k<6BSC!GY->p zm3@^6T13f9q^jP_GW1|4Jp>#$Rh-QeOTNespV>ODACz!tChCp7umNnz)VoA2vc>*Q zbIKeaa!vTu`s7XXMxyjnh3BRs)*O3sotb?8veHUj!xNc)Rr%665Qs!j`28;y`ZOVH zY_lX&l4F75m$FjYg`kRG^*<-cX;`y&?ZxEjw`I%ySzgT_u)hyOAGBNDt-)V4J1b3* zlXZ1^&*qi!%HrSZPdFJVggm4@lzHGwHgRuOb)N3FBf>R2v7|Uis;x18`lkYG92^!K zF!PPJOrD^S&v9cz+DMY2(FD|_m9kq&1Sq+@VYP$5UOvj)+BX>>p_TRSG@Mj-$D4+^ zkRec9KwnIh$-&r5GcrWK&SBK;dhRdjzFP3R2-n3lU*xpOV-MUj4 zv>Xf_oE8CDIBmjwDd+)wg3H1=KD1xrdK0o2)U@|CkINmbd(D;T8ncL=)!U}!J%3cH z25AgY%>upQY-P8e!AfS}Jz!36xO*(^<59rg2in0Gis0u|OC8X*i7pfpM$(ZjE`l7) zd*3z6UIl$-R=>p@Hg&ExsIjZR(PwVp-qaz_Y#qmJVRS|x_& z6{z?oO8oc+dUewoCOq32go3K zFuPh(B+N7wJpJuQRjb zN^lrGMlC%ZWZWgnDS!93_cPbl9iTr0=4o^yrt)?mY;PpYS<9vs4;`ur{r6eP zz$zMXPMnu=wLB6mX3l@N6pGTK)C0XJ<_j&Y;*VLBm0J;iH z|GAH!JCXw27aT`$%OIxu6D|thdv8i;A}i+T7>U;}S8C!gpZ;o4 zb#*0b=I!y6+_6*jMP$bV)M{3H{+TS{@h5HWM8C;M$`vWhL@l?$&RjxKJWp71B%B&HIc3$N_l z`eE(#Ck!@Ogw)Ta{t&M)Z&l9?>sxL_YYJTuI7jS4!iV%bIdXKwLRr6n?rhf?dzPwZ z(aEz}woV#yCu!hUOt(Qak6mE|-{U`ANdF&& zoo!58RT#(HvJLGfTV}(Sjp+3QY3mr=_j`d#z`+QaK(|h;kd1WhtyG&2m@ipzV~H@tNmz72Z~-$}1`4P#@-m$ZX46FzWHO~0iqE+S-EB?0>6i06|8x4B zm)>u`bUsWU?LKX74SioW+;0pvex(~6h5wPyD*s+YANoi>o{?u_`TLgUhDni zcIdC}S6A+(8{av;`Ae&(OwSY5yVb;$@h7HtO!qhE3UHhnyd*F6sBxS6>|^2mj^+fQ|wKYh2wQ#<@h z^)0(T|7!Xt)wi1l-@HNkN1EEnjGa&4xUB7uWCSX&j#u})9OWw4VN)(~HpTq#TWaeH zYr^=N@uVtEiY8@cN@94GI_)r>``Foy=A`p0zEGuU-dDRFni#>FStPpZm11j z*=Xv_`F+b+&18c9ravMUNS^!0e8H1H>mHvldOQ`)mcEEEl{wSZJaqCG9XGHLzWZp_ zt8Cyq>mrl=`MrOl>XHI7iyigY$y`wvG-I&v9 znSY~XCel2$I%@#F^@mC0p^CP-b0ss^h4}^5Q(M0s`wv$Pc{IqaAt;>TmRvDeU_#XJ ztVeQ5Zoy$(?m`xo+*NF|W2F|%3erzHm(E~2eKt`#fSL2RZv&S{*e^xLAlphFQwWhN z>^Ym{5&Y3^ZmBzpmTWacein%n49p*Rgz82d%1b>}Zbktz7>;-|mJo7VI%T%uLLB(mmC^*4=qX;d&{9r7@ zPz>h878%QDf*&ULVxE5)!BQ;PQs{{?j^|?;^dpH%nPVxizG4~8!agW-98bqGhUSqI zr^rzh4KACK!I2TLZHgShf(aMTke#Q@aXi}c7?#P#F`lO5*2Z(-*D1$BeaO~R%twKS z7h4NOQ%o#_^~UWz91fh0az2J(;^t#{4m?6-4j6I`6}12Z8!?vg;Ks$VxLR1A2c<4H zmkADI9D8tWl4t|tPLzKX7S{m*?jM%1%j=ae@D$~HUF30kF{l*X@uGZiG)*kw1jmuI w+Z;G(d@N;iI!OxWI8I;*j>E|u?f*v>?Zz4jUIy~TXEWjLqfJdMDBZ682Zf@MX8-^I diff --git a/Ref/Top/Main.cpp b/Ref/Top/Main.cpp deleted file mode 100644 index 0458508b67..0000000000 --- a/Ref/Top/Main.cpp +++ /dev/null @@ -1,95 +0,0 @@ -#include -#include -#include - -#include -#include - -void print_usage(const char* app) { - (void) printf("Usage: ./%s [options]\n-p\tport_number\n-a\thostname/IP address\n",app); -} - -#include -#include - -Ref::TopologyState state; -// Enable the console logging provided by Os::Log -Os::Log logger; - -volatile sig_atomic_t terminate = 0; - -static void sighandler(int signum) { - Ref::teardown(state); - terminate = 1; -} - -void run1cycle() { - // call interrupt to emulate a clock - Ref::blockDrv.callIsr(); - Os::Task::delay(1000); //10Hz -} - -void runcycles(NATIVE_INT_TYPE cycles) { - if (cycles == -1) { - while (true) { - run1cycle(); - } - } - - for (NATIVE_INT_TYPE cycle = 0; cycle < cycles; cycle++) { - run1cycle(); - } -} - -int main(int argc, char* argv[]) { - U32 port_number = 0; // Invalid port number forced - I32 option; - char *hostname; - option = 0; - hostname = nullptr; - - while ((option = getopt(argc, argv, "hp:a:")) != -1){ - switch(option) { - case 'h': - print_usage(argv[0]); - return 0; - break; - case 'p': - port_number = static_cast(atoi(optarg)); - break; - case 'a': - hostname = optarg; - break; - case '?': - return 1; - default: - print_usage(argv[0]); - return 1; - } - } - - (void) printf("Hit Ctrl-C to quit\n"); - - state = Ref::TopologyState(hostname, port_number); - Ref::setup(state); - - // register signal handlers to exit program - signal(SIGINT,sighandler); - signal(SIGTERM,sighandler); - - int cycle = 0; - - while (!terminate) { -// (void) printf("Cycle %d\n",cycle); - runcycles(1); - cycle++; - } - - // Give time for threads to exit - (void) printf("Waiting for threads...\n"); - Os::Task::delay(1000); - - (void) printf("Exiting...\n"); - - return 0; -} diff --git a/Ref/Top/RefTopology.cpp b/Ref/Top/RefTopology.cpp new file mode 100644 index 0000000000..22a3a2370c --- /dev/null +++ b/Ref/Top/RefTopology.cpp @@ -0,0 +1,184 @@ +// ====================================================================== +// \title Topology.cpp +// \author mstarch +// \brief cpp file containing the topology instantiation code +// +// \copyright +// Copyright 2009-2022, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// ====================================================================== +// Provides access to autocoded functions +#include + +// Necessary project-specified types +#include +#include +#include + +// Used for 1Hz synthetic cycling +#include + +// Allows easy reference to objects in FPP/autocoder required namespaces +using namespace Ref; + +// Instantiate a system logger that will handle Fw::Logger::logMsg calls +Os::Log logger; + +// The reference topology uses a malloc-based allocator for components that need to allocate memory during the +// initialization phase. +Fw::MallocAllocator mallocator; + +// The reference topology uses the F´ packet protocol when communicating with the ground and therefore uses the F´ +// framing and deframing implementations. +Svc::FprimeFraming framing; +Svc::FprimeDeframing deframing; + +// The reference topology divides the incoming clock signal (1Hz) into sub-signals: 1Hz, 1/2Hz, and 1/4Hz +NATIVE_INT_TYPE rateGroupDivisors[Svc::RateGroupDriver::DIVIDER_SIZE] = {1, 2, 4}; + +// Rate groups may supply a context token to each of the attached children whose purpose is set by the project. The +// reference topology sets each token to zero as these contexts are unused in this project. +NATIVE_INT_TYPE rateGroup1Context[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {}; +NATIVE_INT_TYPE rateGroup2Context[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {}; +NATIVE_INT_TYPE rateGroup3Context[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {}; + +// A number of constants are needed for construction of the topology. These are specified here. +enum TopologyConstants { + CMD_SEQ_BUFFER_SIZE = 5 * 1024, + FILE_DOWNLINK_TIMEOUT = 1000, + FILE_DOWNLINK_COOLDOWN = 1000, + FILE_DOWNLINK_CYCLE_TIME = 1000, + FILE_DOWNLINK_FILE_QUEUE_DEPTH = 10, + HEALTH_WATCHDOG_CODE = 0x123, + COMM_PRIORITY = 100, + UPLINK_BUFFER_MANAGER_STORE_SIZE = 3000, + UPLINK_BUFFER_MANAGER_QUEUE_SIZE = 30, + UPLINK_BUFFER_MANAGER_ID = 200 +}; + +// Ping entries are autocoded, however; this code is not properly exported. Thus, it is copied here. +Svc::Health::PingEntry pingEntries[] = { + {PingEntries::blockDrv::WARN, PingEntries::blockDrv::FATAL, "blockDrv"}, + {PingEntries::chanTlm::WARN, PingEntries::chanTlm::FATAL, "chanTlm"}, + {PingEntries::cmdDisp::WARN, PingEntries::cmdDisp::FATAL, "cmdDisp"}, + {PingEntries::cmdSeq::WARN, PingEntries::cmdSeq::FATAL, "cmdSeq"}, + {PingEntries::eventLogger::WARN, PingEntries::eventLogger::FATAL, "eventLogger"}, + {PingEntries::fileDownlink::WARN, PingEntries::fileDownlink::FATAL, "fileDownlink"}, + {PingEntries::fileManager::WARN, PingEntries::fileManager::FATAL, "fileManager"}, + {PingEntries::fileUplink::WARN, PingEntries::fileUplink::FATAL, "fileUplink"}, + {PingEntries::pingRcvr::WARN, PingEntries::pingRcvr::FATAL, "pingRcvr"}, + {PingEntries::prmDb::WARN, PingEntries::prmDb::FATAL, "prmDb"}, + {PingEntries::rateGroup1Comp::WARN, PingEntries::rateGroup1Comp::FATAL, "rateGroup1Comp"}, + {PingEntries::rateGroup2Comp::WARN, PingEntries::rateGroup2Comp::FATAL, "rateGroup2Comp"}, + {PingEntries::rateGroup3Comp::WARN, PingEntries::rateGroup3Comp::FATAL, "rateGroup3Comp"}, +}; + +/** + * \brief configure/setup components in project-specific way + * + * This is a *helper* function which configures/sets up each component requiring project specific input. This includes + * allocating resources, passing-in arguments, etc. This function may be inlined into the topology setup function if + * desired, but is extracted here for clarity. + */ +void configureTopology() { + // Command sequencer needs to allocate memory to hold contents of command sequences + cmdSeq.allocateBuffer(0, mallocator, CMD_SEQ_BUFFER_SIZE); + + // Rate group driver needs a divisor list + rateGroupDriverComp.configure(rateGroupDivisors, FW_NUM_ARRAY_ELEMENTS(rateGroupDivisors)); + + // Rate groups require context arrays. Empty for Reference example. + rateGroup1Comp.configure(rateGroup1Context, FW_NUM_ARRAY_ELEMENTS(rateGroup1Context)); + rateGroup2Comp.configure(rateGroup2Context, FW_NUM_ARRAY_ELEMENTS(rateGroup2Context)); + rateGroup3Comp.configure(rateGroup3Context, FW_NUM_ARRAY_ELEMENTS(rateGroup3Context)); + + // File downlink requires some project-derived properties. + fileDownlink.configure(FILE_DOWNLINK_TIMEOUT, FILE_DOWNLINK_COOLDOWN, FILE_DOWNLINK_CYCLE_TIME, + FILE_DOWNLINK_FILE_QUEUE_DEPTH); + + // Parameter database is configured with a database file name, and that file must be initially read. + prmDb.configure("PrmDb.dat"); + prmDb.readParamFile(); + + // Health is supplied a set of ping entires. + health.setPingEntries(pingEntries, FW_NUM_ARRAY_ELEMENTS(pingEntries), HEALTH_WATCHDOG_CODE); + + // Buffer managers need a configured set of buckets and an allocator used to allocate memory for those buckets. + Svc::BufferManager::BufferBins upBuffMgrBins; + memset(&upBuffMgrBins, 0, sizeof(upBuffMgrBins)); + upBuffMgrBins.bins[0].bufferSize = UPLINK_BUFFER_MANAGER_STORE_SIZE; + upBuffMgrBins.bins[0].numBuffers = UPLINK_BUFFER_MANAGER_QUEUE_SIZE; + fileUplinkBufferManager.setup(UPLINK_BUFFER_MANAGER_ID, 0, mallocator, upBuffMgrBins); + + // Framer and Deframer components need to be passed a protocol handler + downlink.setup(framing); + uplink.setup(deframing); +} + +// Public functions for use in main program are namespaced with deployment name Ref +namespace Ref { +void setupTopology(const TopologyState& state) { + // Autocoded initialization. Function provided by autocoder. + initComponents(state); + // Autocoded id setup. Function provided by autocoder. + setBaseIds(); + // Autocoded connection wiring. Function provided by autocoder. + connectComponents(); + // Autocoded command registration. Function provided by autocoder. + regCommands(); + // Project-specific component configuration. Function provided above. May be inlined, if desired. + configureTopology(); + // Autocoded parameter loading. Function provided by autocoder. + loadParameters(); + // Autocoded task kick-off (active components). Function provided by autocoder. + startTasks(state); + // Initialize socket client communication if and only if there is a valid specification + if (state.hostname != nullptr && state.port != 0) { + Os::TaskString name("ReceiveTask"); + // Uplink is configured for receive so a socket task is started + comm.configure(state.hostname, state.port); + comm.startSocketTask(name, true, COMM_PRIORITY, Default::STACK_SIZE); + } +} + +// Variables used for cycle simulation +Os::Mutex cycleLock; +volatile bool cycleFlag = true; + +void startSimulatedCycle(U32 milliseconds) { + cycleLock.lock(); + bool cycling = cycleFlag; + cycleLock.unLock(); + + // Main loop + while (cycling) { + Ref::blockDrv.callIsr(); + Os::Task::delay(milliseconds); + + cycleLock.lock(); + cycling = cycleFlag; + cycleLock.unLock(); + } +} + +void stopSimulatedCycle() { + cycleLock.lock(); + cycleFlag = false; + cycleLock.unLock(); +} + +void teardownTopology(const TopologyState& state) { + // Autocoded (active component) task clean-up. Functions provided by topology autocoder. + stopTasks(state); + freeThreads(state); + + // Other task clean-up. + comm.stopSocketTask(); + (void)comm.joinSocketTask(nullptr); + + // Resource deallocation + cmdSeq.deallocateBuffer(mallocator); + fileUplinkBufferManager.cleanup(); +} +}; // namespace Ref diff --git a/Ref/Top/RefTopology.hpp b/Ref/Top/RefTopology.hpp new file mode 100644 index 0000000000..b91e477f5f --- /dev/null +++ b/Ref/Top/RefTopology.hpp @@ -0,0 +1,91 @@ +// ====================================================================== +// \title Topology.hpp +// \author mstarch +// \brief header file containing the topology instantiation definitions +// +// \copyright +// Copyright 2009-2022, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// ====================================================================== +#ifndef REF_REFTOPOLOGY_HPP +#define REF_REFTOPOLOGY_HPP +// Included for access to Ref::TopologyState and Ref::ConfigObjects::pingEntries. These definitions are required by the +// autocoder, but are also used in this hand-coded topology. +#include + +// Remove unnecessary Ref:: qualifications +using namespace Ref; +namespace Ref { +/** + * \brief initialize and run the F´ topology + * + * Initializes, configures, and runs the F´ topology. This is performed through a series of steps, some provided via + * autocoded functions, and others provided via the functions implementation. These steps are: + * + * 1. Call the autocoded `initComponents()` function initializing each component via the `component.init` method + * 2. Call the autocoded `setBaseIds()` function to set the base IDs (offset) for each component instance + * 3. Call the autocoded `connectComponents()` function to wire-together the topology of components + * 4. Configure components requiring custom configuration + * 5. Call the autocoded `loadParameters()` function to cause each component to load initial parameter values + * 6. Call the autocoded `startTasks()` function to start the active component tasks + * 7. Start tasks not owned by active components + * + * Step 4 and step 7 are custom and supplied by the project. The ordering of steps 1, 2, 3, 5, and 6 are critical for + * F´ topologies to function. Configuration (step 4) typically assumes a connect but not started topology and is thus + * inserted between step 3 and 5. Step 7 may come before or after the active component initializations. Since these + * custom tasks often start radio communication it is convenient to start them last. + * + * The state argument carries command line inputs used to setup the topology. For an explanation of the required type + * Ref::TopologyState see: RefTopologyDefs.hpp. + * + * \param state: object shuttling CLI arguments (hostname, port) needed to construct the topology + */ +void setupTopology(const TopologyState& state); + +/** + * \brief teardown the F´ topology + * + * Tears down the F´ topology in preparation for shutdown. This is done via a series of steps, some provided by + * autocoded functions, and others provided via the function implementation. These steps are: + * + * 1. Call the autocoded `stopTasks()` function to stop the tasks started by `startTasks()` (active components) + * 2. Call the autocoded `freeThreads()` function to join to the tasks started by `startTasks()` + * 3. Stop the tasks not owned by active components + * 4. Join to the tasks not owned by active components + * 5. Deallocate other resources + * + * Step 1, 2, 3, and 4 must occur in-order as the tasks must be stopped before being joined. These tasks must be stopped + * and joined before any active resources may be deallocated. + * + * For an explanation of the required type Ref::TopologyState see: RefTopologyDefs.hpp. + * + * \param state: state object provided to setupTopology + */ +void teardownTopology(const TopologyState& state); + +/** + * \brief cycle the rate group driver at a crude rate + * + * The reference topology does not have a true 1Hz input clock for the rate group driver because it is designed to + * operate across various computing endpoints (e.g. laptops) where a clear 1Hz source may not be easily and generically + * achieved. This function mimics the cycling via a Task::delay(milliseconds) loop that manually invokes the ISR call + * to the example block driver. + * + * This loop is stopped via a startSimulatedCycle call. + * + * Note: projects should replace this with a component that produces an output port call at the appropriate frequency. + * + * \param milliseconds: milliseconds to delay for each cycle. Default: 1000 or 1Hz. + */ +void startSimulatedCycle(U32 milliseconds = 1000); + +/** + * \brief stop the simulated cycle started by startSimulatedCycle + * + * This stops the cycle started by startSimulatedCycle. + */ +void stopSimulatedCycle(); + +} // namespace Ref +#endif diff --git a/Ref/Top/RefTopologyAc.cpp b/Ref/Top/RefTopologyAc.cpp deleted file mode 100644 index b8455c2146..0000000000 --- a/Ref/Top/RefTopologyAc.cpp +++ /dev/null @@ -1,1349 +0,0 @@ -// ====================================================================== -// \title RefTopologyAc.cpp -// \author Generated by fpp-to-cpp -// \brief cpp file for Ref topology -// -// \copyright -// Copyright (c) 2021 California Institute of Technology. -// U.S. Government sponsorship acknowledged. -// All rights reserved. -// ====================================================================== - -#include "Ref/Top/RefTopologyAc.hpp" - -namespace Ref { - - namespace { - - // ---------------------------------------------------------------------- - // Component configuration objects - // ---------------------------------------------------------------------- - - namespace ConfigObjects { - - namespace downlink { - Svc::FprimeFraming framing; - } - - namespace health { - Svc::HealthImpl::PingEntry pingEntries[] = { - { - PingEntries::blockDrv::WARN, - PingEntries::blockDrv::FATAL, - "blockDrv" - }, - { - PingEntries::chanTlm::WARN, - PingEntries::chanTlm::FATAL, - "chanTlm" - }, - { - PingEntries::cmdDisp::WARN, - PingEntries::cmdDisp::FATAL, - "cmdDisp" - }, - { - PingEntries::cmdSeq::WARN, - PingEntries::cmdSeq::FATAL, - "cmdSeq" - }, - { - PingEntries::eventLogger::WARN, - PingEntries::eventLogger::FATAL, - "eventLogger" - }, - { - PingEntries::fileDownlink::WARN, - PingEntries::fileDownlink::FATAL, - "fileDownlink" - }, - { - PingEntries::fileManager::WARN, - PingEntries::fileManager::FATAL, - "fileManager" - }, - { - PingEntries::fileUplink::WARN, - PingEntries::fileUplink::FATAL, - "fileUplink" - }, - { - PingEntries::pingRcvr::WARN, - PingEntries::pingRcvr::FATAL, - "pingRcvr" - }, - { - PingEntries::prmDb::WARN, - PingEntries::prmDb::FATAL, - "prmDb" - }, - { - PingEntries::rateGroup1Comp::WARN, - PingEntries::rateGroup1Comp::FATAL, - "rateGroup1Comp" - }, - { - PingEntries::rateGroup2Comp::WARN, - PingEntries::rateGroup2Comp::FATAL, - "rateGroup2Comp" - }, - { - PingEntries::rateGroup3Comp::WARN, - PingEntries::rateGroup3Comp::FATAL, - "rateGroup3Comp" - }, - }; - } - - namespace rateGroup1Comp { - NATIVE_UINT_TYPE context[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - } - - namespace rateGroup2Comp { - NATIVE_UINT_TYPE context[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - } - - namespace rateGroup3Comp { - NATIVE_UINT_TYPE context[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - } - - namespace rateGroupDriverComp { - NATIVE_INT_TYPE rgDivs[Svc::RateGroupDriver::DIVIDER_SIZE] = { 1, 2, 4 }; - } - - namespace uplink { - Svc::FprimeDeframing deframing; - } - - } - - // ---------------------------------------------------------------------- - // Component instances - // ---------------------------------------------------------------------- - - // SG1 - SignalGen SG1(FW_OPTIONAL_NAME("SG1")); - - // SG2 - SignalGen SG2(FW_OPTIONAL_NAME("SG2")); - - // SG3 - SignalGen SG3(FW_OPTIONAL_NAME("SG3")); - - // SG4 - SignalGen SG4(FW_OPTIONAL_NAME("SG4")); - - // SG5 - SignalGen SG5(FW_OPTIONAL_NAME("SG5")); - - // blockDrv - // Declared in RefTopologyDefs.cpp - - // chanTlm - Svc::TlmChan chanTlm(FW_OPTIONAL_NAME("chanTlm")); - - // cmdDisp - Svc::CommandDispatcher cmdDisp(FW_OPTIONAL_NAME("cmdDisp")); - - // cmdSeq - Svc::CmdSequencer cmdSeq(FW_OPTIONAL_NAME("cmdSeq")); - - // comm - Drv::TcpClient comm(FW_OPTIONAL_NAME("comm")); - - // downlink - Svc::Framer downlink(FW_OPTIONAL_NAME("downlink")); - - // eventLogger - Svc::ActiveLogger eventLogger(FW_OPTIONAL_NAME("eventLogger")); - - // fatalAdapter - Svc::AssertFatalAdapter fatalAdapter(FW_OPTIONAL_NAME("fatalAdapter")); - - // fatalHandler - Svc::FatalHandler fatalHandler(FW_OPTIONAL_NAME("fatalHandler")); - - // fileDownlink - Svc::FileDownlink fileDownlink(FW_OPTIONAL_NAME("fileDownlink")); - - // fileManager - Svc::FileManager fileManager(FW_OPTIONAL_NAME("fileManager")); - - // fileUplink - Svc::FileUplink fileUplink(FW_OPTIONAL_NAME("fileUplink")); - - // fileUplinkBufferManager - Svc::BufferManager fileUplinkBufferManager(FW_OPTIONAL_NAME("fileUplinkBufferManager")); - - // health - Svc::Health health(FW_OPTIONAL_NAME("health")); - - // linuxTime - Svc::LinuxTime linuxTime(FW_OPTIONAL_NAME("linuxTime")); - - // pingRcvr - PingReceiver pingRcvr(FW_OPTIONAL_NAME("pingRcvr")); - - // prmDb - Svc::PrmDb prmDb(FW_OPTIONAL_NAME("prmDb"), "PrmDb.dat"); - - // rateGroup1Comp - Svc::ActiveRateGroup rateGroup1Comp( - FW_OPTIONAL_NAME("rateGroup1Comp"), - ConfigObjects::rateGroup1Comp::context, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroup1Comp::context) - ); - - // rateGroup2Comp - Svc::ActiveRateGroup rateGroup2Comp( - FW_OPTIONAL_NAME("rateGroup2Comp"), - ConfigObjects::rateGroup2Comp::context, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroup2Comp::context) - ); - - // rateGroup3Comp - Svc::ActiveRateGroup rateGroup3Comp( - FW_OPTIONAL_NAME("rateGroup3Comp"), - ConfigObjects::rateGroup3Comp::context, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroup3Comp::context) - ); - - // rateGroupDriverComp - Svc::RateGroupDriver rateGroupDriverComp( - FW_OPTIONAL_NAME("rateGroupDriverComp"), - ConfigObjects::rateGroupDriverComp::rgDivs, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroupDriverComp::rgDivs) - ); - - // recvBuffComp - RecvBuff recvBuffComp(FW_OPTIONAL_NAME("recvBuffComp")); - - // sendBuffComp - SendBuff sendBuffComp(FW_OPTIONAL_NAME("sendBuffComp")); - - // staticMemory - Svc::StaticMemory staticMemory(FW_OPTIONAL_NAME("staticMemory")); - - // textLogger - Svc::PassiveTextLogger textLogger(FW_OPTIONAL_NAME("textLogger")); - - // uplink - Svc::Deframer uplink(FW_OPTIONAL_NAME("uplink")); - - // ---------------------------------------------------------------------- - // Private functions - // ---------------------------------------------------------------------- - - // Initialize components - void initComponents(const TopologyState& state) { - SG1.init(QueueSizes::SG1, InstanceIds::SG1); - SG2.init(QueueSizes::SG2, InstanceIds::SG2); - SG3.init(QueueSizes::SG3, InstanceIds::SG3); - SG4.init(QueueSizes::SG4, InstanceIds::SG4); - SG5.init(QueueSizes::SG5, InstanceIds::SG5); - blockDrv.init(QueueSizes::blockDrv, InstanceIds::blockDrv); - chanTlm.init(QueueSizes::chanTlm, InstanceIds::chanTlm); - cmdDisp.init(QueueSizes::cmdDisp, InstanceIds::cmdDisp); - cmdSeq.init(QueueSizes::cmdSeq, InstanceIds::cmdSeq); - comm.init(InstanceIds::comm); - downlink.init(InstanceIds::downlink); - eventLogger.init(QueueSizes::eventLogger, InstanceIds::eventLogger); - fatalAdapter.init(InstanceIds::fatalAdapter); - fatalHandler.init(InstanceIds::fatalHandler); - fileDownlink.init(QueueSizes::fileDownlink, InstanceIds::fileDownlink); - fileManager.init(QueueSizes::fileManager, InstanceIds::fileManager); - fileUplink.init(QueueSizes::fileUplink, InstanceIds::fileUplink); - fileUplinkBufferManager.init(InstanceIds::fileUplinkBufferManager); - health.init(QueueSizes::health, InstanceIds::health); - linuxTime.init(InstanceIds::linuxTime); - pingRcvr.init(QueueSizes::pingRcvr, InstanceIds::pingRcvr); - prmDb.init(QueueSizes::prmDb, InstanceIds::prmDb); - rateGroup1Comp.init(QueueSizes::rateGroup1Comp, InstanceIds::rateGroup1Comp); - rateGroup2Comp.init(QueueSizes::rateGroup2Comp, InstanceIds::rateGroup2Comp); - rateGroup3Comp.init(QueueSizes::rateGroup3Comp, InstanceIds::rateGroup3Comp); - rateGroupDriverComp.init(InstanceIds::rateGroupDriverComp); - recvBuffComp.init(InstanceIds::recvBuffComp); - sendBuffComp.init(QueueSizes::sendBuffComp, InstanceIds::sendBuffComp); - staticMemory.init(InstanceIds::staticMemory); - textLogger.init(InstanceIds::textLogger); - uplink.init(InstanceIds::uplink); - } - - // Configure components - void configComponents(const TopologyState& state) { - cmdSeq.allocateBuffer( - 0, - Allocation::mallocator, - ConfigConstants::cmdSeq::BUFFER_SIZE - ); - downlink.setup(ConfigObjects::downlink::framing); - fileDownlink.configure( - ConfigConstants::fileDownlink::TIMEOUT, - ConfigConstants::fileDownlink::COOLDOWN, - ConfigConstants::fileDownlink::CYCLE_TIME, - ConfigConstants::fileDownlink::FILE_QUEUE_DEPTH - ); - Svc::BufferManager::BufferBins upBuffMgrBins; - memset(&upBuffMgrBins, 0, sizeof(upBuffMgrBins)); - { - using namespace ConfigConstants::fileUplinkBufferManager; - upBuffMgrBins.bins[0].bufferSize = STORE_SIZE; - upBuffMgrBins.bins[0].numBuffers = QUEUE_SIZE; - fileUplinkBufferManager.setup( - MGR_ID, - 0, - Allocation::mallocator, - upBuffMgrBins - ); - } - health.setPingEntries( - ConfigObjects::health::pingEntries, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::health::pingEntries), - ConfigConstants::health::WATCHDOG_CODE - ); - uplink.setup(ConfigObjects::uplink::deframing); - } - - // Set component base Ids - void setBaseIds() { - blockDrv.setIdBase(BaseIds::blockDrv); - rateGroup1Comp.setIdBase(BaseIds::rateGroup1Comp); - rateGroup2Comp.setIdBase(BaseIds::rateGroup2Comp); - rateGroup3Comp.setIdBase(BaseIds::rateGroup3Comp); - cmdDisp.setIdBase(BaseIds::cmdDisp); - cmdSeq.setIdBase(BaseIds::cmdSeq); - fileDownlink.setIdBase(BaseIds::fileDownlink); - fileManager.setIdBase(BaseIds::fileManager); - fileUplink.setIdBase(BaseIds::fileUplink); - pingRcvr.setIdBase(BaseIds::pingRcvr); - eventLogger.setIdBase(BaseIds::eventLogger); - chanTlm.setIdBase(BaseIds::chanTlm); - prmDb.setIdBase(BaseIds::prmDb); - health.setIdBase(BaseIds::health); - SG1.setIdBase(BaseIds::SG1); - SG2.setIdBase(BaseIds::SG2); - SG3.setIdBase(BaseIds::SG3); - SG4.setIdBase(BaseIds::SG4); - SG5.setIdBase(BaseIds::SG5); - sendBuffComp.setIdBase(BaseIds::sendBuffComp); - comm.setIdBase(BaseIds::comm); - downlink.setIdBase(BaseIds::downlink); - fatalAdapter.setIdBase(BaseIds::fatalAdapter); - fatalHandler.setIdBase(BaseIds::fatalHandler); - fileUplinkBufferManager.setIdBase(BaseIds::fileUplinkBufferManager); - linuxTime.setIdBase(BaseIds::linuxTime); - rateGroupDriverComp.setIdBase(BaseIds::rateGroupDriverComp); - recvBuffComp.setIdBase(BaseIds::recvBuffComp); - staticMemory.setIdBase(BaseIds::staticMemory); - textLogger.setIdBase(BaseIds::textLogger); - uplink.setIdBase(BaseIds::uplink); - } - - // Connect components - void connectComponents() { - - // Command - cmdDisp.set_compCmdSend_OutputPort( - 0, - SG1.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 1, - SG2.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 2, - SG3.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 3, - SG4.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 4, - SG5.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 5, - cmdDisp.get_CmdDisp_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 6, - cmdSeq.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 7, - eventLogger.get_CmdDisp_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 8, - fileDownlink.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 9, - fileManager.get_cmdIn_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 10, - health.get_CmdDisp_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 11, - pingRcvr.get_CmdDisp_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 12, - prmDb.get_CmdDisp_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 13, - recvBuffComp.get_CmdDisp_InputPort(0) - ); - cmdDisp.set_compCmdSend_OutputPort( - 14, - sendBuffComp.get_CmdDisp_InputPort(0) - ); - - // CommandRegistration - SG1.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(0) - ); - SG2.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(1) - ); - SG3.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(2) - ); - SG4.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(3) - ); - SG5.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(4) - ); - cmdDisp.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(5) - ); - cmdSeq.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(6) - ); - eventLogger.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(7) - ); - fileDownlink.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(8) - ); - fileManager.set_cmdRegOut_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(9) - ); - health.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(10) - ); - pingRcvr.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(11) - ); - prmDb.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(12) - ); - recvBuffComp.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(13) - ); - sendBuffComp.set_CmdReg_OutputPort( - 0, - cmdDisp.get_compCmdReg_InputPort(14) - ); - - // CommandResponse - SG1.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - SG2.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - SG3.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - SG4.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - SG5.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - cmdDisp.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - cmdSeq.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - eventLogger.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - fileDownlink.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - fileManager.set_cmdResponseOut_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - health.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - pingRcvr.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - prmDb.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - recvBuffComp.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - sendBuffComp.set_CmdStatus_OutputPort( - 0, - cmdDisp.get_compCmdStat_InputPort(0) - ); - - // Downlink - chanTlm.set_PktSend_OutputPort( - 0, - downlink.get_comIn_InputPort(0) - ); - comm.set_deallocate_OutputPort( - 0, - staticMemory.get_bufferDeallocate_InputPort(0) - ); - downlink.set_bufferDeallocate_OutputPort( - 0, - fileDownlink.get_bufferReturn_InputPort(0) - ); - downlink.set_framedAllocate_OutputPort( - 0, - staticMemory.get_bufferAllocate_InputPort(0) - ); - downlink.set_framedOut_OutputPort( - 0, - comm.get_send_InputPort(0) - ); - eventLogger.set_PktSend_OutputPort( - 0, - downlink.get_comIn_InputPort(0) - ); - fileDownlink.set_bufferSendOut_OutputPort( - 0, - downlink.get_bufferIn_InputPort(0) - ); - - // Events - SG1.set_logOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - SG2.set_logOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - SG3.set_logOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - SG4.set_logOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - SG5.set_logOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - cmdDisp.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - cmdSeq.set_logOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - eventLogger.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - fatalAdapter.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - fileDownlink.set_eventOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - fileManager.set_eventOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - fileUplink.set_eventOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - fileUplinkBufferManager.set_eventOut_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - health.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - pingRcvr.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - prmDb.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - rateGroup1Comp.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - rateGroup2Comp.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - rateGroup3Comp.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - recvBuffComp.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - sendBuffComp.set_Log_OutputPort( - 0, - eventLogger.get_LogRecv_InputPort(0) - ); - - // FaultProtection - eventLogger.set_FatalAnnounce_OutputPort( - 0, - fatalHandler.get_FatalReceive_InputPort(0) - ); - - // Health - blockDrv.set_PingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(0) - ); - chanTlm.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(1) - ); - cmdDisp.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(2) - ); - cmdSeq.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(3) - ); - eventLogger.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(4) - ); - fileDownlink.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(5) - ); - fileManager.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(6) - ); - fileUplink.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(7) - ); - health.set_PingSend_OutputPort( - 0, - blockDrv.get_PingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 1, - chanTlm.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 2, - cmdDisp.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 3, - cmdSeq.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 4, - eventLogger.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 5, - fileDownlink.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 6, - fileManager.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 7, - fileUplink.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 8, - pingRcvr.get_PingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 9, - prmDb.get_pingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 10, - rateGroup1Comp.get_PingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 11, - rateGroup2Comp.get_PingIn_InputPort(0) - ); - health.set_PingSend_OutputPort( - 12, - rateGroup3Comp.get_PingIn_InputPort(0) - ); - pingRcvr.set_PingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(8) - ); - prmDb.set_pingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(9) - ); - rateGroup1Comp.set_PingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(10) - ); - rateGroup2Comp.set_PingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(11) - ); - rateGroup3Comp.set_PingOut_OutputPort( - 0, - health.get_PingReturn_InputPort(12) - ); - - // Parameters - recvBuffComp.set_ParamGet_OutputPort( - 0, - prmDb.get_getPrm_InputPort(0) - ); - recvBuffComp.set_ParamSet_OutputPort( - 0, - prmDb.get_setPrm_InputPort(0) - ); - sendBuffComp.set_ParamGet_OutputPort( - 0, - prmDb.get_getPrm_InputPort(0) - ); - sendBuffComp.set_ParamSet_OutputPort( - 0, - prmDb.get_setPrm_InputPort(0) - ); - - // RateGroups - blockDrv.set_CycleOut_OutputPort( - 0, - rateGroupDriverComp.get_CycleIn_InputPort(0) - ); - rateGroup1Comp.set_RateGroupMemberOut_OutputPort( - 0, - SG1.get_schedIn_InputPort(0) - ); - rateGroup1Comp.set_RateGroupMemberOut_OutputPort( - 1, - SG2.get_schedIn_InputPort(0) - ); - rateGroup1Comp.set_RateGroupMemberOut_OutputPort( - 2, - chanTlm.get_Run_InputPort(0) - ); - rateGroup1Comp.set_RateGroupMemberOut_OutputPort( - 3, - fileDownlink.get_Run_InputPort(0) - ); - rateGroup2Comp.set_RateGroupMemberOut_OutputPort( - 0, - cmdSeq.get_schedIn_InputPort(0) - ); - rateGroup2Comp.set_RateGroupMemberOut_OutputPort( - 1, - sendBuffComp.get_SchedIn_InputPort(0) - ); - rateGroup2Comp.set_RateGroupMemberOut_OutputPort( - 2, - SG3.get_schedIn_InputPort(0) - ); - rateGroup2Comp.set_RateGroupMemberOut_OutputPort( - 3, - SG4.get_schedIn_InputPort(0) - ); - rateGroup3Comp.set_RateGroupMemberOut_OutputPort( - 0, - health.get_Run_InputPort(0) - ); - rateGroup3Comp.set_RateGroupMemberOut_OutputPort( - 1, - SG5.get_schedIn_InputPort(0) - ); - rateGroup3Comp.set_RateGroupMemberOut_OutputPort( - 2, - blockDrv.get_Sched_InputPort(0) - ); - rateGroup3Comp.set_RateGroupMemberOut_OutputPort( - 3, - fileUplinkBufferManager.get_schedIn_InputPort(0) - ); - rateGroupDriverComp.set_CycleOut_OutputPort( - 0, - rateGroup1Comp.get_CycleIn_InputPort(0) - ); - rateGroupDriverComp.set_CycleOut_OutputPort( - 1, - rateGroup2Comp.get_CycleIn_InputPort(0) - ); - rateGroupDriverComp.set_CycleOut_OutputPort( - 2, - rateGroup3Comp.get_CycleIn_InputPort(0) - ); - - // Ref - blockDrv.set_BufferOut_OutputPort( - 0, - recvBuffComp.get_Data_InputPort(0) - ); - sendBuffComp.set_Data_OutputPort( - 0, - blockDrv.get_BufferIn_InputPort(0) - ); - - // Sequencer - cmdDisp.set_seqCmdStatus_OutputPort( - 0, - cmdSeq.get_cmdResponseIn_InputPort(0) - ); - cmdSeq.set_comCmdOut_OutputPort( - 0, - cmdDisp.get_seqCmdBuff_InputPort(0) - ); - - // Telemetry - SG1.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - SG2.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - SG3.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - SG4.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - SG5.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - blockDrv.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - cmdDisp.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - cmdSeq.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - fileDownlink.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - fileManager.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - fileUplink.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - fileUplinkBufferManager.set_tlmOut_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - health.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - pingRcvr.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - rateGroup1Comp.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - rateGroup2Comp.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - rateGroup3Comp.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - recvBuffComp.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - sendBuffComp.set_Tlm_OutputPort( - 0, - chanTlm.get_TlmRecv_InputPort(0) - ); - - // TextEvents - SG1.set_logTextOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - SG2.set_logTextOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - SG3.set_logTextOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - SG4.set_logTextOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - SG5.set_logTextOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - cmdDisp.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - cmdSeq.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - eventLogger.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - fatalAdapter.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - fileDownlink.set_textEventOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - fileManager.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - fileUplink.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - fileUplinkBufferManager.set_textEventOut_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - health.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - pingRcvr.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - prmDb.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - rateGroup1Comp.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - rateGroup2Comp.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - rateGroup3Comp.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - recvBuffComp.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - sendBuffComp.set_LogText_OutputPort( - 0, - textLogger.get_TextLogger_InputPort(0) - ); - - // Time - SG1.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - SG2.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - SG3.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - SG4.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - SG5.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - blockDrv.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - cmdDisp.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - cmdSeq.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - downlink.set_timeGet_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - eventLogger.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - fatalAdapter.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - fileDownlink.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - fileManager.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - fileUplink.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - fileUplinkBufferManager.set_timeCaller_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - health.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - pingRcvr.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - prmDb.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - rateGroup1Comp.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - rateGroup2Comp.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - rateGroup3Comp.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - recvBuffComp.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - sendBuffComp.set_Time_OutputPort( - 0, - linuxTime.get_timeGetPort_InputPort(0) - ); - - // Uplink - cmdDisp.set_seqCmdStatus_OutputPort( - 1, - uplink.get_cmdResponseIn_InputPort(0) - ); - comm.set_allocate_OutputPort( - 0, - staticMemory.get_bufferAllocate_InputPort(1) - ); - comm.set_recv_OutputPort( - 0, - uplink.get_framedIn_InputPort(0) - ); - fileUplink.set_bufferSendOut_OutputPort( - 0, - fileUplinkBufferManager.get_bufferSendIn_InputPort(0) - ); - uplink.set_bufferAllocate_OutputPort( - 0, - fileUplinkBufferManager.get_bufferGetCallee_InputPort(0) - ); - uplink.set_bufferDeallocate_OutputPort( - 0, - fileUplinkBufferManager.get_bufferSendIn_InputPort(0) - ); - uplink.set_bufferOut_OutputPort( - 0, - fileUplink.get_bufferSendIn_InputPort(0) - ); - uplink.set_comOut_OutputPort( - 0, - cmdDisp.get_seqCmdBuff_InputPort(1) - ); - uplink.set_framedDeallocate_OutputPort( - 0, - staticMemory.get_bufferDeallocate_InputPort(1) - ); - - } - - // Register commands - void regCommands() { - SG1.regCommands(); - SG2.regCommands(); - SG3.regCommands(); - SG4.regCommands(); - SG5.regCommands(); - cmdDisp.regCommands(); - cmdSeq.regCommands(); - eventLogger.regCommands(); - fileDownlink.regCommands(); - fileManager.regCommands(); - health.regCommands(); - pingRcvr.regCommands(); - prmDb.regCommands(); - recvBuffComp.regCommands(); - sendBuffComp.regCommands(); - } - - // Read parameters - void readParameters() { - prmDb.readParamFile(); - } - - // Load parameters - void loadParameters() { - recvBuffComp.loadParameters(); - sendBuffComp.loadParameters(); - } - - // Start tasks - void startTasks(const TopologyState& state) { - blockDrv.start( - static_cast(Priorities::blockDrv), - static_cast(StackSizes::blockDrv), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::blockDrv) - ); - chanTlm.start( - static_cast(Priorities::chanTlm), - static_cast(StackSizes::chanTlm), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::chanTlm) - ); - cmdDisp.start( - static_cast(Priorities::cmdDisp), - static_cast(StackSizes::cmdDisp), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::cmdDisp) - ); - cmdSeq.start( - static_cast(Priorities::cmdSeq), - static_cast(StackSizes::cmdSeq), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::cmdSeq) - ); - // Initialize socket server if and only if there is a valid specification - if (state.hostName != nullptr && state.portNumber != 0) { - Os::TaskString name("ReceiveTask"); - // Uplink is configured for receive so a socket task is started - comm.configure(state.hostName, state.portNumber); - comm.startSocketTask( - name, - ConfigConstants::comm::PRIORITY, - ConfigConstants::comm::STACK_SIZE - ); - } - eventLogger.start( - static_cast(Priorities::eventLogger), - static_cast(StackSizes::eventLogger), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::eventLogger) - ); - fileDownlink.start( - static_cast(Priorities::fileDownlink), - static_cast(StackSizes::fileDownlink), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::fileDownlink) - ); - fileManager.start( - static_cast(Priorities::fileManager), - static_cast(StackSizes::fileManager), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::fileManager) - ); - fileUplink.start( - static_cast(Priorities::fileUplink), - static_cast(StackSizes::fileUplink), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::fileUplink) - ); - pingRcvr.start( - static_cast(Priorities::pingRcvr), - static_cast(StackSizes::pingRcvr), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::pingRcvr) - ); - prmDb.start( - static_cast(Priorities::prmDb), - static_cast(StackSizes::prmDb), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::prmDb) - ); - rateGroup1Comp.start( - static_cast(Priorities::rateGroup1Comp), - static_cast(StackSizes::rateGroup1Comp), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::rateGroup1Comp) - ); - rateGroup2Comp.start( - static_cast(Priorities::rateGroup2Comp), - static_cast(StackSizes::rateGroup2Comp), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::rateGroup2Comp) - ); - rateGroup3Comp.start( - static_cast(Priorities::rateGroup3Comp), - static_cast(StackSizes::rateGroup3Comp), - Os::Task::TASK_DEFAULT, // Default CPU - static_cast(TaskIds::rateGroup3Comp) - ); - } - - // Stop tasks - void stopTasks(const TopologyState& state) { - blockDrv.exit(); - chanTlm.exit(); - cmdDisp.exit(); - cmdSeq.exit(); - eventLogger.exit(); - fileDownlink.exit(); - fileManager.exit(); - fileUplink.exit(); - pingRcvr.exit(); - prmDb.exit(); - rateGroup1Comp.exit(); - rateGroup2Comp.exit(); - rateGroup3Comp.exit(); - } - - // Free threads - void freeThreads(const TopologyState& state) { - (void) blockDrv.ActiveComponentBase::join(nullptr); - (void) chanTlm.ActiveComponentBase::join(nullptr); - (void) cmdDisp.ActiveComponentBase::join(nullptr); - (void) cmdSeq.ActiveComponentBase::join(nullptr); - comm.stopSocketTask(); - (void) comm.joinSocketTask(nullptr); - (void) eventLogger.ActiveComponentBase::join(nullptr); - (void) fileDownlink.ActiveComponentBase::join(nullptr); - (void) fileManager.ActiveComponentBase::join(nullptr); - (void) fileUplink.ActiveComponentBase::join(nullptr); - (void) pingRcvr.ActiveComponentBase::join(nullptr); - (void) prmDb.ActiveComponentBase::join(nullptr); - (void) rateGroup1Comp.ActiveComponentBase::join(nullptr); - (void) rateGroup2Comp.ActiveComponentBase::join(nullptr); - (void) rateGroup3Comp.ActiveComponentBase::join(nullptr); - } - - // Tear down components - void tearDownComponents(const TopologyState& state) { - cmdSeq.deallocateBuffer(Allocation::mallocator); - fileUplinkBufferManager.cleanup(); - } - - } - - // ---------------------------------------------------------------------- - // Public interface functions - // ---------------------------------------------------------------------- - - void setup(const TopologyState& state) { - initComponents(state); - configComponents(state); - setBaseIds(); - connectComponents(); - regCommands(); - readParameters(); - loadParameters(); - startTasks(state); - } - - void teardown(const TopologyState& state) { - stopTasks(state); - freeThreads(state); - tearDownComponents(state); - } - -} diff --git a/Ref/Top/RefTopologyAc.hpp b/Ref/Top/RefTopologyAc.hpp deleted file mode 100644 index 5617dff5a2..0000000000 --- a/Ref/Top/RefTopologyAc.hpp +++ /dev/null @@ -1,249 +0,0 @@ -// ====================================================================== -// \title RefTopologyAc.hpp -// \author Generated by fpp-to-cpp -// \brief hpp file for Ref topology -// -// \copyright -// Copyright (c) 2021 California Institute of Technology. -// U.S. Government sponsorship acknowledged. -// All rights reserved. -// ====================================================================== - -#ifndef Ref_RefTopologyAc_HPP -#define Ref_RefTopologyAc_HPP - -#include "Drv/BlockDriver/BlockDriver.hpp" -#include "Drv/TcpClient/TcpClient.hpp" -#include "Ref/PingReceiver/PingReceiver.hpp" -#include "Ref/RecvBuffApp/RecvBuff.hpp" -#include "Ref/SendBuffApp/SendBuff.hpp" -#include "Ref/SignalGen/SignalGen.hpp" -#include "Ref/Top/RefTopologyDefs.hpp" -#include "Svc/ActiveLogger/ActiveLogger.hpp" -#include "Svc/ActiveRateGroup/ActiveRateGroup.hpp" -#include "Svc/AssertFatalAdapter/AssertFatalAdapter.hpp" -#include "Svc/BufferManager/BufferManager.hpp" -#include "Svc/CmdDispatcher/CommandDispatcher.hpp" -#include "Svc/CmdSequencer/CmdSequencer.hpp" -#include "Svc/Deframer/Deframer.hpp" -#include "Svc/FatalHandler/FatalHandler.hpp" -#include "Svc/FileDownlink/FileDownlink.hpp" -#include "Svc/FileManager/FileManager.hpp" -#include "Svc/FileUplink/FileUplink.hpp" -#include "Svc/Framer/Framer.hpp" -#include "Svc/Health/Health.hpp" -#include "Svc/LinuxTime/LinuxTime.hpp" -#include "Svc/PassiveConsoleTextLogger/PassiveTextLogger.hpp" -#include "Svc/PrmDb/PrmDb.hpp" -#include "Svc/RateGroupDriver/RateGroupDriver.hpp" -#include "Svc/StaticMemory/StaticMemory.hpp" -#include "Svc/TlmChan/TlmChan.hpp" - -namespace Ref { - - // ---------------------------------------------------------------------- - // Constants - // ---------------------------------------------------------------------- - - namespace ConfigConstants { - namespace cmdSeq { - enum { - BUFFER_SIZE = 5*1024 - }; - } - namespace comm { - enum { - PRIORITY = 100, - STACK_SIZE = Default::stackSize - }; - } - namespace fileDownlink { - enum { - TIMEOUT = 1000, - COOLDOWN = 1000, - CYCLE_TIME = 1000, - FILE_QUEUE_DEPTH = 10 - }; - } - namespace fileUplinkBufferManager { - enum { - STORE_SIZE = 3000, - QUEUE_SIZE = 30, - MGR_ID = 200 - }; - } - namespace health { - enum { - WATCHDOG_CODE = 0x123 - }; - } - } - - namespace BaseIds { - enum { - blockDrv = 0x100, - rateGroup1Comp = 0x200, - rateGroup2Comp = 0x300, - rateGroup3Comp = 0x400, - cmdDisp = 0x500, - cmdSeq = 0x600, - fileDownlink = 0x700, - fileManager = 0x800, - fileUplink = 0x900, - pingRcvr = 0xA00, - eventLogger = 0xB00, - chanTlm = 0xC00, - prmDb = 0xD00, - health = 0x2000, - SG1 = 0x2100, - SG2 = 0x2200, - SG3 = 0x2300, - SG4 = 0x2400, - SG5 = 0x2500, - sendBuffComp = 0x2600, - comm = 0x4000, - downlink = 0x4100, - fatalAdapter = 0x4200, - fatalHandler = 0x4300, - fileUplinkBufferManager = 0x4400, - linuxTime = 0x4500, - rateGroupDriverComp = 0x4600, - recvBuffComp = 0x4700, - staticMemory = 0x4800, - textLogger = 0x4900, - uplink = 0x4A00, - }; - } - - namespace InstanceIds { - enum { - SG1, - SG2, - SG3, - SG4, - SG5, - blockDrv, - chanTlm, - cmdDisp, - cmdSeq, - comm, - downlink, - eventLogger, - fatalAdapter, - fatalHandler, - fileDownlink, - fileManager, - fileUplink, - fileUplinkBufferManager, - health, - linuxTime, - pingRcvr, - prmDb, - rateGroup1Comp, - rateGroup2Comp, - rateGroup3Comp, - rateGroupDriverComp, - recvBuffComp, - sendBuffComp, - staticMemory, - textLogger, - uplink, - }; - } - - namespace Priorities { - enum { - blockDrv = 140, - chanTlm = 97, - cmdDisp = 101, - cmdSeq = 100, - eventLogger = 98, - fileDownlink = 100, - fileManager = 100, - fileUplink = 100, - pingRcvr = 100, - prmDb = 96, - rateGroup1Comp = 120, - rateGroup2Comp = 119, - rateGroup3Comp = 118, - }; - } - - namespace QueueSizes { - enum { - SG1 = 10, - SG2 = 10, - SG3 = 10, - SG4 = 10, - SG5 = 10, - blockDrv = 10, - chanTlm = 10, - cmdDisp = 20, - cmdSeq = 10, - eventLogger = 10, - fileDownlink = 30, - fileManager = 30, - fileUplink = 30, - health = 25, - pingRcvr = 10, - prmDb = 10, - rateGroup1Comp = 10, - rateGroup2Comp = 10, - rateGroup3Comp = 10, - sendBuffComp = 10, - }; - } - - namespace StackSizes { - enum { - blockDrv = 16384, - chanTlm = 16384, - cmdDisp = 16384, - cmdSeq = 16384, - eventLogger = 16384, - fileDownlink = 16384, - fileManager = 16384, - fileUplink = 16384, - pingRcvr = 16384, - prmDb = 16384, - rateGroup1Comp = 16384, - rateGroup2Comp = 16384, - rateGroup3Comp = 16384, - }; - } - - namespace TaskIds { - enum { - blockDrv, - chanTlm, - cmdDisp, - cmdSeq, - eventLogger, - fileDownlink, - fileManager, - fileUplink, - pingRcvr, - prmDb, - rateGroup1Comp, - rateGroup2Comp, - rateGroup3Comp, - }; - } - - // ---------------------------------------------------------------------- - // Public interface functions - // ---------------------------------------------------------------------- - - //! Set up the topology - void setup( - const TopologyState& state //!< The topology state - ); - - //! Tear down the topology - void teardown( - const TopologyState& state //!< The topology state - ); - -} - -#endif diff --git a/Ref/Top/RefTopologyAppAi.xml b/Ref/Top/RefTopologyAppAi.xml deleted file mode 100644 index a1d06fb439..0000000000 --- a/Ref/Top/RefTopologyAppAi.xml +++ /dev/null @@ -1,896 +0,0 @@ - - - - - - Drv/BlockDriver/BlockDriverComponentAi.xml - Drv/ByteStreamDriverModel/ByteStreamDriverModelComponentAi.xml - Ref/PingReceiver/PingReceiverComponentAi.xml - Ref/RecvBuffApp/RecvBuffComponentAi.xml - Ref/SendBuffApp/SendBuffComponentAi.xml - Ref/SignalGen/SignalGenComponentAi.xml - Svc/ActiveLogger/ActiveLoggerComponentAi.xml - Svc/ActiveRateGroup/ActiveRateGroupComponentAi.xml - Svc/AssertFatalAdapter/AssertFatalAdapterComponentAi.xml - Svc/BufferManager/BufferManagerComponentAi.xml - Svc/CmdDispatcher/CommandDispatcherComponentAi.xml - Svc/CmdSequencer/CmdSequencerComponentAi.xml - Svc/Deframer/DeframerComponentAi.xml - Svc/FatalHandler/FatalHandlerComponentAi.xml - Svc/FileDownlink/FileDownlinkComponentAi.xml - Svc/FileManager/FileManagerComponentAi.xml - Svc/FileUplink/FileUplinkComponentAi.xml - Svc/Framer/FramerComponentAi.xml - Svc/Health/HealthComponentAi.xml - Svc/PassiveConsoleTextLogger/PassiveTextLoggerComponentAi.xml - Svc/PrmDb/PrmDbComponentAi.xml - Svc/RateGroupDriver/RateGroupDriverComponentAi.xml - Svc/StaticMemory/StaticMemoryComponentAi.xml - Svc/Time/TimeComponentAi.xml - Svc/TlmChan/TlmChanComponentAi.xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/Ref/Top/RefTopologyDefs.cpp b/Ref/Top/RefTopologyDefs.cpp deleted file mode 100644 index cbd9cd7946..0000000000 --- a/Ref/Top/RefTopologyDefs.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "Ref/Top/RefTopologyDefs.hpp" - -namespace Ref { - - namespace Allocation { - - Fw::MallocAllocator mallocator; - - } - -} diff --git a/Ref/Top/RefTopologyDefs.hpp b/Ref/Top/RefTopologyDefs.hpp index bd91a825b5..93e50bbfbe 100644 --- a/Ref/Top/RefTopologyDefs.hpp +++ b/Ref/Top/RefTopologyDefs.hpp @@ -1,58 +1,97 @@ -#ifndef RefTopologyDefs_HPP -#define RefTopologyDefs_HPP +// ====================================================================== +// \title RefTopologyDefs.hpp +// \author mstarch +// \brief required header file containing the required definitions for the topology autocoder +// +// \copyright +// Copyright 2009-2022, by the California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// ====================================================================== +#ifndef REF_REFTOPOLOGYDEFS_HPP +#define REF_REFTOPOLOGYDEFS_HPP #include "Drv/BlockDriver/BlockDriver.hpp" #include "Fw/Types/MallocAllocator.hpp" #include "Ref/Top/FppConstantsAc.hpp" #include "Svc/FramingProtocol/FprimeProtocol.hpp" +#include "Svc/Health/Health.hpp" +// Definitions are placed within a namespace named after the deployment namespace Ref { - namespace Allocation { - - // Malloc allocator for topology construction - extern Fw::MallocAllocator mallocator; - - } - - // State for topology construction - struct TopologyState { - TopologyState() : - hostName(""), - portNumber(0) - { - - } - TopologyState( - const char *hostName, - U32 portNumber - ) : - hostName(hostName), - portNumber(portNumber) - { - - } - const char* hostName; - U32 portNumber; - }; - - // Health ping entries - namespace PingEntries { - namespace blockDrv { enum { WARN = 3, FATAL = 5 }; } - namespace chanTlm { enum { WARN = 3, FATAL = 5 }; } - namespace cmdDisp { enum { WARN = 3, FATAL = 5 }; } - namespace cmdSeq { enum { WARN = 3, FATAL = 5 }; } - namespace eventLogger { enum { WARN = 3, FATAL = 5 }; } - namespace fileDownlink { enum { WARN = 3, FATAL = 5 }; } - namespace fileManager { enum { WARN = 3, FATAL = 5 }; } - namespace fileUplink { enum { WARN = 3, FATAL = 5 }; } - namespace pingRcvr { enum { WARN = 3, FATAL = 5 }; } - namespace prmDb { enum { WARN = 3, FATAL = 5 }; } - namespace rateGroup1Comp { enum { WARN = 3, FATAL = 5 }; } - namespace rateGroup2Comp { enum { WARN = 3, FATAL = 5 }; } - namespace rateGroup3Comp { enum { WARN = 3, FATAL = 5 }; } - } +/** + * \brief required type definition to carry state + * + * The topology autocoder requires an object that carries state with the name `Ref::TopologyState`. Only the type + * definition is required by the autocoder and the contents of this object are otherwise opaque to the autocoder. The + * contents are entirely up to the definition of the project. This reference application specifies hostname and port + * fields, which are derived by command line inputs. + */ +struct TopologyState { + const char* hostname; + U32 port; +}; +/** + * \brief required ping constants + * + * The topology autocoder requires a WARN and FATAL constant definition for each component that supports the health-ping + * interface. These are expressed as enum constants placed in a namespace named for the component instance. These + * are all placed in the PingEntries namespace. + * + * Each constant specifies how many missed pings are allowed before a WARNING_HI/FATAL event is triggered. In the + * following example, the health component will emit a WARNING_HI event if the component instance cmdDisp does not + * respond for 3 pings and will FATAL if responses are not received after a total of 5 pings. + * + * ```c++ + * namespace PingEntries { + * namespace cmdDisp { + * enum { WARN = 3, FATAL = 5 }; + * } + * } + * ``` + */ +namespace PingEntries { +namespace blockDrv { +enum { WARN = 3, FATAL = 5 }; } - +namespace chanTlm { +enum { WARN = 3, FATAL = 5 }; +} +namespace cmdDisp { +enum { WARN = 3, FATAL = 5 }; +} +namespace cmdSeq { +enum { WARN = 3, FATAL = 5 }; +} +namespace eventLogger { +enum { WARN = 3, FATAL = 5 }; +} +namespace fileDownlink { +enum { WARN = 3, FATAL = 5 }; +} +namespace fileManager { +enum { WARN = 3, FATAL = 5 }; +} +namespace fileUplink { +enum { WARN = 3, FATAL = 5 }; +} +namespace pingRcvr { +enum { WARN = 3, FATAL = 5 }; +} +namespace prmDb { +enum { WARN = 3, FATAL = 5 }; +} +namespace rateGroup1Comp { +enum { WARN = 3, FATAL = 5 }; +} +namespace rateGroup2Comp { +enum { WARN = 3, FATAL = 5 }; +} +namespace rateGroup3Comp { +enum { WARN = 3, FATAL = 5 }; +} +} // namespace PingEntries +} // namespace Ref #endif diff --git a/Ref/Top/instances.fpp b/Ref/Top/instances.fpp index 67568eef7a..efde81b0bb 100644 --- a/Ref/Top/instances.fpp +++ b/Ref/Top/instances.fpp @@ -5,11 +5,8 @@ module Ref { # ---------------------------------------------------------------------- module Default { - - constant queueSize = 10 - - constant stackSize = 64 * 1024 - + constant QUEUE_SIZE = 10 + constant STACK_SIZE = 64 * 1024 } # ---------------------------------------------------------------------- @@ -17,206 +14,94 @@ module Ref { # ---------------------------------------------------------------------- instance blockDrv: Drv.BlockDriver base id 0x0100 \ - queue size Default.queueSize \ - stack size Default.stackSize \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ priority 140 instance rateGroup1Comp: Svc.ActiveRateGroup base id 0x0200 \ - queue size Default.queueSize \ - stack size Default.stackSize \ - priority 120 \ - { - - phase Fpp.ToCpp.Phases.configObjects """ - NATIVE_INT_TYPE context[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - rateGroup1Comp.configure( - ConfigObjects::rateGroup1Comp::context, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroup1Comp::context) - ); - """ - - } + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ + priority 120 instance rateGroup2Comp: Svc.ActiveRateGroup base id 0x0300 \ - queue size Default.queueSize \ - stack size Default.stackSize \ - priority 119 \ - { - - phase Fpp.ToCpp.Phases.configObjects """ - NATIVE_INT_TYPE context[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - rateGroup2Comp.configure( - ConfigObjects::rateGroup2Comp::context, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroup2Comp::context) - ); - """ - - } + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ + priority 119 instance rateGroup3Comp: Svc.ActiveRateGroup base id 0x0400 \ - queue size Default.queueSize \ - stack size Default.stackSize \ - priority 118 \ - { - - phase Fpp.ToCpp.Phases.configObjects """ - NATIVE_INT_TYPE context[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - rateGroup3Comp.configure( - ConfigObjects::rateGroup3Comp::context, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroup3Comp::context) - ); - """ - - } + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ + priority 118 instance cmdDisp: Svc.CommandDispatcher base id 0x0500 \ queue size 20 \ - stack size Default.stackSize \ + stack size Default.STACK_SIZE \ priority 101 instance cmdSeq: Svc.CmdSequencer base id 0x0600 \ - queue size Default.queueSize \ - stack size Default.stackSize \ - priority 100 \ - { - - phase Fpp.ToCpp.Phases.configConstants """ - enum { - BUFFER_SIZE = 5*1024 - }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - cmdSeq.allocateBuffer( - 0, - Allocation::mallocator, - ConfigConstants::cmdSeq::BUFFER_SIZE - ); - """ - - phase Fpp.ToCpp.Phases.tearDownComponents """ - cmdSeq.deallocateBuffer(Allocation::mallocator); - """ - - } + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ + priority 100 instance fileDownlink: Svc.FileDownlink base id 0x0700 \ queue size 30 \ - stack size Default.stackSize \ - priority 100 \ - { - - phase Fpp.ToCpp.Phases.configConstants """ - enum { - TIMEOUT = 1000, - COOLDOWN = 1000, - CYCLE_TIME = 1000, - FILE_QUEUE_DEPTH = 10 - }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - fileDownlink.configure( - ConfigConstants::fileDownlink::TIMEOUT, - ConfigConstants::fileDownlink::COOLDOWN, - ConfigConstants::fileDownlink::CYCLE_TIME, - ConfigConstants::fileDownlink::FILE_QUEUE_DEPTH - ); - """ - - } + stack size Default.STACK_SIZE \ + priority 100 instance fileManager: Svc.FileManager base id 0x0800 \ queue size 30 \ - stack size Default.stackSize \ + stack size Default.STACK_SIZE \ priority 100 instance fileUplink: Svc.FileUplink base id 0x0900 \ queue size 30 \ - stack size Default.stackSize \ + stack size Default.STACK_SIZE \ priority 100 instance pingRcvr: Ref.PingReceiver base id 0x0A00 \ - queue size Default.queueSize \ - stack size Default.stackSize \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ priority 100 instance eventLogger: Svc.ActiveLogger base id 0x0B00 \ - queue size Default.queueSize \ - stack size Default.stackSize \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ priority 98 instance chanTlm: Svc.TlmChan base id 0x0C00 \ - queue size Default.queueSize \ - stack size Default.stackSize \ + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ priority 97 instance prmDb: Svc.PrmDb base id 0x0D00 \ - queue size Default.queueSize \ - stack size Default.stackSize \ - priority 96 \ - { - - phase Fpp.ToCpp.Phases.instances """ - Svc::PrmDb prmDb(FW_OPTIONAL_NAME("prmDb"), "PrmDb.dat"); - """ - - phase Fpp.ToCpp.Phases.readParameters """ - prmDb.readParamFile(); - """ - - } + queue size Default.QUEUE_SIZE \ + stack size Default.STACK_SIZE \ + priority 96 # ---------------------------------------------------------------------- # Queued component instances # ---------------------------------------------------------------------- instance $health: Svc.Health base id 0x2000 \ - queue size 25 \ - { - - phase Fpp.ToCpp.Phases.configConstants """ - enum { - WATCHDOG_CODE = 0x123 - }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - health.setPingEntries( - ConfigObjects::health::pingEntries, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::health::pingEntries), - ConfigConstants::health::WATCHDOG_CODE - ); - """ - - } + queue size 25 instance SG1: Ref.SignalGen base id 0x2100 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE instance SG2: Ref.SignalGen base id 0x2200 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE instance SG3: Ref.SignalGen base id 0x2300 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE instance SG4: Ref.SignalGen base id 0x2400 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE instance SG5: Ref.SignalGen base id 0x2500 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE instance sendBuffComp: Ref.SendBuff base id 0x2600 \ - queue size Default.queueSize + queue size Default.QUEUE_SIZE # ---------------------------------------------------------------------- # Passive component instances @@ -225,105 +110,22 @@ module Ref { @ Communications driver. May be swapped with other comm drivers like UART @ Note: Here we have TCP reliable uplink and UDP (low latency) downlink instance comm: Drv.ByteStreamDriverModel base id 0x4000 \ - type "Drv::TcpClient" \ - at "../../Drv/TcpClient/TcpClient.hpp" \ - { - - phase Fpp.ToCpp.Phases.configConstants """ - enum { - PRIORITY = 100, - STACK_SIZE = Default::stackSize - }; - """ - - phase Fpp.ToCpp.Phases.startTasks """ - // Initialize socket server if and only if there is a valid specification - if (state.hostName != nullptr && state.portNumber != 0) { - Os::TaskString name("ReceiveTask"); - // Uplink is configured for receive so a socket task is started - comm.configure(state.hostName, state.portNumber); - comm.startSocketTask( - name, - true, - ConfigConstants::comm::PRIORITY, - ConfigConstants::comm::STACK_SIZE - ); - } - """ - - phase Fpp.ToCpp.Phases.freeThreads """ - comm.stopSocketTask(); - (void) comm.joinSocketTask(nullptr); - """ - - } + type "Drv::TcpClient" \ # type specified to select implementor of ByteStreamDriverModel + at "../../Drv/TcpClient/TcpClient.hpp" # location of above implementor must also be specified - instance downlink: Svc.Framer base id 0x4100 { - - phase Fpp.ToCpp.Phases.configObjects """ - Svc::FprimeFraming framing; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - downlink.setup(ConfigObjects::downlink::framing); - """ - - } + instance downlink: Svc.Framer base id 0x4100 instance fatalAdapter: Svc.AssertFatalAdapter base id 0x4200 instance fatalHandler: Svc.FatalHandler base id 0x4300 - instance fileUplinkBufferManager: Svc.BufferManager base id 0x4400 { - - phase Fpp.ToCpp.Phases.configConstants """ - enum { - STORE_SIZE = 3000, - QUEUE_SIZE = 30, - MGR_ID = 200 - }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - Svc::BufferManager::BufferBins upBuffMgrBins; - memset(&upBuffMgrBins, 0, sizeof(upBuffMgrBins)); - { - using namespace ConfigConstants::fileUplinkBufferManager; - upBuffMgrBins.bins[0].bufferSize = STORE_SIZE; - upBuffMgrBins.bins[0].numBuffers = QUEUE_SIZE; - fileUplinkBufferManager.setup( - MGR_ID, - 0, - Allocation::mallocator, - upBuffMgrBins - ); - } - """ - - phase Fpp.ToCpp.Phases.tearDownComponents """ - fileUplinkBufferManager.cleanup(); - """ - - } + instance fileUplinkBufferManager: Svc.BufferManager base id 0x4400 instance linuxTime: Svc.Time base id 0x4500 \ type "Svc::LinuxTime" \ at "../../Svc/LinuxTime/LinuxTime.hpp" - instance rateGroupDriverComp: Svc.RateGroupDriver base id 0x4600 { - - phase Fpp.ToCpp.Phases.configObjects """ - NATIVE_INT_TYPE rgDivs[Svc::RateGroupDriver::DIVIDER_SIZE] = { 1, 2, 4 }; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - rateGroupDriverComp.configure( - ConfigObjects::rateGroupDriverComp::rgDivs, - FW_NUM_ARRAY_ELEMENTS(ConfigObjects::rateGroupDriverComp::rgDivs) - ); - """ - - } + instance rateGroupDriverComp: Svc.RateGroupDriver base id 0x4600 instance recvBuffComp: Ref.RecvBuff base id 0x4700 @@ -331,17 +133,7 @@ module Ref { instance textLogger: Svc.PassiveTextLogger base id 0x4900 - instance uplink: Svc.Deframer base id 0x4A00 { - - phase Fpp.ToCpp.Phases.configObjects """ - Svc::FprimeDeframing deframing; - """ - - phase Fpp.ToCpp.Phases.configComponents """ - uplink.setup(ConfigObjects::uplink::deframing); - """ - - } + instance uplink: Svc.Deframer base id 0x4A00 instance systemResources: Svc.SystemResources base id 0x4B00 diff --git a/Svc/ActiveRateGroup/ActiveRateGroup.hpp b/Svc/ActiveRateGroup/ActiveRateGroup.hpp index 62fc8f15b9..11e64d8103 100644 --- a/Svc/ActiveRateGroup/ActiveRateGroup.hpp +++ b/Svc/ActiveRateGroup/ActiveRateGroup.hpp @@ -30,6 +30,7 @@ namespace Svc { class ActiveRateGroup : public ActiveRateGroupComponentBase { public: + static constexpr NATIVE_INT_TYPE CONNECTION_COUNT_MAX = NUM_RATEGROUPMEMBEROUT_OUTPUT_PORTS; //! \brief ActiveRateGroup constructor //! @@ -110,7 +111,7 @@ namespace Svc { U32 m_cycles; //!< cycles executed U32 m_maxTime; //!< maximum execution time in microseconds volatile bool m_cycleStarted; //!< indicate that cycle has started. Used to detect overruns. - NATIVE_INT_TYPE m_contexts[NUM_RATEGROUPMEMBEROUT_OUTPUT_PORTS]; //!< Must match number of output ports + NATIVE_INT_TYPE m_contexts[CONNECTION_COUNT_MAX]; //!< Must match number of output ports NATIVE_INT_TYPE m_numContexts; //!< Number of contexts passed in by user NATIVE_INT_TYPE m_overrunThrottle; //!< throttle value for overrun events U32 m_cycleSlips; //!< tracks number of cycle slips diff --git a/Svc/PrmDb/PrmDbImpl.cpp b/Svc/PrmDb/PrmDbImpl.cpp index 6fb74adc39..540ce5b162 100644 --- a/Svc/PrmDb/PrmDbImpl.cpp +++ b/Svc/PrmDb/PrmDbImpl.cpp @@ -41,8 +41,12 @@ namespace Svc { }; } - PrmDbImpl::PrmDbImpl(const char* name, const char* file) : PrmDbComponentBase(name) { + PrmDbImpl::PrmDbImpl(const char* name) : PrmDbComponentBase(name) { this->clearDb(); + } + + void PrmDbImpl::configure(const char* file) { + FW_ASSERT(file != nullptr); this->m_fileName = file; } @@ -125,7 +129,7 @@ namespace Svc { } void PrmDbImpl::PRM_SAVE_FILE_cmdHandler(FwOpcodeType opCode, U32 cmdSeq) { - + FW_ASSERT(this->m_fileName.length() > 0); Os::File paramFile; WorkingBuffer buff; @@ -240,6 +244,7 @@ namespace Svc { } void PrmDbImpl::readParamFile() { + FW_ASSERT(this->m_fileName.length() > 0); // load file. FIXME: Put more robust file checking, such as a CRC. Os::File paramFile; diff --git a/Svc/PrmDb/PrmDbImpl.hpp b/Svc/PrmDb/PrmDbImpl.hpp index 53ccfd90bb..3016849558 100644 --- a/Svc/PrmDb/PrmDbImpl.hpp +++ b/Svc/PrmDb/PrmDbImpl.hpp @@ -39,8 +39,7 @@ namespace Svc { //! the file name for opening later. //! //! \param name component instance name - //! \param file file where parameters are stored. - PrmDbImpl(const char* name, const char* file); + PrmDbImpl(const char* name); //! \brief PrmDb initialization function //! @@ -52,6 +51,14 @@ namespace Svc { void init(NATIVE_INT_TYPE queueDepth, NATIVE_INT_TYPE instance); + //! \brief PrmDb configure method + //! + //! The configure method stores the file name for opening later. + //! + //! \param file file where parameters are stored. + void configure(const char* file); + + //! \brief PrmDb file read function //! //! The readFile function reads the set of parameters from the file passed in to diff --git a/Svc/PrmDb/test/ut/PrmDbTester.cpp b/Svc/PrmDb/test/ut/PrmDbTester.cpp index 8c41e92d72..cfff113f04 100644 --- a/Svc/PrmDb/test/ut/PrmDbTester.cpp +++ b/Svc/PrmDb/test/ut/PrmDbTester.cpp @@ -44,10 +44,10 @@ TEST(ParameterDbTest,NominalPopulateTest) { TEST_CASE(105.1.1,"Nominal populate test"); COMMENT("Write values to the parameter database and verify that they were written correctly"); - Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); + Svc::PrmDbImpl impl("PrmDbImpl"); impl.init(10,0); - + impl.configure("TestFile.prm"); Svc::PrmDbImplTester tester(impl); tester.init(); @@ -65,9 +65,10 @@ TEST(ParameterDbTest,NominalFileSaveTest) { TEST_CASE(105.1.2,"Nominal file save test"); COMMENT("Write values to the parameter database and save them to a file."); - Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); + Svc::PrmDbImpl impl("PrmDbImpl"); impl.init(10,0); + impl.configure("TestFile.prm"); Svc::PrmDbImplTester tester(impl); @@ -86,9 +87,10 @@ TEST(ParameterDbTest,NominalFileLoadTest) { TEST_CASE(105.1.3,"Nominal file load test"); COMMENT("Read values from the created file and verify they are correct."); - Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); + Svc::PrmDbImpl impl("PrmDbImpl"); impl.init(10,0); + impl.configure("TestFile.prm"); Svc::PrmDbImplTester tester(impl); @@ -104,7 +106,7 @@ TEST(ParameterDbTest,NominalFileLoadTest) { //TEST(ParameterDbTest,RefPrmFile) { // -// Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); +// Svc::PrmDbImpl impl("PrmDbImpl"); // // impl.init(10); // @@ -125,9 +127,10 @@ TEST(ParameterDbTest,PrmMissingExtraParamsTest) { TEST_CASE(105.2.1,"Missing and too many parameters test"); COMMENT("Attempt to read a nonexistent parameter and write too many parameters"); - Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); + Svc::PrmDbImpl impl("PrmDbImpl"); impl.init(10,0); + impl.configure("TestFile.prm"); Svc::PrmDbImplTester tester(impl); @@ -146,9 +149,10 @@ TEST(ParameterDbTest,PrmFileReadError) { TEST_CASE(105.2.2,"File read errors"); COMMENT("Induce errors at various stages of reading the file"); - Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); + Svc::PrmDbImpl impl("PrmDbImpl"); impl.init(10,0); + impl.configure("TestFile.prm"); Svc::PrmDbImplTester tester(impl); @@ -167,9 +171,10 @@ TEST(ParameterDbTest,PrmFileWriteError) { TEST_CASE(105.2.3,"File write errors"); COMMENT("Induce errors at various stages of writing the file"); - Svc::PrmDbImpl impl("PrmDbImpl","TestFile.prm"); + Svc::PrmDbImpl impl("PrmDbImpl"); impl.init(10,0); + impl.configure("TestFile.prm"); Svc::PrmDbImplTester tester(impl); From 8943e4d8a788508f93247c03ac8bd042f05ede9a Mon Sep 17 00:00:00 2001 From: Thibault <70470823+ThibFrgsGmz@users.noreply.github.com> Date: Tue, 8 Nov 2022 02:55:09 +0100 Subject: [PATCH 092/169] Fix #1709 PolyType does not compile when FW_HAS_F64 is undefined (#1764) * Encapsulate TYPE_F64 w/ FW_HAS_F64 * Undefine TYPE_U/I wrt FW_HAS_XX_BIT --- Fw/Types/PolyType.cpp | 4 ++++ Fw/Types/PolyType.hpp | 8 ++++++++ 2 files changed, 12 insertions(+) diff --git a/Fw/Types/PolyType.cpp b/Fw/Types/PolyType.cpp index d0fb11a573..32c2eeb702 100644 --- a/Fw/Types/PolyType.cpp +++ b/Fw/Types/PolyType.cpp @@ -533,6 +533,8 @@ namespace Fw { case TYPE_I64: stat = buffer.serialize(this->m_val.i64Val); break; +#endif +#if FW_HAS_F64 case TYPE_F64: stat = buffer.serialize(this->m_val.f64Val); break; @@ -586,6 +588,8 @@ namespace Fw { return buffer.deserialize(this->m_val.u64Val); case TYPE_I64: return buffer.deserialize(this->m_val.i64Val); +#endif +#if FW_HAS_F64 case TYPE_F64: return buffer.deserialize(this->m_val.f64Val); #endif diff --git a/Fw/Types/PolyType.hpp b/Fw/Types/PolyType.hpp index 3d6ba541fc..5f24b4813d 100644 --- a/Fw/Types/PolyType.hpp +++ b/Fw/Types/PolyType.hpp @@ -113,14 +113,22 @@ namespace Fw { TYPE_NOTYPE, // !< No type stored yet TYPE_U8, // !< U8 type stored TYPE_I8, // !< I8 type stored +#if FW_HAS_16_BIT TYPE_U16, // !< U16 type stored TYPE_I16, // !< I16 type stored +#endif +#if FW_HAS_32_BIT TYPE_U32, // !< U32 type stored TYPE_I32, // !< I32 type stored +#endif +#if FW_HAS_64_BIT TYPE_U64, // !< U64 type stored TYPE_I64, // !< I64 type stored +#endif TYPE_F32, // !< F32 type stored +#if FW_HAS_F64 TYPE_F64, // !< F64 type stored +#endif TYPE_BOOL, // !< bool type stored TYPE_PTR // !< pointer type stored } Type; From 44e8917bb758f99058c72fd2af1d7d5ed0ffe780 Mon Sep 17 00:00:00 2001 From: Tiffany Chieu Date: Wed, 9 Nov 2022 09:19:34 -0800 Subject: [PATCH 093/169] FPP v1.1.0 Integration (#1630) * Add enum tests for FPP autocoder * Filter ai_xml sources against generated sources * Revise enum tests for FPP autocoder * Add test utils for FPP autocoder * Add array tests for FPP autocoder * Refactor FppTest * Add .gitignore * Revise enum tests for FPP autocoder * Revise array tests for FPP autocoder * Add string tests for FPP autocoder * Small changes to FPP autocoder tests * Add struct tests for FPP autocoder * Revise enum tests for FPP autocoder * Update ActiveLogger and Health components for new enum deserialize() behavior * Make string test suite type-parametrized * Update READMEs for FppTest * Register FppTest as a deployment and add README * Remove quotes from GENERATED_SOURCES * Begin transition to type-parametrized tests * Transition to type-parametrized tests * Small changes to FPP autocoder tests * Small fix to FPP autocoder tests * Update fprime-fpp version * Update expected words for spell checker * Small fix * Update fprime-fpp version * Add file headers * Update expected words for spell checker * Update fprime-fpp version * Update fprime-fpp version --- .github/actions/spelling/expect.txt | 10 +- FppTest/.gitignore | 1 + FppTest/CMakeLists.txt | 27 ++ FppTest/README.md | 9 + FppTest/array/ArrayToStringTest.cpp | 60 ++++ FppTest/array/CMakeLists.txt | 29 ++ FppTest/array/FormatTest.cpp | 282 +++++++++++++++ FppTest/array/README.md | 12 + FppTest/array/array.fpp | 3 + FppTest/array/enum.fpp | 7 + FppTest/array/format.fpp | 27 ++ FppTest/array/main.cpp | 146 ++++++++ FppTest/array/string.fpp | 3 + FppTest/array/struct.fpp | 6 + FppTest/enum/CMakeLists.txt | 27 ++ FppTest/enum/EnumToStringTest.cpp | 125 +++++++ FppTest/enum/IsValidTest.cpp | 54 +++ FppTest/enum/README.md | 12 + FppTest/enum/default.fpp | 8 + FppTest/enum/explicit.fpp | 6 + FppTest/enum/implicit.fpp | 8 + FppTest/enum/interval.fpp | 10 + FppTest/enum/main.cpp | 108 ++++++ FppTest/enum/serialize_type.fpp | 16 + FppTest/source.cpp | 1 + FppTest/struct/CMakeLists.txt | 25 ++ FppTest/struct/NonPrimitiveStructTest.cpp | 332 ++++++++++++++++++ FppTest/struct/PrimitiveStructTest.cpp | 215 ++++++++++++ FppTest/struct/README.md | 9 + FppTest/struct/main.cpp | 44 +++ FppTest/struct/struct.fpp | 31 ++ FppTest/typed_tests/ArrayTest.hpp | 237 +++++++++++++ FppTest/typed_tests/EnumTest.hpp | 210 +++++++++++ FppTest/typed_tests/README.md | 175 +++++++++ FppTest/typed_tests/StringTest.hpp | 131 +++++++ FppTest/utils/Utils.cpp | 58 +++ FppTest/utils/Utils.hpp | 36 ++ Svc/ActiveLogger/ActiveLoggerImpl.cpp | 17 - .../test/ut/ActiveLoggerImplTester.cpp | 10 +- Svc/Health/HealthComponentImpl.cpp | 6 - Svc/Health/test/ut/Tester.cpp | 2 +- requirements.txt | 2 +- 42 files changed, 2505 insertions(+), 32 deletions(-) create mode 100644 FppTest/.gitignore create mode 100644 FppTest/CMakeLists.txt create mode 100644 FppTest/README.md create mode 100644 FppTest/array/ArrayToStringTest.cpp create mode 100644 FppTest/array/CMakeLists.txt create mode 100644 FppTest/array/FormatTest.cpp create mode 100644 FppTest/array/README.md create mode 100644 FppTest/array/array.fpp create mode 100644 FppTest/array/enum.fpp create mode 100644 FppTest/array/format.fpp create mode 100644 FppTest/array/main.cpp create mode 100644 FppTest/array/string.fpp create mode 100644 FppTest/array/struct.fpp create mode 100644 FppTest/enum/CMakeLists.txt create mode 100644 FppTest/enum/EnumToStringTest.cpp create mode 100644 FppTest/enum/IsValidTest.cpp create mode 100644 FppTest/enum/README.md create mode 100644 FppTest/enum/default.fpp create mode 100644 FppTest/enum/explicit.fpp create mode 100644 FppTest/enum/implicit.fpp create mode 100644 FppTest/enum/interval.fpp create mode 100644 FppTest/enum/main.cpp create mode 100644 FppTest/enum/serialize_type.fpp create mode 100644 FppTest/source.cpp create mode 100644 FppTest/struct/CMakeLists.txt create mode 100644 FppTest/struct/NonPrimitiveStructTest.cpp create mode 100644 FppTest/struct/PrimitiveStructTest.cpp create mode 100644 FppTest/struct/README.md create mode 100644 FppTest/struct/main.cpp create mode 100644 FppTest/struct/struct.fpp create mode 100644 FppTest/typed_tests/ArrayTest.hpp create mode 100644 FppTest/typed_tests/EnumTest.hpp create mode 100644 FppTest/typed_tests/README.md create mode 100644 FppTest/typed_tests/StringTest.hpp create mode 100644 FppTest/utils/Utils.cpp create mode 100644 FppTest/utils/Utils.hpp diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index a175684166..f1d5c08a83 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -160,6 +160,7 @@ changeme CHANNELID chdir cheetahtemplate +Chieu CHK CHNG chr @@ -552,6 +553,7 @@ gethostname getinput getitem getline +getm getopt getoutput getpid @@ -762,8 +764,8 @@ lineroo lineterm linting linux -LINUXUARTDRIVER LINUXTIMEIMPL +LINUXUARTDRIVER Listst LJR lkml @@ -1207,7 +1209,9 @@ SETFL setinheritsched setitem SETLOGGING +setm setop +setprecision setprotocol setquaternion setschedparam @@ -1280,6 +1284,7 @@ ssh ssize SSL sss +sstream Ssymbols stacklevel stackoverflow @@ -1311,6 +1316,7 @@ stringchan stringified Stringpacket stringparam +stringstream STRINGUTILS strlen strncat @@ -1470,8 +1476,8 @@ tts ttype Tuszynski TXD -typedef'ed typedef +typedef'ed typeid typeinfo typelist diff --git a/FppTest/.gitignore b/FppTest/.gitignore new file mode 100644 index 0000000000..404abb2212 --- /dev/null +++ b/FppTest/.gitignore @@ -0,0 +1 @@ +coverage/ diff --git a/FppTest/CMakeLists.txt b/FppTest/CMakeLists.txt new file mode 100644 index 0000000000..f767d187cd --- /dev/null +++ b/FppTest/CMakeLists.txt @@ -0,0 +1,27 @@ +### +# FPP Test +# +# Builds unit tests for FPP autocoder +### + +cmake_minimum_required(VERSION 3.13) +cmake_policy(SET CMP0048 NEW) +project(FppTest C CXX) + +include("${CMAKE_CURRENT_LIST_DIR}/../cmake/FPrime.cmake") +include("${CMAKE_CURRENT_LIST_DIR}/../cmake/FPrime-Code.cmake") + +if (BUILD_TESTING AND NOT __FPRIME_NO_UT_GEN__) + add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/enum/") + add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/array/") + add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/struct/") +endif() + +set(SOURCE_FILES "source.cpp") +set(MOD_DEPS + ${PROJECT_NAME}/enum + ${PROJECT_NAME}/array + ${PROJECT_NAME}/struct +) + +register_fprime_deployment() diff --git a/FppTest/README.md b/FppTest/README.md new file mode 100644 index 0000000000..1c966bbe59 --- /dev/null +++ b/FppTest/README.md @@ -0,0 +1,9 @@ +# FppTest + +This project contains unit tests for the FPP autocoder. + +To use this directory, you must have installed F Prime, and you must be inside +the F Prime Python virtual environment. + +* To build the tests, run `fprime-util build --ut`. +* To run the tests, run `fprime-util check`. diff --git a/FppTest/array/ArrayToStringTest.cpp b/FppTest/array/ArrayToStringTest.cpp new file mode 100644 index 0000000000..23ca249e72 --- /dev/null +++ b/FppTest/array/ArrayToStringTest.cpp @@ -0,0 +1,60 @@ +// ====================================================================== +// \title ArrayToStringTest.cpp +// \author T. Chieu +// \brief cpp file for ArrayToStringTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/array/EnumArrayAc.hpp" +#include "FppTest/array/StringArrayAc.hpp" +#include "FppTest/array/StructArrayAc.hpp" +#include "FppTest/array/Uint32ArrayArrayAc.hpp" + +#include "FppTest/typed_tests/ArrayTest.hpp" + +#include "gtest/gtest.h" + +#include + +// Test array string functions +template +class ArrayToStringTest : public ::testing::Test { +protected: + void SetUp() override { + FppTest::Array::setTestVals(testVals); + } + + typename ArrayType::ElementType testVals[ArrayType::SIZE]; +}; + +using ArrayTypes = ::testing::Types< + Enum, + String, + Struct, + Uint32Array +>; +TYPED_TEST_SUITE(ArrayToStringTest, ArrayTypes); + +// Test array toString() and ostream operator functions +TYPED_TEST(ArrayToStringTest, ToString) { + TypeParam a(this->testVals); + std::stringstream buf1, buf2; + + buf1 << a; + + buf2 << "[ "; + for (U32 i = 0; i < TypeParam::SIZE; i++) { + buf2 << this->testVals[i] << " "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} diff --git a/FppTest/array/CMakeLists.txt b/FppTest/array/CMakeLists.txt new file mode 100644 index 0000000000..23a286cec7 --- /dev/null +++ b/FppTest/array/CMakeLists.txt @@ -0,0 +1,29 @@ +# ====================================================================== +# CMakeLists.txt +# ====================================================================== + +# We need to declare the XML source files this way to invoke the autocoder. +# However, only the UT build is allowed here. +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/array.fpp" + "${CMAKE_CURRENT_LIST_DIR}/enum.fpp" + "${CMAKE_CURRENT_LIST_DIR}/string.fpp" + "${CMAKE_CURRENT_LIST_DIR}/struct.fpp" + "${CMAKE_CURRENT_LIST_DIR}/format.fpp" +) +register_fprime_module() + +# Declare dependencies on test modules +set(UT_MOD_DEPS + Fw/Test + STest +) + +# List all .cpp files as UT_SOURCE_FILES. Only the UT build is allowed. +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/ArrayToStringTest.cpp" + "${CMAKE_CURRENT_LIST_DIR}/FormatTest.cpp" + "${CMAKE_CURRENT_LIST_DIR}/../utils/Utils.cpp" + "${CMAKE_CURRENT_LIST_DIR}/main.cpp" +) +register_fprime_ut() diff --git a/FppTest/array/FormatTest.cpp b/FppTest/array/FormatTest.cpp new file mode 100644 index 0000000000..59ab523fd5 --- /dev/null +++ b/FppTest/array/FormatTest.cpp @@ -0,0 +1,282 @@ +// ====================================================================== +// \title FormatTest.cpp +// \author T. Chieu +// \brief cpp file for FormatTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/array/FormatBoolArrayAc.hpp" +#include "FppTest/array/FormatU8ArrayAc.hpp" +#include "FppTest/array/FormatU16DecArrayAc.hpp" +#include "FppTest/array/FormatU32OctArrayAc.hpp" +#include "FppTest/array/FormatU64HexArrayAc.hpp" +#include "FppTest/array/FormatI8ArrayAc.hpp" +#include "FppTest/array/FormatI16DecArrayAc.hpp" +#include "FppTest/array/FormatI32OctArrayAc.hpp" +#include "FppTest/array/FormatI64HexArrayAc.hpp" +#include "FppTest/array/FormatF32eArrayAc.hpp" +#include "FppTest/array/FormatF32fArrayAc.hpp" +#include "FppTest/array/FormatF64gArrayAc.hpp" +#include "FppTest/array/FormatStringArrayAc.hpp" +#include "FppTest/array/FormatCharArrayAc.hpp" +#include "FppTest/utils/Utils.hpp" + +#include "gtest/gtest.h" + +#include +#include + +// Tests FPP format strings +class FormatTest : public ::testing::Test { +protected: + void SetUp() override { + buf2 << "[ "; + } + + std::stringstream buf1, buf2; +}; + +TEST_F(FormatTest, Bool) { + bool testVals[FormatBool::SIZE] = {true, true, false}; + FormatBool a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatBool::SIZE; i++) { + buf2 << "a " << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, U8) { + U8 testVals[FormatU8::SIZE] = {0, 100, std::numeric_limits::max()}; + FormatU8 a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatU8::SIZE; i++) { + buf2 << "a " << (U16) testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, U16Dec) { + U16 testVals[FormatU16Dec::SIZE] = {0, 100, std::numeric_limits::max()}; + FormatU16Dec a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatU16Dec::SIZE; i++) { + buf2 << "a " << std::dec << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, U32Oct) { + U32 testVals[FormatU32Oct::SIZE] = {0, 100, std::numeric_limits::max()}; + FormatU32Oct a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatU32Oct::SIZE; i++) { + buf2 << "a " << std::oct << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, U64Hex) { + U64 testVals[FormatU64Hex::SIZE] = + {0, 100, std::numeric_limits::max()}; + FormatU64Hex a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatU64Hex::SIZE; i++) { + buf2 << "a " << std::hex << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, I8) { + I8 testVals[FormatI8::SIZE] = + {std::numeric_limits::min(), 0, std::numeric_limits::max()}; + FormatI8 a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatI8::SIZE; i++) { + buf2 << "a " << (I16) testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, I16Dec) { + I16 testVals[FormatI16Dec::SIZE] = + {std::numeric_limits::min(), 0, std::numeric_limits::max()}; + FormatI16Dec a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatI16Dec::SIZE; i++) { + buf2 << "a " << std::dec << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, I32Oct) { + I32 testVals[FormatI32Oct::SIZE] = + {std::numeric_limits::min(), 0, std::numeric_limits::max()}; + FormatI32Oct a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatI32Oct::SIZE; i++) { + buf2 << "a " << std::oct << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); + +} + +TEST_F(FormatTest, I64Hex) { + I64 testVals[FormatI64Hex::SIZE] = + {std::numeric_limits::min(), 0, std::numeric_limits::max()}; + FormatI64Hex a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatI64Hex::SIZE; i++) { + buf2 << "a " << std::hex << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, F32E) { + F32 testVals[FormatF32e::SIZE] = + {std::numeric_limits::min(), 0.0, std::numeric_limits::max()}; + FormatF32e a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatF32e::SIZE; i++) { + buf2 << "a " << std::setprecision(1) << std::scientific << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, F32F) { + F32 testVals[FormatF32f::SIZE] = + {std::numeric_limits::min(), 0.0, std::numeric_limits::max()}; + FormatF32f a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatF32f::SIZE; i++) { + buf2 << "a " << std::setprecision(2) << std::fixed << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, F64G) { + F64 testVals[FormatF64g::SIZE] = + {std::numeric_limits::min(), 0.0, std::numeric_limits::max()}; + FormatF64g a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatF64g::SIZE; i++) { + buf2 << "a " << std::setprecision(3) << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, String) { + FormatString::StringSize80 testVals[FormatString::SIZE]; + char buf[80]; + for (U32 i = 0; i < FormatString::SIZE; i++) { + FppTest::Utils::setString(buf, sizeof(buf)); + testVals[i] = buf; + } + + FormatString a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatString::SIZE; i++) { + buf2 << "% " << testVals[i].toChar() << " "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} + +TEST_F(FormatTest, Char) { + U8 testVals[FormatChar::SIZE] = + {FppTest::Utils::getU8(), FppTest::Utils::getU8(), FppTest::Utils::getU8()}; + FormatChar a(testVals); + + buf1 << a; + for (U32 i = 0; i < FormatChar::SIZE; i++) { + buf2 << "a " << testVals[i] << " b "; + } + buf2 << "]"; + + ASSERT_STREQ( + buf1.str().c_str(), + buf2.str().c_str() + ); +} diff --git a/FppTest/array/README.md b/FppTest/array/README.md new file mode 100644 index 0000000000..e2b06345e7 --- /dev/null +++ b/FppTest/array/README.md @@ -0,0 +1,12 @@ +# FppTest/array + +This directory contains unit tests for the FPP array code generator. + +* ArrayToStringTest: Tests array toString() and ostream operator functions +* FormatTest: Tests FPP format strings + +To use this directory, you must have installed F Prime, and you must be inside +the F Prime Python virtual environment. + +* To build the tests, run `fprime-util build --ut`. +* To run the tests, run `fprime-util check`. \ No newline at end of file diff --git a/FppTest/array/array.fpp b/FppTest/array/array.fpp new file mode 100644 index 0000000000..a9c17a3c23 --- /dev/null +++ b/FppTest/array/array.fpp @@ -0,0 +1,3 @@ +array Uint32 = [2] U32; + +array Uint32Array = [3] Uint32; diff --git a/FppTest/array/enum.fpp b/FppTest/array/enum.fpp new file mode 100644 index 0000000000..d536e60602 --- /dev/null +++ b/FppTest/array/enum.fpp @@ -0,0 +1,7 @@ +enum E { + A, + B, + C, +} + +array Enum = [3] E default [ E.A, E.B, E.C ] diff --git a/FppTest/array/format.fpp b/FppTest/array/format.fpp new file mode 100644 index 0000000000..241ae68fc0 --- /dev/null +++ b/FppTest/array/format.fpp @@ -0,0 +1,27 @@ +array FormatBool = [3] bool format "a {} b" + +array FormatU8 = [3] U8 format "a {} b" + +array FormatU16Dec = [3] U16 format "a {d} b" + +array FormatU32Oct = [3] U32 format "a {o} b" + +array FormatU64Hex = [3] U64 format "a {x} b" + +array FormatI8 = [3] I8 format "a {} b" + +array FormatI16Dec = [3] I16 format "a {d} b" + +array FormatI32Oct = [3] I32 format "a {o} b" + +array FormatI64Hex = [3] I64 format "a {x} b" + +array FormatF32e = [3] F32 format "a {.1e} b" + +array FormatF32f = [3] F32 format "a {.2f} b" + +array FormatF64g = [3] F64 format "a {.3g} b" + +array FormatString = [3] string format "% {}" + +array FormatChar = [3] U8 format "a {c} b" diff --git a/FppTest/array/main.cpp b/FppTest/array/main.cpp new file mode 100644 index 0000000000..856fcc1f45 --- /dev/null +++ b/FppTest/array/main.cpp @@ -0,0 +1,146 @@ +// ====================================================================== +// \title main.cpp +// \author T. Chieu +// \brief main cpp file for FPP array tests +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/array/EnumArrayAc.hpp" +#include "FppTest/array/StringArrayAc.hpp" +#include "FppTest/array/StructArrayAc.hpp" +#include "FppTest/array/Uint32ArrayArrayAc.hpp" +#include "FppTest/array/String100ArrayAc.hpp" + +#include "FppTest/typed_tests/ArrayTest.hpp" +#include "FppTest/typed_tests/StringTest.hpp" +#include "FppTest/utils/Utils.hpp" + +#include "STest/Random/Random.hpp" +#include "gtest/gtest.h" + +// Instantiate array tests +using ArrayTestImplementations = ::testing::Types< + Enum, + String, + Struct, + Uint32Array +>; +INSTANTIATE_TYPED_TEST_SUITE_P(FppTest, ArrayTest, ArrayTestImplementations); + +// Specializations for default values +template <> +void FppTest::Array::setDefaultVals(E (&a)[Enum::SIZE]) { + a[0] = E::A; + a[1] = E::B; + a[2] = E::C; +} + +// Specialization for test values +template<> +void FppTest::Array::setTestVals(E (&a)[Enum::SIZE]) { + a[0] = static_cast(STest::Pick::startLength( + E::B, + E::NUM_CONSTANTS - 1 + )); + + for (U32 i = 1; i < Enum::SIZE; i++) { + a[i] = static_cast(STest::Pick::startLength( + E::A, + E::NUM_CONSTANTS - 1 + )); + } +} + +template<> +void FppTest::Array::setTestVals + (::String::StringSize80 (&a)[::String::SIZE]) { + char buf[80]; + for (U32 i = 0; i < ::String::SIZE; i++) { + FppTest::Utils::setString(buf, sizeof(buf)); + a[i] = buf; + } +} + +template<> +void FppTest::Array::setTestVals(S (&a)[Struct::SIZE]) { + U32 b[3]; + for (U32 i = 0; i < Struct::SIZE; i++) { + for (U32 j = 0; j < 3; j++) { + b[j] = FppTest::Utils::getU32(); + } + a[i].set(FppTest::Utils::getU32(), b); + } +} + +template<> +void FppTest::Array::setTestVals(Uint32 (&a)[Uint32Array::SIZE]) { + Uint32 b; + for (U32 i = 0; i < Uint32Array::SIZE; i++) { + for (U32 j = 0; j < Uint32::SIZE; j++) { + b[j] = FppTest::Utils::getU32(); + } + a[i] = b; + } +} + +// Specializations for multi element constructor +template<> +Enum FppTest::Array::getMultiElementConstructedArray + (E (&a)[Enum::SIZE]) { + return Enum(a[0], a[1], a[2]); +} + +template<> +::String FppTest::Array::getMultiElementConstructedArray<::String> + (::String::StringSize80 (&a)[::String::SIZE]) { + return ::String(a[0], a[1], a[2]); +} + +template<> +Struct FppTest::Array::getMultiElementConstructedArray + (S (&a)[Struct::SIZE]) { + return Struct(a[0], a[1], a[2]); +} + +template<> +Uint32Array FppTest::Array::getMultiElementConstructedArray + (Uint32 (&a)[Uint32Array::SIZE]) { + return Uint32Array(a[0], a[1], a[2]); +} + +// Specializations for serialized size +template <> +U32 FppTest::Array::getSerializedSize<::String> + (::String::StringSize80 (&a)[::String::SIZE]) { + U32 serializedSize = 0; + + for (U32 i = 0; i < ::String::SIZE; i++) { + serializedSize += a[i].length() + sizeof(FwBuffSizeType); + } + + return serializedSize; +} + +// Instantiate string tests for arrays +using StringTestImplementations = ::testing::Types< + String::StringSize80, + String100::StringSize100 +>; +INSTANTIATE_TYPED_TEST_SUITE_P(Array, StringTest, StringTestImplementations); + +template<> +U32 FppTest::String::getSize() { + return 100; +} + +int main(int argc, char* argv[]) { + ::testing::InitGoogleTest(&argc, argv); + STest::Random::seed(); + + return RUN_ALL_TESTS(); +} diff --git a/FppTest/array/string.fpp b/FppTest/array/string.fpp new file mode 100644 index 0000000000..fc2c052005 --- /dev/null +++ b/FppTest/array/string.fpp @@ -0,0 +1,3 @@ +array String = [3] string + +array String100 = [3] string size 100 diff --git a/FppTest/array/struct.fpp b/FppTest/array/struct.fpp new file mode 100644 index 0000000000..1c47492abe --- /dev/null +++ b/FppTest/array/struct.fpp @@ -0,0 +1,6 @@ +struct S { + mU32: U32 + mU32Arr: [3] U32 +} + +array Struct = [3] S diff --git a/FppTest/enum/CMakeLists.txt b/FppTest/enum/CMakeLists.txt new file mode 100644 index 0000000000..4dc0819bc7 --- /dev/null +++ b/FppTest/enum/CMakeLists.txt @@ -0,0 +1,27 @@ +# ====================================================================== +# CMakeLists.txt +# ====================================================================== + +# We need to declare the XML source files this way to invoke the autocoder. +# However, only the UT build is allowed here. +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/implicit.fpp" + "${CMAKE_CURRENT_LIST_DIR}/explicit.fpp" + "${CMAKE_CURRENT_LIST_DIR}/default.fpp" + "${CMAKE_CURRENT_LIST_DIR}/interval.fpp" + "${CMAKE_CURRENT_LIST_DIR}/serialize_type.fpp" +) +register_fprime_module() + +# Declare dependencies on test modules +set(UT_MOD_DEPS + Fw/Test + STest +) + +# List all .cpp files as UT_SOURCE_FILES. Only the UT build is allowed. +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/EnumToStringTest.cpp" + "${CMAKE_CURRENT_LIST_DIR}/main.cpp" +) +register_fprime_ut() diff --git a/FppTest/enum/EnumToStringTest.cpp b/FppTest/enum/EnumToStringTest.cpp new file mode 100644 index 0000000000..c533b637f7 --- /dev/null +++ b/FppTest/enum/EnumToStringTest.cpp @@ -0,0 +1,125 @@ +// ====================================================================== +// \title EnumToStringTest.cpp +// \author T. Chieu +// \brief cpp file for EnumToStringTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/enum/ImplicitEnumAc.hpp" +#include "FppTest/enum/ExplicitEnumAc.hpp" +#include "FppTest/enum/DefaultEnumAc.hpp" +#include "FppTest/enum/IntervalEnumAc.hpp" +#include "FppTest/enum/SerializeTypeU8EnumAc.hpp" +#include "FppTest/enum/SerializeTypeU64EnumAc.hpp" + +#include "gtest/gtest.h" + +#include +#include + +namespace FppTest { + + // Populate an array with enum values + template + void setEnumValArray(typename EnumType::T (&a)[EnumType::NUM_CONSTANTS+1]) { + for (U32 i = 0; i < EnumType::NUM_CONSTANTS + 1; i++) { + a[i] = static_cast(i); + } + } + + template<> + void setEnumValArray(Explicit::T (&a)[Explicit::NUM_CONSTANTS+1]) { + a[0] = Explicit::A; + a[1] = Explicit::B; + a[2] = Explicit::C; + a[3] = static_cast(11); + } + + template<> + void setEnumValArray(Interval::T (&a)[Interval::NUM_CONSTANTS+1]) { + a[0] = Interval::A; + a[1] = Interval::B; + a[2] = Interval::C; + a[3] = Interval::D; + a[4] = Interval::E; + a[5] = Interval::F; + a[6] = Interval::G; + a[7] = static_cast(11); + } + + // Populate an array with strings representing enum values + template + void setEnumStrArray(std::string (&a)[EnumType::NUM_CONSTANTS+1]) { + a[0] = "A (0)"; + a[1] = "B (1)"; + a[2] = "C (2)"; + a[3] = "D (3)"; + a[4] = "E (4)"; + a[5] = "[invalid] (5)"; + } + + template<> + void setEnumStrArray(std::string (&a)[Explicit::NUM_CONSTANTS+1]) { + a[0] = "A (-1952875139)"; + a[1] = "B (2)"; + a[2] = "C (2000999333)"; + a[3] = "[invalid] (11)"; + } + + template <> + void setEnumStrArray(std::string (&a)[Interval::NUM_CONSTANTS+1]) { + a[0] = "A (0)"; + a[1] = "B (3)"; + a[2] = "C (4)"; + a[3] = "D (5)"; + a[4] = "E (10)"; + a[5] = "F (100)"; + a[6] = "G (101)"; + a[7] = "[invalid] (11)"; + } + +} // namespace FppTest + +// Test enum string functions +template +class EnumToStringTest : public ::testing::Test { +protected: + void SetUp() override { + FppTest::setEnumValArray(vals); + FppTest::setEnumStrArray(strs); + }; + + EnumType e; + std::stringstream buf; + + typename EnumType::T vals[EnumType::NUM_CONSTANTS+1]; + std::string strs[EnumType::NUM_CONSTANTS+1]; +}; + +// Specify type parameters for this test suite +using EnumTypes = ::testing::Types< + Implicit, + Explicit, + Default, + Interval, + SerializeTypeU8, + SerializeTypeU64 +>; +TYPED_TEST_SUITE(EnumToStringTest, EnumTypes); + +// Test enum toString() and ostream operator functions +TYPED_TEST(EnumToStringTest, ToString) { + for (U32 i = 0; i < TypeParam::NUM_CONSTANTS + 1; i++) { + this->e = this->vals[i]; + this->buf << this->e; + + ASSERT_STREQ(this->buf.str().c_str(), this->strs[i].c_str()); + + this->buf.str(""); + } +} diff --git a/FppTest/enum/IsValidTest.cpp b/FppTest/enum/IsValidTest.cpp new file mode 100644 index 0000000000..8c1d02d9cd --- /dev/null +++ b/FppTest/enum/IsValidTest.cpp @@ -0,0 +1,54 @@ +// ====================================================================== +// \title IsValidTest.cpp +// \author T. Chieu +// \brief cpp file for IsValidTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/enum/IntervalEnumAc.hpp" + +#include "gtest/gtest.h" + +// Test boundary values for enum isValid() function +TEST(IsValidTest, IntervalEnum) { + Interval e = static_cast(-1); + ASSERT_FALSE(e.isValid()); + + e = static_cast(0); + ASSERT_TRUE(e.isValid()); + + e = static_cast(1); + ASSERT_FALSE(e.isValid()); + + e = static_cast(2); + ASSERT_FALSE(e.isValid()); + + e = static_cast(3); + ASSERT_TRUE(e.isValid()); + + e = static_cast(5); + ASSERT_TRUE(e.isValid()); + + e = static_cast(6); + ASSERT_FALSE(e.isValid()); + + e = static_cast(10); + ASSERT_TRUE(e.isValid()); + + e = static_cast(99); + ASSERT_FALSE(e.isValid()); + + e = static_cast(100); + ASSERT_TRUE(e.isValid()); + + e = static_cast(101); + ASSERT_TRUE(e.isValid()); + + e = static_cast(102); + ASSERT_FALSE(e.isValid()); +} diff --git a/FppTest/enum/README.md b/FppTest/enum/README.md new file mode 100644 index 0000000000..f984de13d9 --- /dev/null +++ b/FppTest/enum/README.md @@ -0,0 +1,12 @@ +# FppTest/enum + +This directory contains unit tests for the FPP enum code generator. + +* EnumToStringTest: Tests enum toString() and ostream operator functions +* IsValidTest: Additional tests for isValid() function with boundary values + +To use this directory, you must have installed F Prime, and you must be inside +the F Prime Python virtual environment. + +* To build the tests, run `fprime-util build --ut`. +* To run the tests, run `fprime-util check`. diff --git a/FppTest/enum/default.fpp b/FppTest/enum/default.fpp new file mode 100644 index 0000000000..d06a22fc22 --- /dev/null +++ b/FppTest/enum/default.fpp @@ -0,0 +1,8 @@ +@ An enum with specified default values +enum Default { + A, + B, + C, + D, + E, +} default C diff --git a/FppTest/enum/explicit.fpp b/FppTest/enum/explicit.fpp new file mode 100644 index 0000000000..0e3746477c --- /dev/null +++ b/FppTest/enum/explicit.fpp @@ -0,0 +1,6 @@ +@ An enum with explicit constant values +enum Explicit { + A = -1952875139, + B = 2, + C = 2000999333, +} diff --git a/FppTest/enum/implicit.fpp b/FppTest/enum/implicit.fpp new file mode 100644 index 0000000000..617e4ec1f1 --- /dev/null +++ b/FppTest/enum/implicit.fpp @@ -0,0 +1,8 @@ +@ An enum with implicit constant values +enum Implicit { + A, @< Member A + B, + C, + D, + E, +} diff --git a/FppTest/enum/interval.fpp b/FppTest/enum/interval.fpp new file mode 100644 index 0000000000..09e73091e6 --- /dev/null +++ b/FppTest/enum/interval.fpp @@ -0,0 +1,10 @@ +@ An enum with many intervals of values +enum Interval { + A = 0, + B = 3, + C = 4, + D = 5, + E = 10, + F = 100, + G = 101, +} diff --git a/FppTest/enum/main.cpp b/FppTest/enum/main.cpp new file mode 100644 index 0000000000..120335db4f --- /dev/null +++ b/FppTest/enum/main.cpp @@ -0,0 +1,108 @@ +// ====================================================================== +// \title main.cpp +// \author T. Chieu +// \brief main cpp file for FPP enum tests +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/enum/ImplicitEnumAc.hpp" +#include "FppTest/enum/ExplicitEnumAc.hpp" +#include "FppTest/enum/DefaultEnumAc.hpp" +#include "FppTest/enum/IntervalEnumAc.hpp" +#include "FppTest/enum/SerializeTypeU8EnumAc.hpp" +#include "FppTest/enum/SerializeTypeU64EnumAc.hpp" + +#include "FppTest/typed_tests/EnumTest.hpp" + +#include "STest/Random/Random.hpp" +#include "gtest/gtest.h" + +// Instantiate enum tests +using EnumTestImplementations = ::testing::Types< + Implicit, + Explicit, + Default, + Interval, + SerializeTypeU8, + SerializeTypeU64 +>; +INSTANTIATE_TYPED_TEST_SUITE_P(FppTest, + EnumTest, + EnumTestImplementations); + +// Specializations for default value +template<> +Explicit::T FppTest::Enum::getDefaultValue() { + return Explicit::A; +} + +template<> +Default::T FppTest::Enum::getDefaultValue() { + return Default::C; +} + +// Specializations for valid value +template<> +Explicit::T FppTest::Enum::getValidValue() { + U32 val = STest::Pick::startLength(0, Explicit::NUM_CONSTANTS - 1); + + switch (val) { + case 0: return Explicit::A; + case 1: return Explicit::B; + default: return Explicit::C; + } +} + +template<> +Interval::T FppTest::Enum::getValidValue() { + U32 val = STest::Pick::startLength(0, Interval::NUM_CONSTANTS - 1); + + switch (val) { + case 0: return Interval::A; + case 1: return Interval::B; + case 2: return Interval::C; + case 3: return Interval::D; + case 4: return Interval::E; + case 5: return Interval::F; + default: return Interval::G; + } +} + +// Specializations for invalid value +template <> +Explicit::T FppTest::Enum::getInvalidValue() { + U32 sign = STest::Pick::lowerUpper(0, 1); + + switch (sign) { + case 0: + return static_cast(STest::Pick::lowerUpper( + Explicit::C + 1, + std::numeric_limits::max() + )); + default: + return static_cast(STest::Pick::lowerUpper( + (Explicit::A - 1) * (-1), + std::numeric_limits::max() + ) * (-1)); + } +} + +template<> +Interval::T FppTest::Enum::getInvalidValue() { + return static_cast(STest::Pick::lowerUpper( + Interval::G + 1, + std::numeric_limits::max() + )); +} + +int main(int argc, char* argv[]) { + ::testing::InitGoogleTest(&argc, argv); + STest::Random::seed(); + + return RUN_ALL_TESTS(); +} diff --git a/FppTest/enum/serialize_type.fpp b/FppTest/enum/serialize_type.fpp new file mode 100644 index 0000000000..af8e3d370f --- /dev/null +++ b/FppTest/enum/serialize_type.fpp @@ -0,0 +1,16 @@ +@ An enum with a specified serialize type +enum SerializeTypeU8 : U8 { + A, + B, + C, + D, + E, +} + +enum SerializeTypeU64 : U64 { + A, + B, + C, + D, + E, +} diff --git a/FppTest/source.cpp b/FppTest/source.cpp new file mode 100644 index 0000000000..20844df592 --- /dev/null +++ b/FppTest/source.cpp @@ -0,0 +1 @@ +// Empty source file so that SOURCES for target FppTest is not empty diff --git a/FppTest/struct/CMakeLists.txt b/FppTest/struct/CMakeLists.txt new file mode 100644 index 0000000000..8602f311ea --- /dev/null +++ b/FppTest/struct/CMakeLists.txt @@ -0,0 +1,25 @@ +# ====================================================================== +# CMakeLists.txt +# ====================================================================== + +# We need to declare the XML source files this way to invoke the autocoder. +# However, only the UT build is allowed here. +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/struct.fpp" +) +register_fprime_module() + +# Declare dependencies on test modules +set(UT_MOD_DEPS + Fw/Test + STest +) + +# List all .cpp files as UT_SOURCE_FILES. Only the UT build is allowed. +set(UT_SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/PrimitiveStructTest.cpp" + "${CMAKE_CURRENT_LIST_DIR}/NonPrimitiveStructTest.cpp" + "${CMAKE_CURRENT_LIST_DIR}/../utils/Utils.cpp" + "${CMAKE_CURRENT_LIST_DIR}/main.cpp" +) +register_fprime_ut() diff --git a/FppTest/struct/NonPrimitiveStructTest.cpp b/FppTest/struct/NonPrimitiveStructTest.cpp new file mode 100644 index 0000000000..508126b4f1 --- /dev/null +++ b/FppTest/struct/NonPrimitiveStructTest.cpp @@ -0,0 +1,332 @@ +// ====================================================================== +// \title NonPrimitiveStructTest.cpp +// \author T. Chieu +// \brief cpp file for NonPrimitiveStructTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/struct/NonPrimitiveSerializableAc.hpp" +#include "FppTest/utils/Utils.hpp" + +#include "Fw/Types/SerialBuffer.hpp" +#include "Fw/Types/StringUtils.hpp" +#include "STest/Pick/Pick.hpp" + +#include "gtest/gtest.h" + +#include + +// Test NonPrimitive struct class +class NonPrimitiveStructTest : public ::testing::Test { +protected: + void SetUp() override { + char buf[testString.getCapacity()]; + FppTest::Utils::setString(buf, sizeof(buf)); + testString = buf; + + testEnum = static_cast(STest::Pick::startLength( + StructEnum::A, + StructEnum::B + )); + + for (U32 i = 0; i < StructArray::SIZE; i++) { + testArray[i] = FppTest::Utils::getU32(); + } + + testStruct.set( + true, + FppTest::Utils::getU32(), + static_cast(FppTest::Utils::getU32()), + static_cast(FppTest::Utils::getU32()) + ); + + for (U32 i = 0; i < 3; i++) { + testU32Arr[0] = FppTest::Utils::getU32(); + } + + for (U32 i = 0; i < 3; i++) { + testStructArr[i].set( + true, + FppTest::Utils::getU32(), + static_cast(FppTest::Utils::getU32()), + static_cast(FppTest::Utils::getU32()) + ); + } + } + + void assertStructMembers(const NonPrimitive& s) { + ASSERT_EQ(s.getmString(), testString); + ASSERT_EQ(s.getmEnum(), testEnum); + ASSERT_EQ(s.getmArray(), testArray); + ASSERT_EQ(s.getmStruct(), testStruct); + + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s.getmU32Arr()[i], testU32Arr[i]); + } + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s.getmStructArr()[i], testStructArr[i]); + } + } + + void assertUnsuccessfulSerialization(NonPrimitive& s, U32 bufSize) { + U8 data[bufSize]; + Fw::SerialBuffer buf(data, sizeof(data)); + Fw::SerializeStatus status; + + // Serialize + status = buf.serialize(s); + ASSERT_NE(status, Fw::FW_SERIALIZE_OK); + + // Deserialize + status = buf.deserialize(s); + ASSERT_NE(status, Fw::FW_SERIALIZE_OK); + } + + NonPrimitive::StringSize80 testString; + StructEnum testEnum; + StructArray testArray; + Primitive testStruct; + U32 testU32Arr[3]; + Primitive testStructArr[3]; +}; + +// Test struct constants and default constructor +TEST_F(NonPrimitiveStructTest, Default) { + NonPrimitive s; + + StructArray defaultArray; + Primitive defaultStruct1(true, 0, 0, 3.14); + Primitive defaultStruct2(true, 0, 0, 1.16); + + // Constants + ASSERT_EQ( + NonPrimitive::SERIALIZED_SIZE, + NonPrimitive::StringSize80::SERIALIZED_SIZE + + StructEnum::SERIALIZED_SIZE + + StructArray::SERIALIZED_SIZE + + Primitive::SERIALIZED_SIZE + + (3 * sizeof(U32)) + + (3 * Primitive::SERIALIZED_SIZE) + ); + + // Default constructor + ASSERT_EQ(s.getmString(), ""); + ASSERT_EQ(s.getmEnum(), StructEnum::C); + ASSERT_EQ(s.getmArray(), defaultArray); + ASSERT_EQ(s.getmStruct(), defaultStruct1); + + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s.getmU32Arr()[i], 0); + } + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s.getmStructArr()[i], defaultStruct2); + } +} + +// Test struct constructors +TEST_F(NonPrimitiveStructTest, Constructors) { + // Member constructor + NonPrimitive s1(testString, testEnum, testArray, + testStruct, testU32Arr, testStructArr); + assertStructMembers(s1); + + // Scalar member constructor + NonPrimitive s2(testString, testEnum, testArray, + testStruct, testU32Arr[0], testStructArr[0]); + + ASSERT_EQ(s2.getmString(), testString); + ASSERT_EQ(s2.getmEnum(), testEnum); + ASSERT_EQ(s2.getmArray(), testArray); + ASSERT_EQ(s2.getmStruct(), testStruct); + + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s2.getmU32Arr()[i], testU32Arr[0]); + } + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s2.getmStructArr()[i], testStructArr[0]); + } + + // Copy constructor + NonPrimitive s3(s1); + assertStructMembers(s3); +} + +// Test struct assignment operator +TEST_F(NonPrimitiveStructTest, AssignmentOp) { + NonPrimitive s1; + NonPrimitive s2(testString, testEnum, testArray, + testStruct, testU32Arr, testStructArr); + + // Copy assignment + s1 = s2; + assertStructMembers(s1); + + NonPrimitive& s1Ref = s1; + s1 = s1Ref; + ASSERT_EQ(&s1, &s1Ref); +} + +// Test struct equality and inequality operators +TEST_F(NonPrimitiveStructTest, EqualityOp) { + NonPrimitive s1, s2; + + ASSERT_TRUE(s1 == s2); + ASSERT_FALSE(s1 != s2); + + s1.setmString(testString); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmString(testString); + s1.setmEnum(testEnum); + + ASSERT_NE(s1, s2); + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmEnum(testEnum); + s1.setmArray(testArray); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmArray(testArray); + s1.setmStruct(testStruct); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmStruct(testStruct); + s1.setmU32Arr(testU32Arr); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmU32Arr(testU32Arr); + s1.setmStructArr(testStructArr); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmStructArr(testStructArr); + + ASSERT_TRUE(s1 == s2); + ASSERT_FALSE(s1 != s2); +} + +// Test struct getter and setter functions +TEST_F(NonPrimitiveStructTest, GetterSetterFunctions) { + NonPrimitive s1, s2; + + // Set all members + s1.set(testString, testEnum, testArray, + testStruct, testU32Arr, testStructArr); + assertStructMembers(s1); + + // Set individual members + s2.setmString(testString); + ASSERT_EQ(s2.getmString(), testString); + + s2.setmEnum(testEnum); + ASSERT_EQ(s2.getmEnum(), testEnum); + + s2.setmArray(testArray); + ASSERT_EQ(s2.getmArray(), testArray); + + s2.setmStruct(testStruct); + ASSERT_EQ(s2.getmStruct(), testStruct); + + s2.setmU32Arr(testU32Arr); + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s2.getmU32Arr()[i], testU32Arr[i]); + } + + s2.setmStructArr(testStructArr); + for (U32 i = 0; i < 3; i++) { + ASSERT_EQ(s2.getmStructArr()[i], testStructArr[i]); + } + + // Check non-const getter + s2.getmStruct().setmU32(testU32Arr[0]); + ASSERT_EQ(s2.getmStruct().getmU32(), testU32Arr[0]); +} + +// Test struct serialization and deserialization +TEST_F(NonPrimitiveStructTest, Serialization) { + NonPrimitive s(testString, testEnum, testArray, + testStruct, testU32Arr, testStructArr); + NonPrimitive sCopy; + + U32 stringSerializedSize = testString.length() + sizeof(FwBuffSizeType); + U32 serializedSize = NonPrimitive::SERIALIZED_SIZE + - NonPrimitive::StringSize80::SERIALIZED_SIZE + + stringSerializedSize; + Fw::SerializeStatus status; + + // Test successful serialization + U8 data[NonPrimitive::SERIALIZED_SIZE]; + Fw::SerialBuffer buf(data, sizeof(data)); + + // Serialize + status = buf.serialize(s); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(buf.getBuffLength(), serializedSize); + + // Deserialize + status = buf.deserialize(sCopy); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(s, sCopy); + + // Test unsuccessful serialization + assertUnsuccessfulSerialization(s, stringSerializedSize - 1); + assertUnsuccessfulSerialization(s, stringSerializedSize + + StructEnum::SERIALIZED_SIZE - 1); + assertUnsuccessfulSerialization(s, stringSerializedSize + + StructEnum::SERIALIZED_SIZE + StructArray::SERIALIZED_SIZE - 1); + assertUnsuccessfulSerialization(s, stringSerializedSize + + StructEnum::SERIALIZED_SIZE + StructArray::SERIALIZED_SIZE + + Primitive::SERIALIZED_SIZE - 1); + assertUnsuccessfulSerialization(s, stringSerializedSize + + StructEnum::SERIALIZED_SIZE + StructArray::SERIALIZED_SIZE + + Primitive::SERIALIZED_SIZE + (3 * sizeof(U32)) - 1); + assertUnsuccessfulSerialization(s, serializedSize - 1); +} + +// Test struct toString() and ostream operator functions +TEST_F(NonPrimitiveStructTest, ToString) { + NonPrimitive s(testString, testEnum, testArray, + testStruct, testU32Arr, testStructArr); + std::stringstream buf1, buf2; + + buf1 << s; + + buf2 << "( " + << "mString = " << testString << ", " + << "mEnum = " << testEnum << ", " + << "mArray = " << testArray << ", " + << "mStruct = " << testStruct << ", " + << "mU32Arr = [ " + << testU32Arr[0] << ", " + << testU32Arr[1] << ", " + << testU32Arr[2] << " ], " + << "mStructArr = [ " + << testStructArr[0] << ", " + << testStructArr[1] << ", " + << testStructArr[2] << " ] " + << " )"; + + // Truncate string output + char buf2Str[FW_SERIALIZABLE_TO_STRING_BUFFER_SIZE]; + Fw::StringUtils::string_copy(buf2Str, buf2.str().c_str(), + FW_SERIALIZABLE_TO_STRING_BUFFER_SIZE); + + ASSERT_STREQ(buf1.str().c_str(), buf2Str); +} diff --git a/FppTest/struct/PrimitiveStructTest.cpp b/FppTest/struct/PrimitiveStructTest.cpp new file mode 100644 index 0000000000..c9e539b8e8 --- /dev/null +++ b/FppTest/struct/PrimitiveStructTest.cpp @@ -0,0 +1,215 @@ +// ====================================================================== +// \title PrimitiveStructTest.cpp +// \author T. Chieu +// \brief cpp file for PrimitiveStructTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/struct/PrimitiveSerializableAc.hpp" +#include "FppTest/utils/Utils.hpp" + +#include "Fw/Types/SerialBuffer.hpp" +#include "Fw/Types/StringUtils.hpp" +#include "STest/Pick/Pick.hpp" + +#include "gtest/gtest.h" + +#include + +// Test Primitive struct class +class PrimitiveStructTest : public ::testing::Test { +protected: + void SetUp() override { + testBool = true; + testU32 = FppTest::Utils::getU32(); + testI16 = static_cast(FppTest::Utils::getU32()); + testF64 = static_cast(FppTest::Utils::getU32()); + } + + void assertStructMembers(const Primitive& s) { + ASSERT_EQ(s.getmBool(), testBool); + ASSERT_EQ(s.getmU32(), testU32); + ASSERT_EQ(s.getmI16(), testI16); + ASSERT_EQ(s.getmF64(), testF64); + } + + void assertUnsuccessfulSerialization(Primitive& s, U32 bufSize) { + U8 data[bufSize]; + Fw::SerialBuffer buf(data, sizeof(data)); + Fw::SerializeStatus status; + + // Serialize + status = buf.serialize(s); + ASSERT_NE(status, Fw::FW_SERIALIZE_OK); + + // Deserialize + status = buf.deserialize(s); + ASSERT_NE(status, Fw::FW_SERIALIZE_OK); + } + + bool testBool; + U32 testU32; + I16 testI16; + F64 testF64; +}; + +// Test struct constants and default constructor +TEST_F(PrimitiveStructTest, Default) { + Primitive s; + + // Constants + ASSERT_EQ( + Primitive::SERIALIZED_SIZE, + sizeof(U8) + + sizeof(U32) + + sizeof(I16) + + sizeof(F64) + ); + + // Default constructor + ASSERT_EQ(s.getmBool(), false); + ASSERT_EQ(s.getmU32(), 0); + ASSERT_EQ(s.getmI16(), 0); + ASSERT_EQ(s.getmF64(), 0.0); +} + +// Test struct constructors +TEST_F(PrimitiveStructTest, Constructors) { + // Member constructor + Primitive s1(testBool, testU32, testI16, testF64); + assertStructMembers(s1); + + // Copy constructor + Primitive s2(s1); + assertStructMembers(s2); +} + +// Test struct assignment operator +TEST_F(PrimitiveStructTest, AssignmentOp) { + Primitive s1; + Primitive s2(testBool, testU32, testI16, testF64); + + // Copy assignment + s1 = s2; + assertStructMembers(s1); + + Primitive& s1Ref = s1; + s1 = s1Ref; + ASSERT_EQ(&s1, &s1Ref); +} + +// Test struct equality and inequality operators +TEST_F(PrimitiveStructTest, EqualityOp) { + Primitive s1, s2; + + ASSERT_TRUE(s1 == s2); + ASSERT_FALSE(s1 != s2); + + s1.setmBool(testBool); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmBool(testBool); + s1.setmU32(testU32); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmU32(testU32); + s1.setmI16(testI16); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmI16(testI16); + s1.setmF64(testF64); + + ASSERT_FALSE(s1 == s2); + ASSERT_TRUE(s1 != s2); + + s2.setmF64(testF64); + + ASSERT_TRUE(s1 == s2); + ASSERT_FALSE(s1 != s2); +} + +// Test struct getter and setter functions +TEST_F(PrimitiveStructTest, GetterSetterFunctions) { + Primitive s1, s2; + + // Set all members + s1.set(testBool, testU32, testI16, testF64); + assertStructMembers(s1); + + // Set individual members + s2.setmBool(testBool); + ASSERT_EQ(s2.getmBool(), testBool); + + s2.setmU32(testU32); + ASSERT_EQ(s2.getmU32(), testU32); + + s2.setmI16(testI16); + ASSERT_EQ(s2.getmI16(), testI16); + + s2.setmF64(testF64); + ASSERT_EQ(s2.getmF64(), testF64); +} + +// Test struct serialization and deserialization +TEST_F(PrimitiveStructTest, Serialization) { + Primitive s(testBool, testU32, testI16, testF64); + Primitive sCopy; + + Fw::SerializeStatus status; + + // Test successful serialization + U8 data[Primitive::SERIALIZED_SIZE]; + Fw::SerialBuffer buf(data, sizeof(data)); + + // Serialize + status = buf.serialize(s); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(buf.getBuffLength(), Primitive::SERIALIZED_SIZE); + + // Deserialize + status = buf.deserialize(sCopy); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(s, sCopy); + + // Test unsuccessful serialization + assertUnsuccessfulSerialization(s, sizeof(U8) - 1); + assertUnsuccessfulSerialization(s, sizeof(U8) + sizeof(U32) - 1); + assertUnsuccessfulSerialization(s, sizeof(U8) + sizeof(U32) + + sizeof(I16) - 1); + assertUnsuccessfulSerialization(s, Primitive::SERIALIZED_SIZE - 1); +} + +// Test struct toString() and ostream operator functions +TEST_F(PrimitiveStructTest, ToString) { + Primitive s(testBool, testU32, testI16, testF64); + std::stringstream buf1, buf2; + + buf1 << s; + + buf2 << "( " + << "mBool = " << testBool << ", " + << "mU32 = " << testU32 << ", " + << "mI16 = " << testI16 << ", " + << "mF64 = " << std::fixed << testF64 + << " )"; + + // Truncate string output + char buf2Str[FW_SERIALIZABLE_TO_STRING_BUFFER_SIZE]; + Fw::StringUtils::string_copy(buf2Str, buf2.str().c_str(), + FW_SERIALIZABLE_TO_STRING_BUFFER_SIZE); + + ASSERT_STREQ(buf1.str().c_str(), buf2Str); +} diff --git a/FppTest/struct/README.md b/FppTest/struct/README.md new file mode 100644 index 0000000000..42d4ca4bb9 --- /dev/null +++ b/FppTest/struct/README.md @@ -0,0 +1,9 @@ +# FppTest/struct + +This directory contains unit tests for the FPP struct code generator. + +To use this directory, you must have installed F Prime, and you must be inside +the F Prime Python virtual environment. + +* To build the tests, run `fprime-util build --ut`. +* To run the tests, run `fprime-util check`. diff --git a/FppTest/struct/main.cpp b/FppTest/struct/main.cpp new file mode 100644 index 0000000000..60a72d7d63 --- /dev/null +++ b/FppTest/struct/main.cpp @@ -0,0 +1,44 @@ +// ====================================================================== +// \title main.cpp +// \author T. Chieu +// \brief main cpp file for FPP struct tests +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "FppTest/struct/NonPrimitiveSerializableAc.hpp" +#include "FppTest/struct/MultiStringSerializableAc.hpp" +#include "FppTest/typed_tests/StringTest.hpp" + +#include "STest/Random/Random.hpp" +#include "gtest/gtest.h" + +// Instantiate string tests for structs +using StringTestImplementations = ::testing::Types< + NonPrimitive::StringSize80, + MultiString::StringSize50, + MultiString::StringSize60, + MultiString::StringSize80 +>; +INSTANTIATE_TYPED_TEST_SUITE_P(Struct, StringTest, StringTestImplementations); + +template<> +U32 FppTest::String::getSize() { + return 50; +} + +template<> +U32 FppTest::String::getSize() { + return 60; +} + +int main(int argc, char* argv[]) { + ::testing::InitGoogleTest(&argc, argv); + STest::Random::seed(); + + return RUN_ALL_TESTS(); +} diff --git a/FppTest/struct/struct.fpp b/FppTest/struct/struct.fpp new file mode 100644 index 0000000000..e64d927777 --- /dev/null +++ b/FppTest/struct/struct.fpp @@ -0,0 +1,31 @@ +enum StructEnum { A, B, C } +array StructArray = [3] U32 + +struct Primitive { + mBool: bool + mU32: U32 + mI16: I16 + mF64: F64 +} + +struct NonPrimitive { + mString: string + mEnum: StructEnum + mArray: StructArray + mStruct: Primitive + mU32Arr: [3] U32 + mStructArr: [3] Primitive +} default { + mEnum = StructEnum.C + mStruct = { mBool = true, mF64 = 3.14 } + mStructArr = { mBool = true, mF64 = 1.16 } +} + +struct MultiString { + mStr_1: string + mStr_2: string + mStr50_1: string size 50 + mStr50_2: string size 50 + mStrArr_1: [3] string size 60 + mStrArr_2: [3] string size 60 +} diff --git a/FppTest/typed_tests/ArrayTest.hpp b/FppTest/typed_tests/ArrayTest.hpp new file mode 100644 index 0000000000..12cea993ad --- /dev/null +++ b/FppTest/typed_tests/ArrayTest.hpp @@ -0,0 +1,237 @@ +// ====================================================================== +// \title ArrayTest.hpp +// \author T. Chieu +// \brief hpp file for ArrayTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef FPP_TEST_ARRAY_TEST_HPP +#define FPP_TEST_ARRAY_TEST_HPP + +#include "Fw/Types/SerialBuffer.hpp" + +#include "STest/Pick/Pick.hpp" +#include "gtest/gtest.h" + +#include + +namespace FppTest { + + namespace Array { + + // Set default values for an array type + template + void setDefaultVals + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]) {} + + // Set test values for an array type + template + void setTestVals + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]); + + template + ArrayType getMultiElementConstructedArray + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]); + + // Get the serialized size of an array + template + U32 getSerializedSize + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]) { + return ArrayType::SERIALIZED_SIZE; + } + + } // namespace Array + +} // namespace FppTest + +// Test an array class +template +class ArrayTest : public ::testing::Test { +protected: + void SetUp() override { + FppTest::Array::setDefaultVals(defaultVals); + + FppTest::Array::setTestVals(testVals); + ASSERT_FALSE(valsAreEqual()); + }; + + bool valsAreEqual() { + for (U32 i = 0; i < ArrayType::SIZE; i++) { + if (defaultVals[i] != testVals[i]) { + return false; + } + } + + return true; + } + + typename ArrayType::ElementType defaultVals[ArrayType::SIZE]; + typename ArrayType::ElementType testVals[ArrayType::SIZE]; +}; + +TYPED_TEST_SUITE_P(ArrayTest); + +// Test array constants and default constructor +TYPED_TEST_P(ArrayTest, Default) { + TypeParam a; + + // Constants + ASSERT_EQ(TypeParam::SIZE, 3); + ASSERT_EQ( + TypeParam::SERIALIZED_SIZE, + TypeParam::SIZE * TypeParam::ElementType::SERIALIZED_SIZE + ); + + // Default constructor + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a[i], this->defaultVals[i]); + } +} + +// Test array constructors +TYPED_TEST_P(ArrayTest, Constructors) { + // Array constructor + TypeParam a1(this->testVals); + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a1[i], this->testVals[i]); + } + + // Single element constructor + TypeParam a2(this->testVals[0]); + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a2[i], this->testVals[0]); + } + + // Multiple element constructor + TypeParam a3 = FppTest::Array::getMultiElementConstructedArray + (this->testVals); + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a3[i], this->testVals[i]); + } + + // Copy constructor + TypeParam a4(a1); + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a4[i], a1[i]); + } +} + +// Test array subscript operator +TYPED_TEST_P(ArrayTest, SubscriptOp) { + TypeParam a; + + for (U32 i = 0; i < TypeParam::SIZE; i++) { + a[i] = this->testVals[0]; + ASSERT_EQ(a[i], this->testVals[0]); + } +} + +// Test array assignment operator +TYPED_TEST_P(ArrayTest, AssignmentOp) { + TypeParam a1, a2; + + // Array assignment + a1 = this->testVals; + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a1[i], this->testVals[i]); + } + + // Copy assignment + TypeParam& a1Ref = a1; + a1 = a1Ref; + ASSERT_EQ(&a1, &a1Ref); + + a1 = a2; + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a2[i], a1[i]); + } + + // Single element assignment + a1 = this->testVals[0]; + for (U32 i = 0; i < TypeParam::SIZE; i++) { + ASSERT_EQ(a1[i], this->testVals[0]); + } +} + +// Test array equality and inequality operators +TYPED_TEST_P(ArrayTest, EqualityOp) { + TypeParam a1, a2; + + ASSERT_TRUE(a1 == a2); + ASSERT_FALSE(a1 != a2); + + a2 = this->testVals; + + ASSERT_FALSE(a1 == a2); + ASSERT_TRUE(a1 != a2); + + a1 = a2; + + ASSERT_TRUE(a1 == a2); + ASSERT_FALSE(a1 != a2); +} + +// Test array serialization and deserialization +TYPED_TEST_P(ArrayTest, Serialization) { + TypeParam a(this->testVals); + + U32 serializedSize = + FppTest::Array::getSerializedSize(this->testVals); + Fw::SerializeStatus status; + + // Test successful serialization + TypeParam aCopy; + U8 data[TypeParam::SERIALIZED_SIZE]; + Fw::SerialBuffer buf(data, sizeof(data)); + + // Serialize + status = buf.serialize(a); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ( + buf.getBuffLength(), + serializedSize + ); + + // Deserialize + status = buf.deserialize(aCopy); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(a, aCopy); + + // Test unsuccessful serialization + TypeParam aCopy2; + U8 data2[serializedSize-1]; + Fw::SerialBuffer buf2(data2, sizeof(data2)); + + // Serialize + status = buf2.serialize(a); + + ASSERT_NE(status, Fw::FW_SERIALIZE_OK); + ASSERT_NE( + buf2.getBuffLength(), + serializedSize + ); + + // Deserialize + status = buf2.deserialize(aCopy2); + + ASSERT_NE(status, Fw::FW_SERIALIZE_OK); +} + +// Register all test patterns +REGISTER_TYPED_TEST_SUITE_P(ArrayTest, + Default, + Constructors, + SubscriptOp, + AssignmentOp, + EqualityOp, + Serialization +); + +#endif diff --git a/FppTest/typed_tests/EnumTest.hpp b/FppTest/typed_tests/EnumTest.hpp new file mode 100644 index 0000000000..1e6b4407b6 --- /dev/null +++ b/FppTest/typed_tests/EnumTest.hpp @@ -0,0 +1,210 @@ +// ====================================================================== +// \title EnumTest.hpp +// \author T. Chieu +// \brief hpp file for EnumTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef FPP_TEST_ENUM_TEST_HPP +#define FPP_TEST_ENUM_TEST_HPP + +#include "Fw/Types/SerialBuffer.hpp" + +#include "STest/Pick/Pick.hpp" +#include "gtest/gtest.h" + +#include + +namespace FppTest { + + namespace Enum { + + // Get the default value of an enum + template + typename EnumType::T getDefaultValue() { + return static_cast(0); + } + + // Get a valid value of an enum + template + typename EnumType::T getValidValue() { + U32 val = STest::Pick::startLength( + 0, + static_cast(EnumType::NUM_CONSTANTS - 1) + ); + + return static_cast(val); + } + + // Get an invalid value of an enum + template + typename EnumType::T getInvalidValue() { + U8 sign = 0; + if (std::numeric_limits::min() < 0) { + sign = STest::Pick::lowerUpper(0, 1); + } + + switch (sign) { + case 0: + return static_cast(STest::Pick::lowerUpper( + EnumType::NUM_CONSTANTS, + static_cast( + std::numeric_limits::max() + ) + )); + default: + return static_cast(STest::Pick::lowerUpper( + 1, + static_cast((-1) * + (std::numeric_limits::min() + 1) + ) + ) * (-1)); + } + } + + } // namespace Enum + +} // namespace FppTest + +// Test core enum interface +template +class EnumTest : public ::testing::Test {}; + +TYPED_TEST_SUITE_P(EnumTest); + +// Test enum constants and default construction +TYPED_TEST_P(EnumTest, Default) { + TypeParam e; + + // Constants + ASSERT_EQ( + TypeParam::SERIALIZED_SIZE, + sizeof(typename TypeParam::SerialType) + ); + + // Default constructor + ASSERT_EQ(e.e, FppTest::Enum::getDefaultValue()); +} + +// Test enum constructors +TYPED_TEST_P(EnumTest, Constructors) { + typename TypeParam::T validVal = FppTest::Enum::getValidValue(); + + // Raw enum value constructor + TypeParam e1(validVal); + ASSERT_EQ(e1.e, validVal); + + // Copy constructor + TypeParam e2(e1); + ASSERT_EQ(e2.e, validVal); +} + +// Test enum assignment operator +TYPED_TEST_P(EnumTest, AssignmentOp) { + TypeParam e1; + TypeParam e2; + + typename TypeParam::T validVal = FppTest::Enum::getValidValue(); + + // Raw enum value assignment + e1 = validVal; + ASSERT_EQ(e1.e, validVal); + + // Object assignment + e2 = e1; + ASSERT_EQ(e2.e, validVal); +} + +// Test enum equality and inequality operator +TYPED_TEST_P(EnumTest, EqualityOp) { + // Initialize two distinct valid values + typename TypeParam::T validVal1 = FppTest::Enum::getValidValue(); + typename TypeParam::T validVal2 = FppTest::Enum::getValidValue(); + while (validVal1 == validVal2) { + validVal2 = FppTest::Enum::getValidValue(); + } + + TypeParam e1; + TypeParam e2; + TypeParam e3(validVal1); + TypeParam e4(validVal2); + + // operator== + ASSERT_TRUE(e3 == validVal1); + ASSERT_TRUE(e4 == validVal2); + ASSERT_FALSE(e3 == validVal2); + ASSERT_FALSE(e4 == validVal1); + + ASSERT_TRUE(e1 == e2); + ASSERT_FALSE(e3 == e4); + + // operator!= + ASSERT_TRUE(e3 != validVal2); + ASSERT_TRUE(e4 != validVal1); + ASSERT_FALSE(e3 != validVal1); + ASSERT_FALSE(e4 != validVal2); + + ASSERT_TRUE(e3 != e4); + ASSERT_FALSE(e1 != e2); +} + +// Test enum isValid() function +TYPED_TEST_P(EnumTest, IsValidFunction) { + TypeParam validEnum = FppTest::Enum::getValidValue(); + TypeParam invalidEnum = FppTest::Enum::getInvalidValue(); + + ASSERT_TRUE(validEnum.isValid()); + ASSERT_FALSE(invalidEnum.isValid()); +} + +// Test enum serialization and deserialization +TYPED_TEST_P(EnumTest, Serialization) { + TypeParam validEnum = FppTest::Enum::getValidValue(); + TypeParam invalidEnum = FppTest::Enum::getInvalidValue(); + + // Copy of enums to test after serialization + TypeParam validEnumCopy; + TypeParam invalidEnumCopy; + + Fw::SerializeStatus status; + U8 data[TypeParam::SERIALIZED_SIZE * 2]; + Fw::SerialBuffer buf(data, sizeof(data)); + + // Serialize the enums + status = buf.serialize(validEnum); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(buf.getBuffLength(), sizeof(typename TypeParam::SerialType)); + + status = buf.serialize(invalidEnum); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(buf.getBuffLength(), sizeof(typename TypeParam::SerialType) * 2); + + // Deserialize the enums + status = buf.deserialize(validEnumCopy); + + ASSERT_EQ(status, Fw::FW_SERIALIZE_OK); + ASSERT_EQ(validEnumCopy, validEnum); + + status = buf.deserialize(invalidEnumCopy); + + ASSERT_EQ(status, Fw::FW_DESERIALIZE_FORMAT_ERROR); +} + +// Register all test patterns +REGISTER_TYPED_TEST_SUITE_P(EnumTest, + Default, + Constructors, + AssignmentOp, + EqualityOp, + IsValidFunction, + Serialization +); + +#endif diff --git a/FppTest/typed_tests/README.md b/FppTest/typed_tests/README.md new file mode 100644 index 0000000000..cd8f14b075 --- /dev/null +++ b/FppTest/typed_tests/README.md @@ -0,0 +1,175 @@ +# FppTest/typed_tests + +This directory contains the following type-parametrized test suites for +C++ code generated by the FPP autocoder. + +* `EnumTest`: Tests an enum class +* `ArrayTest`: Tests an array class +* `StringTest`: Tests a nested string class within an array of struct class + +## Instantiating a Test Suite + +To use a type-parametrized test suite, instantiate it with a list of types: + +```c++ +#include "FppTest/typed_tests/TestSuite.hpp" + +using TestTypes = ::testing::Types< + Type1, + Type2, + Type3 +>; +INSTANTIATE_TYPED_TEST_SUITE_P(InstanceName, + TestSuite, + TestTypes); +``` + +## Implementing Specializations + +In addition to instantiating the test suite, you may also need to implement some +explicit specializations for template functions if the behavior of your class +differs from the provided default implementation. + +### `EnumTest` Suite + +- `getDefaultValue()`: Returns the default value of an enum type. The default +implementation returns 0. + + ```c++ + // Function signature + template + typename EnumType::T FppTest::Enum::getDefaultValue(); + ``` + +- `getValidValue()`: Returns a random valid enum value. The default implementation +assumes the values of the enum have been implicitly defined, i.e. it returns +a value in the interval `[0, EnumType::NUM_CONSTANTS-1]`. + + ```c++ + // Function signature + template + typename EnumType::T FppTest::Enum::getValidValue(); + ``` + +- `getInvalidValue()`: Returns an random invalid enum value. The default +implementation assumes the values of the enum have been implicitly defined, +i.e. it returns a value either in the interval `[min, -1]` (if the serial +representation type is signed) or in the interval +`[EnumType::NUM_CONSTANTS, max]`, where `min` and `max` are the minimum +and maximum values of the serial representation type, respectively. + + ```c++ + // Function signature + template + typename EnumType::T FppTest::Enum::getInvalidValue(); + ``` + +### `ArrayTest` Suite + +The following functions MUST be implemented for your array type! + +- `setTestVals()`: Sets test values for an array. There is no default +implementation, so this function must be implemented for your array type! +In addition, these test values must be different from the default values. + + ```c++ + // Function signature + template + void FppTest::Array::setTestVals + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]); + ``` + +- `getMultiElementConstructedArray()`: Returns an array constructed using its +multiple element constructor. There is no default implementation, so this +function must be implemented for your array type! + + ```c++ + // Function signature + template + ArrayType FppTest::Array::getMultiElementConstructedArray + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]); + ``` + +The following functions may or may not need to be implemented: + +- `setDefaultVals()`: Sets the default values for an array. The default +implementation is empty (i.e. the values are either zero-initialized or +default-initialized). + + ```c++ + // Function signature + template + void FppTest::Array::setDefaultVals + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]); + ``` + +- `getSerializedSize()`: Returns the serialized size of an array. The default +implementation returns the `SERIALIZED_SIZE` of the array type. In particular, +this function will need to be implemented for arrays containing string values. + + ```c++ + // Function signature + template + U32 FppTest::Array::getSerializedSize + (typename ArrayType::ElementType (&a)[ArrayType::SIZE]); + ``` + +### `StringTest` Suite + +- `getSize()`: Returns the size of a string type. The default implementation +returns the default string size of 80. + + ```c++ + // Function signature + template + U32 FppTest::String::getSize(); + ``` + +## Example + +For example, to use the `ArrayTest` suite with array types `U32Array`, an array +of three U32 values, and `F32Array`, an array of four F32 values: + +```c++ +#include "FppTest/typed_tests/ArrayTest.hpp" + +// Instantiate the test suite with a list of types +using ArrayTypes = ::testing::Types< + U32Array, + F32Array +>; +INSTANTIATE_TYPED_TEST_SUITE_P(ExampleInstance, + ArrayTest, + ArrayTypes); + +// Explicit specializations for setTestVals() +template <> +void FppTest::Array::setTestVals + (U32Array::ElementType (&a)[U32Array::SIZE]) { + for (U32 i = 0; i < U32Array::SIZE; i++) { + a[i] = i; + } +} + +template <> +void FppTest::Array::setTestVals + (F32Array::ElementType (&a)[F32Array::SIZE]) { + for (U32 i = 0; i < F32Array::SIZE; i++) { + a[i] = static_cast(i); + } +} + +// Explicit specializations for getMultiElementConstructedArray() +template<> +U32Array FppTest::Array::getMultiElementConstructedArray + (U32Array::ElementType (&a)[U32Array::SIZE]) { + return U32Array(a[0], a[1], a[2]); +} + +template<> +F32Array FppTest::Array::getMultiElementConstructedArray + (F32Array::ElementType (&a)[F32Array::SIZE]) { + return F32Array(a[0], a[1], a[2], a[3]); +} +``` + diff --git a/FppTest/typed_tests/StringTest.hpp b/FppTest/typed_tests/StringTest.hpp new file mode 100644 index 0000000000..ea2008cc46 --- /dev/null +++ b/FppTest/typed_tests/StringTest.hpp @@ -0,0 +1,131 @@ +// ====================================================================== +// \title StringTest.hpp +// \author T. Chieu +// \brief hpp file for StringTest class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef FPP_TEST_STRING_TEST_HPP +#define FPP_TEST_STRING_TEST_HPP + +#include "FppTest/utils/Utils.hpp" + +#include "Fw/Types/String.hpp" +#include "Fw/Types/StringUtils.hpp" + +#include "gtest/gtest.h" + +namespace FppTest { + + namespace String { + + // Get the size of a string type + template + U32 getSize() { + return 80; + } + + } // namespace String + +} // namespace FppTest + +// Test a nested string class +template +class StringTest : public ::testing::Test { +protected: + void SetUp() override { + size = FppTest::String::getSize(); + + FppTest::Utils::setString(src, size); + + char fwStrBuf1[Fw::String::STRING_SIZE]; + FppTest::Utils::setString(fwStrBuf1, sizeof(fwStrBuf1)); + fwStr = fwStrBuf1; + + // Truncate fwStr for comparison + char fwStrBuf2[size]; + Fw::StringUtils::string_copy(fwStrBuf2, fwStr.toChar(), size); + fwSubstr = fwStrBuf2; + } + + U32 size; + char src[StringType::SERIALIZED_SIZE]; + + Fw::String fwStr; + Fw::String fwSubstr; +}; + +TYPED_TEST_SUITE_P(StringTest); + +// Test string capacity and default constructor +TYPED_TEST_P(StringTest, Default) { + TypeParam str; + + // Capacity + ASSERT_EQ(str.getCapacity(), this->size); + + // Serialized size + ASSERT_EQ( + TypeParam::SERIALIZED_SIZE, + this->size + sizeof(FwBuffSizeType) + ); + + // Default constructors + ASSERT_STREQ(str.toChar(), ""); +} + +// Test string constructors +TYPED_TEST_P(StringTest, Constructors) { + // Char array constructor + TypeParam str1(this->src); + ASSERT_STREQ(str1.toChar(), this->src); + + // Copy constructor + TypeParam str2(str1); + ASSERT_STREQ(str2.toChar(), str1.toChar()); + + // Fw::StringBase constructor + TypeParam str3(this->fwStr); + ASSERT_STREQ(str3.toChar(), this->fwSubstr.toChar()); +} + +// Test string assignment operator +TYPED_TEST_P(StringTest, AssignmentOp) { + TypeParam str1; + TypeParam str2; + TypeParam str3; + + // Char array assignment + str1 = this->src; + ASSERT_STREQ(str1.toChar(), this->src); + + // Copy assignment + TypeParam& strRef = str1; + str1 = strRef; + ASSERT_EQ(&str1, &strRef); + + str2 = str1; + ASSERT_STREQ(str1.toChar(), str1.toChar()); + + // Fw::StringBase assignment + Fw::StringBase& sbRef = str1; + str1 = sbRef; + ASSERT_EQ(&str1, &sbRef); + + str3 = this->fwStr; + ASSERT_STREQ(str3.toChar(), this->fwSubstr.toChar()); +} + +// Register all test patterns +REGISTER_TYPED_TEST_SUITE_P(StringTest, + Default, + Constructors, + AssignmentOp +); + +#endif diff --git a/FppTest/utils/Utils.cpp b/FppTest/utils/Utils.cpp new file mode 100644 index 0000000000..64fdd0b6b8 --- /dev/null +++ b/FppTest/utils/Utils.cpp @@ -0,0 +1,58 @@ +// ====================================================================== +// \title Utils.cpp +// \author T. Chieu +// \brief cpp file for Utils class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#include "STest/Pick/Pick.hpp" + +#include +#include +#include + +namespace FppTest { + + namespace Utils { + + U8 getU8() { + return static_cast(STest::Pick::lowerUpper( + 1, + std::numeric_limits::max() + )); + } + + U32 getU32() { + return STest::Pick::lowerUpper( + 1, + std::numeric_limits::max() + ); + } + + char getChar() { + return static_cast(STest::Pick::lowerUpper(1, 127)); + } + + void setString(char* buf, U32 size) { + U32 length = STest::Pick::lowerUpper(1, size); + + if (length == 0) { + buf[0] = 0; + return; + } + + for (U32 i = 0; i < length - 1; i++) { + buf[i] = getChar(); + } + + buf[length-1] = 0; + } + + } // namespace Utils + +} // namespace FppTest diff --git a/FppTest/utils/Utils.hpp b/FppTest/utils/Utils.hpp new file mode 100644 index 0000000000..24308d49a5 --- /dev/null +++ b/FppTest/utils/Utils.hpp @@ -0,0 +1,36 @@ +// ====================================================================== +// \title Utils.hpp +// \author T. Chieu +// \brief hpp file for Utils class +// +// \copyright +// Copyright (C) 2009-2022 California Institute of Technology. +// ALL RIGHTS RESERVED. United States Government Sponsorship +// acknowledged. +// +// ====================================================================== + +#ifndef FPP_TEST_UTILS_HPP +#define FPP_TEST_UTILS_HPP + +namespace FppTest { + + namespace Utils { + + // Returns a random nonzero U8 + U8 getU8(); + + // Returns a random nonzero U32 + U32 getU32(); + + // Returns a random non-null char + char getChar(); + + // Populates buf with a random nonempty string of random length with max length size + void setString(char *buf, U32 size); + + } // namespace Utils + +} // namespace FppTest + +#endif diff --git a/Svc/ActiveLogger/ActiveLoggerImpl.cpp b/Svc/ActiveLogger/ActiveLoggerImpl.cpp index ce9a38b4f8..8bd9ad7711 100644 --- a/Svc/ActiveLogger/ActiveLoggerImpl.cpp +++ b/Svc/ActiveLogger/ActiveLoggerImpl.cpp @@ -127,13 +127,6 @@ namespace Svc { } void ActiveLoggerImpl::SET_EVENT_FILTER_cmdHandler(FwOpcodeType opCode, U32 cmdSeq, FilterSeverity filterLevel, Enabled filterEnable) { - if ( (filterLevel.e > FilterSeverity::DIAGNOSTIC) or - (filterLevel.e < FilterSeverity::WARNING_HI) or - (filterEnable.e < Enabled::ENABLED) or - (filterEnable.e > Enabled::DISABLED)) { - this->cmdResponse_out(opCode,cmdSeq,Fw::CmdResponse::VALIDATION_ERROR); - return; - } this->m_filterState[filterLevel.e].enabled = filterEnable; this->cmdResponse_out(opCode,cmdSeq,Fw::CmdResponse::OK); } @@ -145,16 +138,6 @@ namespace Svc { Enabled idEnabled //!< ID filter state ) { - // check parameter - switch (idEnabled.e) { - case Enabled::ENABLED: - case Enabled::DISABLED: - break; - default: - this->cmdResponse_out(opCode,cmdSeq,Fw::CmdResponse::VALIDATION_ERROR); - return; - } - if (Enabled::ENABLED == idEnabled.e) { // add ID // search list for existing entry for (NATIVE_INT_TYPE entry = 0; entry < TELEM_ID_FILTER_SIZE; entry++) { diff --git a/Svc/ActiveLogger/test/ut/ActiveLoggerImplTester.cpp b/Svc/ActiveLogger/test/ut/ActiveLoggerImplTester.cpp index 85f4862fbb..ff95e840e4 100644 --- a/Svc/ActiveLogger/test/ut/ActiveLoggerImplTester.cpp +++ b/Svc/ActiveLogger/test/ut/ActiveLoggerImplTester.cpp @@ -173,7 +173,7 @@ namespace Svc { 0, ActiveLoggerImpl::OPCODE_SET_EVENT_FILTER, cmdSeq, - Fw::CmdResponse::VALIDATION_ERROR + Fw::CmdResponse::FORMAT_ERROR ); this->clearHistory(); reportFilterLevel = FilterSeverity::WARNING_HI; @@ -184,7 +184,7 @@ namespace Svc { 0, ActiveLoggerImpl::OPCODE_SET_EVENT_FILTER, cmdSeq, - Fw::CmdResponse::VALIDATION_ERROR + Fw::CmdResponse::FORMAT_ERROR ); FilterSeverity eventLevel; this->clearHistory(); @@ -196,7 +196,7 @@ namespace Svc { 0, ActiveLoggerImpl::OPCODE_SET_EVENT_FILTER, cmdSeq, - Fw::CmdResponse::VALIDATION_ERROR + Fw::CmdResponse::FORMAT_ERROR ); this->clearHistory(); @@ -209,7 +209,7 @@ namespace Svc { 0, ActiveLoggerImpl::OPCODE_SET_EVENT_FILTER, cmdSeq, - Fw::CmdResponse::VALIDATION_ERROR + Fw::CmdResponse::FORMAT_ERROR ); } @@ -374,7 +374,7 @@ namespace Svc { 0, ActiveLoggerImpl::OPCODE_SET_ID_FILTER, cmdSeq, - Fw::CmdResponse::VALIDATION_ERROR + Fw::CmdResponse::FORMAT_ERROR ); ASSERT_EVENTS_SIZE(0); diff --git a/Svc/Health/HealthComponentImpl.cpp b/Svc/Health/HealthComponentImpl.cpp index c2400244e5..d60338a598 100644 --- a/Svc/Health/HealthComponentImpl.cpp +++ b/Svc/Health/HealthComponentImpl.cpp @@ -165,12 +165,6 @@ namespace Svc { return; } - // check enable value - if (enable != Fw::Enabled::DISABLED && enable != Fw::Enabled::ENABLED) { - this->cmdResponse_out(opCode,cmdSeq,Fw::CmdResponse::VALIDATION_ERROR); - return; - } - this->m_pingTrackerEntries[entryIndex].enabled = enable.e; Fw::Enabled isEnabled(Fw::Enabled::DISABLED); if (enable == Fw::Enabled::ENABLED) { diff --git a/Svc/Health/test/ut/Tester.cpp b/Svc/Health/test/ut/Tester.cpp index 56caea055f..6b3e17ed0b 100644 --- a/Svc/Health/test/ut/Tester.cpp +++ b/Svc/Health/test/ut/Tester.cpp @@ -675,7 +675,7 @@ namespace Svc { this->dispatchAll(); ASSERT_CMD_RESPONSE_SIZE(1); - ASSERT_CMD_RESPONSE(0,HealthComponentBase::OPCODE_HLTH_PING_ENABLE,0,Fw::CmdResponse::VALIDATION_ERROR); + ASSERT_CMD_RESPONSE(0,HealthComponentBase::OPCODE_HLTH_PING_ENABLE,0,Fw::CmdResponse::FORMAT_ERROR); //send command with bad ping entry sendCmd_HLTH_PING_ENABLE(0,0,"notask",Fw::Enabled::ENABLED); diff --git a/requirements.txt b/requirements.txt index 07101c59c7..f9c8a745de 100644 --- a/requirements.txt +++ b/requirements.txt @@ -13,7 +13,7 @@ cookiecutter==1.7.3 Flask==1.1.4 Flask-Compress==1.12 Flask-RESTful==0.3.9 -fprime-fpp==1.0.2 +fprime-fpp==1.1.0 fprime-gds==3.1.4 fprime-tools==3.1.1 gcovr==5.1 From 4829d3d56f12b4667d2f350dc81fcda8d5c81b63 Mon Sep 17 00:00:00 2001 From: M Starch Date: Mon, 14 Nov 2022 12:18:53 -0800 Subject: [PATCH 094/169] lestarch: add communication adapter interface handling to Svc::Framer (#1763) * lestarch: updating framer to handle com status * lestarch: updating Framer SDD for status handling * lestarch: fixing Framer UTs for status * lestarch: reformatting Framer code * lestarch: sp * framer rework review fixes * sp * Update Framer diagram * squashing stray asterisk per review comment Co-authored-by: bocchino --- .github/actions/spelling/expect.txt | 1 + Svc/ComQueue/docs/sdd.md | 12 ++- Svc/Framer/Framer.cpp | 77 +++++++------- Svc/Framer/Framer.fpp | 11 ++ Svc/Framer/Framer.hpp | 25 +++-- Svc/Framer/docs/img/Framer.png | Bin 86526 -> 109683 bytes Svc/Framer/docs/sdd.md | 47 +++++---- Svc/Framer/test/ut/TestMain.cpp | 16 ++- Svc/Framer/test/ut/Tester.cpp | 98 +++++++++++------- Svc/Framer/test/ut/Tester.hpp | 14 +++ Svc/FramingProtocol/docs/sdd.md | 22 ++-- ....md => communication-adapter-interface.md} | 45 ++++++-- docs/Design/img/com-adapter.png | Bin 92476 -> 154761 bytes docs/Design/img/com-adapter.txt | 34 ++++++ 14 files changed, 280 insertions(+), 122 deletions(-) rename docs/Design/{communications-adapter-interface.md => communication-adapter-interface.md} (55%) create mode 100644 docs/Design/img/com-adapter.txt diff --git a/.github/actions/spelling/expect.txt b/.github/actions/spelling/expect.txt index f1d5c08a83..03d61a73de 100644 --- a/.github/actions/spelling/expect.txt +++ b/.github/actions/spelling/expect.txt @@ -673,6 +673,7 @@ instantiator instring instrlen integertypename +interoperate intlimits ints Inttype diff --git a/Svc/ComQueue/docs/sdd.md b/Svc/ComQueue/docs/sdd.md index 8a8eeb3652..8dce9969f2 100644 --- a/Svc/ComQueue/docs/sdd.md +++ b/Svc/ComQueue/docs/sdd.md @@ -11,16 +11,18 @@ in the queues being paused until a following `Fw::Success::SUCCESS` signal. passing in a configuration table at initialization. Queued messages from the highest priority source port are serviced first and a round-robin algorithm is used to balance between ports of shared priority. -`Svc::ComQueue` is designed to follow the -[communication adapter interface](https://nasa.github.io/fprime/Design/communications-adapter-interface.html). +`Svc::ComQueue` is designed to act alongside instances of the +[communication adapter interface](https://nasa.github.io/fprime/Design/communication-adapter-interface.html) and +implements the communication queue +[protocol](https://nasa.github.io/fprime/Design/communication-adapter-interface.html#communication-queue-protocol). ## 2. Assumptions 1. Incoming buffers to a given port are in priority order 2. Data is considered to be successfully sent when a `Fw::Success::SUCCESS` signal was received 3. The com adapter is responsible for any retransmission of failed data -4. The system includes a downstream - [communications adapter](https://nasa.github.io/fprime/Design/communications-adapter-interface.html) +4. The system includes downstream components implementing the + [communications adapter](https://nasa.github.io/fprime/Design/communication-adapter-interface.html) ## 3. Requirements @@ -162,4 +164,4 @@ buffer and com buffer data, do: 1. If it is less than the size value, then invoke the sendComBuffer function. 2. If it is greater than the size value, then invoke the sendBuffer function. 4. Break out of the loop, but enter a new loop that starts at the next entry and linearly swap the remaining items in -the prioritized list. +the prioritized list. diff --git a/Svc/Framer/Framer.cpp b/Svc/Framer/Framer.cpp index 873ff0f20a..3ec1cf8f1e 100644 --- a/Svc/Framer/Framer.cpp +++ b/Svc/Framer/Framer.cpp @@ -10,9 +10,9 @@ // // ====================================================================== +#include #include #include "Fw/Logger/Logger.hpp" -#include #include "Utils/Hash/Hash.hpp" namespace Svc { @@ -21,13 +21,8 @@ namespace Svc { // Construction, initialization, and destruction // ---------------------------------------------------------------------- -Framer ::Framer(const char* const compName) : - FramerComponentBase(compName), - FramingProtocolInterface(), - m_protocol(nullptr) -{ - -} +Framer ::Framer(const char* const compName) + : FramerComponentBase(compName), FramingProtocolInterface(), m_protocol(nullptr), m_frame_sent(false) {} void Framer ::init(const NATIVE_INT_TYPE instance) { FramerComponentBase::init(instance); @@ -36,56 +31,60 @@ void Framer ::init(const NATIVE_INT_TYPE instance) { Framer ::~Framer() {} void Framer ::setup(FramingProtocol& protocol) { - FW_ASSERT(m_protocol == nullptr); - m_protocol = &protocol; + FW_ASSERT(this->m_protocol == nullptr); + this->m_protocol = &protocol; protocol.setup(*this); } +void Framer ::handle_framing(const U8* const data, const U32 size, Fw::ComPacket::ComPacketType packet_type) { + FW_ASSERT(this->m_protocol != nullptr); + this->m_frame_sent = false; // Clear the flag to detect if frame was sent + this->m_protocol->frame(data, size, packet_type); + // If no frame was sent, Framer has the obligation to report success + if (this->isConnected_comStatusOut_OutputPort(0) && (!this->m_frame_sent)) { + Fw::Success status = Fw::Success::SUCCESS; + this->comStatusOut_out(0, status); + } +} + // ---------------------------------------------------------------------- // Handler implementations for user-defined typed input ports // ---------------------------------------------------------------------- -void Framer ::comIn_handler( - const NATIVE_INT_TYPE portNum, - Fw::ComBuffer& data, - U32 context -) { - FW_ASSERT(m_protocol != nullptr); - m_protocol->frame( - data.getBuffAddr(), - data.getBuffLength(), - Fw::ComPacket::FW_PACKET_UNKNOWN - ); +void Framer ::comIn_handler(const NATIVE_INT_TYPE portNum, Fw::ComBuffer& data, U32 context) { + this->handle_framing(data.getBuffAddr(), data.getBuffLength(), Fw::ComPacket::FW_PACKET_UNKNOWN); } -void Framer ::bufferIn_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer& fwBuffer -) { - FW_ASSERT(m_protocol != nullptr); - m_protocol->frame( - fwBuffer.getData(), - fwBuffer.getSize(), - Fw::ComPacket::FW_PACKET_FILE - ); - bufferDeallocate_out(0, fwBuffer); +void Framer ::bufferIn_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& fwBuffer) { + this->handle_framing(fwBuffer.getData(), fwBuffer.getSize(), Fw::ComPacket::FW_PACKET_FILE); + // Deallocate the buffer after it was processed by the framing protocol + this->bufferDeallocate_out(0, fwBuffer); } +void Framer ::comStatusIn_handler(const NATIVE_INT_TYPE portNum, Fw::Success& condition) { + if (this->isConnected_comStatusOut_OutputPort(portNum)) { + this->comStatusOut_out(portNum, condition); + } +} + +// ---------------------------------------------------------------------- +// Framing protocol implementations +// ---------------------------------------------------------------------- + void Framer ::send(Fw::Buffer& outgoing) { - const Drv::SendStatus sendStatus = framedOut_out(0, outgoing); + FW_ASSERT(!this->m_frame_sent); // Prevent multiple sends per-packet + const Drv::SendStatus sendStatus = this->framedOut_out(0, outgoing); if (sendStatus.e != Drv::SendStatus::SEND_OK) { - // Note: if there is a data sending problem, an EVR likely wouldn't + // Note: if there is a data sending problem, an EVR likely wouldn't // make it down. Log the issue in hopes that // someone will see it. - Fw::Logger::logMsg( - "[ERROR] Failed to send framed data: %d\n", - sendStatus.e - ); + Fw::Logger::logMsg("[ERROR] Failed to send framed data: %d\n", sendStatus.e); } + this->m_frame_sent = true; // A frame was sent } Fw::Buffer Framer ::allocate(const U32 size) { - return framedAllocate_out(0, size); + return this->framedAllocate_out(0, size); } } // end namespace Svc diff --git a/Svc/Framer/Framer.fpp b/Svc/Framer/Framer.fpp index 071d06951f..3017d2380f 100644 --- a/Svc/Framer/Framer.fpp +++ b/Svc/Framer/Framer.fpp @@ -34,6 +34,17 @@ module Svc { @ buffer passes to the receiver. output port framedOut: Drv.ByteStreamSend + # ---------------------------------------------------------------------- + # Handling of of ready signals + # ---------------------------------------------------------------------- + + @ Port receiving the general status from the downstream component + @ indicating it is ready or not-ready for more input + guarded input port comStatusIn: Fw.SuccessCondition + + @ Port receiving indicating the status of framer for receiving more data + output port comStatusOut: Fw.SuccessCondition + } } diff --git a/Svc/Framer/Framer.hpp b/Svc/Framer/Framer.hpp index c94f6e7b74..88f09af8c9 100644 --- a/Svc/Framer/Framer.hpp +++ b/Svc/Framer/Framer.hpp @@ -28,11 +28,7 @@ namespace Svc { * Using this component, projects can implement and supply a fresh FramingProtocol implementation * without changing the reference topology. */ -class Framer : - public FramerComponentBase, - public FramingProtocolInterface -{ - +class Framer : public FramerComponentBase, public FramingProtocolInterface { public: // ---------------------------------------------------------------------- // Construction, initialization, and destruction @@ -74,6 +70,11 @@ class Framer : Fw::Buffer& fwBuffer /*!< The buffer*/ ); + //! Handler implementation for comStatusIn + //! + void comStatusIn_handler(const NATIVE_INT_TYPE portNum, /*!< The port number*/ + Fw::Success& condition /*!< The condition*/); + // ---------------------------------------------------------------------- // Implementation of FramingProtocolInterface // ---------------------------------------------------------------------- @@ -90,16 +91,26 @@ class Framer : //! Send implementation //! - void send( - Fw::Buffer& outgoing //!< The buffer to send + void send(Fw::Buffer& outgoing //!< The buffer to send ); + // ---------------------------------------------------------------------- + // Helper functions + // ---------------------------------------------------------------------- + + //! \brief helper function to handle framing of the raw data + //! + void handle_framing(const U8* const data, const U32 size, Fw::ComPacket::ComPacketType packet_type); + // ---------------------------------------------------------------------- // Member variables // ---------------------------------------------------------------------- //! The FramingProtocol implementation FramingProtocol* m_protocol; + + //! Flag determining if at least one frame was sent during framing + bool m_frame_sent; }; } // end namespace Svc diff --git a/Svc/Framer/docs/img/Framer.png b/Svc/Framer/docs/img/Framer.png index 518e74ea3cef7833e6918e113a470b8bf01bee5e..bf86d6b49328b57626f055678748541905aee425 100644 GIT binary patch literal 109683 zcmeEuc|4SR`+rF_(I#6Z5yeTCiU?U+qzK8rhmd7V_MKEJdnHTuWXrzqh7`&kAqHdL z$5_TTw%>L4ea?BF=RD6-=l|dNqu0xs!^}OO`}4W3_jcXhx8ViA z*|u#DY1=jm5^5K`BDrxAUf9lQdiCmU^Q+QVF%}qWr3dgS>#Hzr?f%0D`#)}@ zJbRShwX~)Z6~{OAsG;h0Ep^eIJHA1lBo@{tdEVc+^zYtn*p?GqFH0pkeVkS6M`eIV=1Hs|oAcju(xgl*as?(}S|lvUW;ZB$u{r|nK6otJ&%orM0qWtw2=)(^{S~i0Jx2~)X^0Q?)c4%KW5<^Ald$j;J03q2-|-PE z{3Suk=(geEH-1MBqvp2De3mh12(?dzmAh!9e$!Y^ZW|Z;jM}#Sndvr4_-Q-*I|~0` zfnzCte`OCTcE|5OQ^4A9+g5FO_Ao5|wwu>3D?4tV?%f^9tkNYh8+7}S%pvD}OfGw{54OL>*+6eE7>B##KB$%SB4R?DvC$A96i|MBtRl6PA#rwsn(ntwyyA={tkA8#sILAx^dg)z~IL8k<-Q%KG6$5;Qy56V2Vp=|;3h1%AZ z?QP+K|GY__9E=CY&F7hhNxy%x3e_#)#TJ1@fi@N4gyP>{{p03t+_{_cW%qLZl>OH~ zUZX_4rdGEu?5X|j&x`QS75wK%{`j5bYm%{%`X;d6?uoT#dG{|L`t!eyJp_Ls z6DD`%e_q4yck=i5soP0Ou5{yq`E+DJe8)8D1(uN1V{zf04fJI;UW zEPt1#zf04fz|tSv=5N&Wm-fcrsOc}Yt-s;xUus)_^N2s{&rg2%yEOe>n*QhZ_?t)k zrGor7kN8Uk`EMTaKM&f!5Q@Kf#9u1N|DTqoyR9- zjhHO;;V=aas}20k@n1M1(nj3q`F8C+{9-i5V^hF(yoD=~fA>GCTx=(0pYv2Yodh*+ z(cQwxs}3xgTJm+5Ik-TP^`5jZIs7kL_`mE}WLJ9zP_3Jd`L~@>km&f@=weYCW#9e2 zHbBR|U&Hv#DXFjr-?Q|MB94G^E*VJW$0Wq7<2;ct@k*BWCZ=M;-g*4(GiO^Y)^%13 zQ+`3malmV$no+O8UDs`~UEo1~rNG*BZc>+V1W$TS9hWH%T_`8ZTYN8xH#aE&_dY1= zoTnuN{0(C(y_)vRjI#MU+fE&agcX}+iOsn{-saZc+NpW(@7a1N6lu{HH_i4hg8ZLP zK*QS7{KFft?X~Mnn98gW?{!}zOe{1@ zG+!Hyv}tnZ4f0s+)OA6N%ztKYb6f5WExpXs?=TkSkZ2evCdiZ9aDD>r!Yx_8a@(1u z{HACTOTvoVz;f6*!`8W47Cbsh#BsJ?V4;EEM1sFjK&gJpH1Q3Gl%00^80DbLaGwiN zu2b7aj$zn^Jdva&w=|IyQ{as6i5MJ;pS!vAhrl3NE?CR0PE{I-2b zjIivUcQ^2$@eGtc?sT%WA#?H=$I_I&8zqVqUAZzh)RwIHE@zwGlNFA58C9Z=6tTf| z{tIVP`Ep-r`>-!hfjYw@*QG8Kt;Np1OY5^AO$qs(@6iGduKHiMb~RDTq6z>|DPdaO@3swGor3qNZ~pHS7COkisY0vZZcw9{ia(=7pJ3 zqI^rc{qh{g_`T_#Owjhpiv)+cpA-dO?wlJwcdvSwuFaHUWMeZcv~#CUO2#fz!itp( zeB8^Qr#vuK&OhP8FFjJUv4qPU`7{)xCe-I>Sn$cxw$C1iHvPCy=oX6`NwHoqpOIL$ zAkUy&+W&~!Ooyk!WwMBemh_g9X7WJbShNeTl;nK0%gjv{k9Dg;z01nad|A!cKjpM? zMmrj)mSb`o1?#Ka%+vE#!!2^Yl(_YIuRdgPoxOZi+|{vA#{do#PQJmDobXUmucC~= z8~(opgWtC$sjTv~lKh(vI2LrO@ znWtr67a5DRX@y^pa>=*ytLadxMMoxOmIWp}Kz^$*(vn+xt6p#O{KisY1$yF)^Eo(N zc~w+r;)O@U*rj%29kK7OXkVJbl+9gVQp&@S0+~exHwF%Pe0CqaB-nK?DDCKwbv=(- zK}7Zz-`OuGgW^$Fc=NyA=@R>K{I)jmTM31DchSz|@>7AOYmUX7Z-XRv!z~m+8S($` z;_-X=v7rc(7cnh?t)OLJLd34+uy%9CxVE;ANojfRIB+RTWlU8I9UKA`Mb&L?R0~g5 zEm@zhZ}Vc*{cdbgbHv1=trNa5zak4E%qT>o^>k9?tC^Cij8?M(B?U1%p9lB2J+!|e zHHEI(W&PTP>fOg3WAC?dqZ~I^$C4yACKNO(XFszC-cq`CPHJFj*PWx693Padjz(xH zPUqC~{_q$T(V5xs25SB~>3t5%bDGROOcYUchrfRzpyhuJg2rD}`kcuK>(KMq;3eSn z>`Nw7Qd{A4e4Vsb({o!?B~IZZ?Ym7)ze+Kt6YF$|1vtxevh!q7I>(zEee1K&B)H38 zCGS;Z81;>MXN?chvV5~S=CR4y>#?;l@l~2du9S#%IVxg%e<1sv^N3X~b7+XR^%vWz z^g;$p6IQ*upPtj0Lg{K`nZAO7tw^18H`JYrwWU)5Q&#^U*5jXDwDJ>Yx7HVyYx3NT zo8TlDHx}<_5igU|OE-klJ^|Nq^BJ?fy3e*&uGF+wO_vrL@`eILI|RSDFMqSrk~{yh z?2SX8lWgY6D(5IPO{?hQH>Ec7%<_=^BIB`i?Pq*7xmil##wY1G^j^@aE4(kdf!;Y9 zfx#9;(YCbp)o7buA(M4R2xXFd1sG*>r=s8g4r+4_GjPp&lgXLx<}D= zi+`Utg=e6|W|5p7_Pf9p7bA4y8)KPgEbfj=L4`UB%tDw9@3)xIHzvI0ex5r@btTS( zOl>S?dPJ!ZaZY1VZBWHSMAf)y)}BeMpAg$1wV8fPRy2jO*xV~`V(xk3>eIZLuu6ws zx3WE#m`fcVSB`&u*S24D`b8i7HFryA-?F*Tt*(iywi`@|ZAx99zdHQ~$B7g>cI_P} zQhIfIAT14rzfh24X6cU`EhoMo8g0CAj?{Q@$WP4uNIh?1bIR#`mk z_O^XOJ-18zFH=zZ?A)9Wt%%33j|x>Y34DDnsYlzpH|f{rF-gzUYN%%Mb2V&Fm*IPB z1DB!H%-c>RgeLA}P>-FRtXLWJwRqnG<*f7p(+*11F!iP79vjnIW`_nAiz;1DEJxXC zdGBA}LJtZ|`J!r|wygqlp|pHK%yHY<{tpx14Fh?~$#X-sNefM)nYK)iDN%V0&ks%; zN1#KHw$-siZe2b$(;E|@^n2Ri_q*^Xf1%^I zsObY9D_19qV3{`0%tB*LTITBtF*8A%#tUjjp$B8$qbjS5KP?kl-d=5sz5KX!eW5u9DNWOy zTr&1*Q}0cN;9BJLw#c1rLxB=~I!WDchiq%d0Et}vCiv^pltQ-x@7QLV6crKxZJ5+; zo;f1V{2>e8RE&^ad)zcNy`Zj_Lxg>r{%z(`H++jAFH?>PiyXlSaq{>((~)2`c?7#e zWS0d%0}#cDW4KeYHilTX?q8rA$c-x)3DGk443C>bIUvVW!>%y;qUG1J#SNMpCF60v zt$?&6cQ*NCa8k%Hq4N~G0g&H$vR2Z{cG9uSC^P}Txm4JtZRNLDKu#Cnw-ODM+k!HES*k)ki?v<)F^L5bdzBDiw@v+C@$&lUN*c2E?8avp&p; zp1HaqnBQroU>xJNl-Df277r*{Xy37mR(zL^UM^T^(6(z=nRxr`IM-gQrwWv0!S8n; zTTFb1!=81$16{#>)~!Rs#3&{er4y3>J~5n&fL)t0-P%}I;BUTU)0LQDD7I>G3Bb2T z7~hp@BlMS3p$%6O{Bci~8-?&a-*r~7r4o7+ZeHJZ{pT6_(<`2R2aBK`)StXg zpNsPPq@Zj--XMC!?0j^z8Rv->ngxOGXdcDT}Yc5sMyt z^W4m>@jF|V3d6W>%dj_RbeM{m1#vyKM8bb;Za7FG5zy1wYLjB@z9Z*PQnT-8666*G zN_D!x_n~omb*_8m_TBOId=;0dpEZe0rRBf%9(8ctwO@?XGHpZKY$&biS}?T6;~oNh zl7yf~H-fp|)aQ%@+^6Mk{b$S}UWV+~dS5c&J)k&h7bv(kxzG9P#TR8Vqs2BXJ}tXG zNknS4y~1hi!cbCnJ|krs8m|k>*!p;*jQD z@RQk4v~P=0i{GBD8mxX(QPnur2=zg#G%>lKaiA>u2IKa~xTR0D3h`I>3!fBKeKIRA zw)jm@A4_(FLPjFN29OYHP^;*L)2Xvn@Lso2&65D9zKN?O-=S5dC#KBid9!p+D*3FQ zGENkZXRcYqR}bK(#Fg2D@-?}F* zgnTuhNnaZEeL=~eLpzT<_Iu_54>bvv9?}>$^KBWwLe2Bq>#Dgv_H<$x8v%+R0zb%oxYJe*!4V%_~dDZs5Ot+>gu8Ksn5(=`=D|B zY19APE0B{zh58*AE78+7=hwZbJSwueGF0knmWd^sX+mkFPQ~v#D)3vXUw)5uy`59Q zcPl91pF@iLPdS#h&Hzv3ZlLvy?p9DHaGBAFr=mlb*8)A(4GYWxXA#TT8gf8tFlwhU zAEKG|HsX3$r%9Q!xw%}Clx4K%QPYQ4z~)^cC1~8 z2B*|np^%(_hxpa8n3zGEuue8xrmblWdh08RW5 zr<1c8z3IA#6go9~Dq zyFdXz@I*Pmu9J;WAQwLtXR?1|Y>$tl(AM>p(eKUvHu-S-jvru9NUGE=8xtu#r0_Ms zA9n$pNdP95&Rnr1%4JjS_WnS*E71inTiEAp&V)-oUIa}v0ebK$>fP-Did&*p=M;mp zt&a4nhuF;&k2R&NjPN|x_V7c|OU)(&S222?1ZogjPP05a<>E6Q``GO}`cy&0)q`nwCTScwWo|`Pt@tq^ewlxnl4k3G? z_O+!D1>V#awe}5DN?#ZHn9ec={kA2|Cv``)lwJI|%-o8rTMH1)BtrK2DSHRNXM!94 z%-MTqMnd(XH*Auvxcel4@|i}U3r_Dn*Gc3zZV0n@-v?kXK0&l9lSY>X__3^BpYMuA z_4&_I1oBiS-_bhpipCWS+u>r1vg992=|9=`D{A4n#W%aTMl_MVF}ibo3E;0SC~kDT zM5=6aitP1KXkIUP;i!!G4#8r7Fwf0&TQ>@@r`J)|HFZy#=&_}&9I(g|qL zEp(ZXDvF3Y6Hvu1gg1&f6^*#BSQGM5!vqimydt6i$riWw8a(SVi4m(7<1x>6HRV=V zhgL3%<4)Oe{X)(~eDWuH&xBK<+UKeHcyd0o89kd^%)Ypsqe?eEmA*zhcJyslTwNF+ zcEzA;0$md^E9QYqPsvup(lyYuq9>Go@K= z%40r%;M?V2N(|p9CwI65ld)DEF$W6pnTvDJO8e`QO_z#|CE42JAk6MQEO7s}2;A2; znKS9iMd+SXn)wC|uX;~K*5*0RVzBSM$T0>q9~yBJAshjjo<1tNE)L-wZQ^)re`>rx2q z%k32bKF(5TAo4tA`0RM%z%v%zJoA{T82zV5WSWKfhC6V}oD?QfJTp2j>A$rIS@sky z*`w>`lA9Q13&--A?Z2PMEbYY-J+{`oaGzYWNw&IcK!sXCwdpk;&-%FkOd7e2$Zf=uD9z!6*X%uivzhJ^t~p(2}j3WM!tgWp?KwS?-s{u(0yXtXx;nP#C?| zE`jJ`I{iJ{YiO4U=fU_Lm2YV0^oy9Qrf_UN16wVG)tm%U{M}=IUc9 z+0G8$6BzHIKCHwXw*`>Pd?kxj=F7cHAqNBeeM5rK+H3_Qm2#VGA#qKqVT|>-nq?ie zZs?m@nluY}ZSv+SmvaTBm9efMvzcRZ@on;===%9@>ASj}Xk|57tUsUNq2D!hQE_Lk z#SxORo1h5oc^}-Xt?wfk&u^`{s1$-KMnZ{NvMzN8w8<6a&^oQyd! z2jC(m?R22hH|9Z)%opj56OuYnlYFU@5qF_eJIJM*rtSLwTUn4MiWY8ra*C5Pp>Qz5=&n**)8MMRm#%|q5`FXzJ+5nh`>**v*|ft_FrVj06O z8^Z`}hxkhWW7}r2<>6?1WrnC13@1ioHc3hEf7^EC1CC7f5X6<6b*ZjhFO6Q{M4JPi zt`1&wTkT3FFPs8hEXXACSNodu;^9O5laKoWa-xezLMHt9n?8%F>*-|hFB>>#FM#CT z80ChXRszw?guAro&5PS=W2Q?R-PEK;(8SVt-)8p4pdLj7Fzadt2j<(PCdX5ud@a=Ivk8L#{gFgx;3^aj^uv*O64ZiA-1@| z+0waJA0_Guc1_*{4=QkLs|0dV|@M)kH|I# zPJIXqB|ud&ZM@L=!>{TFGTNpGQk%dz)xya%SB>EKxCBR0QE3mnc*qB|h0)uD8gw}^ zvJzUbPRU0oZGC2CZ-@%q`&@v9#{;4eN4&d5Cg$y5@nAU}7$3^iS0P8ie=YA}xMu8x8we zX$V*DPtC-d3Fk^|tu{{py1+OQcW$RR4FJQ#%uh$4+Uj~2>@$K*}3p+)(6}hk0rB*jH%a^(-^}4_*)Nu5x znblB?<-78_yeoX*pXV7P{$})NO8o6?$&FX~72uw6MfciLqHGH#dHNY^{keWrzoX~x z-B1-y7O%whE(qf05@X!S0@ZX%@qyyx^kT!52IKV8VGR5_{z$@zLRDQ zu(OTjk0~xYtJ#346?V2Imc1Eoe&2Q))`eOu!n=PaU$*psVMqSn7=S+K)AL$o&{eL83&(IN`uj&$E1NhU1I4KcNuX*|T3=%}qTQCd$crcyVl0n?W zph&q*(`yegU@Fvc+46w6X1cN1scx!m<_o;4WLY+j_r>-@SFvoPigA*Ky%gnW* z$j-A-?l7~U8OMS5&Qw}XjH?7eA-XQ)ivQiOoj_Xzr7=)?=~n?W)%Y0G%$AZTQ5dOqgkpQXPlrYGb?MXvFS+&@K2I!H^bMQ; zEg_>0-oN6BsKcqTZBLR$U!zFjm54EA>nXk+yTtMgQFzNig(zmqfMZ;|AtK6o&@-gW z9(1q-^(wc1N#ARutF{G1=qJ3rMuB2WpZ8T?__*N&1vdAAiD4LDQ@R8=4!f?8mn4@% z>zjbq_gng)S{^37VtkFa=AD7L+ZifSbxtJ$UVTzB#Cpl(T*bw)`a)9$iI)Kize0E- zCvI0fnE~}SQvTw=6Wi61&?N9=*`yrJpeHqO&C8vuri;2b`Kf#Y%0f66mQaxKh)SBO zuG0vVUJ<@5;80^TbShZOqJgJ9*%`LS!L&XdV$6KOOj*sI*tQl4+UW#{Pp8YC3Xetd z1ESL}9%_8x;l8;LlLRhzZsRI5NHy<&Q|>Sx@{TuzD^Qrz(fyVIA%eKK`xmzsVz#(@ zEMdXW7gY0(Ia$!f6fXCMrA4ty#9k1Z*gPcf&r zUmP5#31|Sx_JbbHg7(wjLxgL~)?LHz<$TfXQ=2o8Jo>^o+%Q_8`dj;YIllhq=tUcN_`ck4RlTsp1pyL9I`jEW<=Q z-ZTME*p_^xEt9ugR8IKb{lep&AO33xZ1JO@aP9R_V?%{>+JnGTHq(k#=e7O(B49&$ zJZjIA*Ye%FcQK{9x5rp3GnFE8d11u{fjlE$?hf@+iL!#NK?vYp0=l3pQE6>?#D6Hf zVrzq#q#lx&jL!MOVG4K{x~Gahn{Hut;3IXji@|YqFovjhxXr!sHnOQt z84K>BQyKSdmVYuii927<9rScRv!=Q?ab+k_0SqCBaN}^(Nr$P~sTI*Cm@JjRiF17x zEC9HS1wAY+$6Oj)n~F$B7sRE2aNm9}8DBHRvcI?MWmmZxqFxZiv+ut$^;qH_)a>H4nD1F-U85|76-%MGGJ|=%j>tY; z>fClGS|uF=_3#E_2o2y(5uf^&Vl`KY7s0|e*pIDpdAVXs47bQBv3k>|VwsSxY7|_9 zqy*5Qp-lj;;VtVq3!;t^b**7+A+Z@LelG4b;Xbon7P*ZfqPqAa`rY2|-4F#zn#Ii) z!9(5Js;-!gxj+w#JyrQ#u~7jyOof<(FKYBc!3tIjC|xUpRchW&yA^qiiQ>P6*b=A5 zX23(d0X~o^g81587aBuBB`6fM5tz!QiCH)xzQQU8mw|37&VD!FtTwdA5sHo{*UrHM zAG0}J911=>-c3!i<4iV$9MBNO;?|wRTUQu7#tD1`kaTVZLc90iUB-Ld@A$79?d&-e zYF5RC5$ba*353vhjq!+Uaz}9_0kr?Z#-;p#WR434pPqN)s_-Qln?}S8|A~}*^+H?w+ zJ4L8=K#?J;obQAPMDRxWZJy6zLZ(mR*`_;RzA(k~#Xw$(he*oB!mh?JQ;~Wdhy06c zpJ%D-St#;gz|p?}l>Yk61Q4Ar9V(JPv#6jB2-N5RVPNA4aVhcH$1DNI?5CsOF=XQa zY{1^}&3safyGS~eJ&n8k0duK(8(a?fK6k-73Ky8>p1K{&myuc5tVXPUGbD2X%*%2~ zN;P?riFi`onaq00y#r1*D!CSh%70b-R z*7wN0ME6iH(tN>tqOYVD<%_s&lIc=XxtAaBYVRvpWv0i^Yo%jNEsK!?vKp2Y(elNj-`9$Kvc1t#aVc9*a~K=oW)m7bw*U5Jw01rRdL7eDrlGl5KZZPnYH6C9>7ozmm8y=tCce_`!iS*?j3s?Led~2CLFPWs6-DSY3TFaQCf9=B=Lp{W{G!UoPOo?h(K!?dYQjr+)<@iUh!pLhiT5$Jwv;~{-`h6%rN z9du;>oaU>BcKN8~PlqD$8#4}VprCx^YJf_$mOv=Pi!T@DH^pW3LIYOE-FxK0*r+J_ zz$BHgW675lZxpH%5~AxoVc|WHa~6L`mM0kDbo;?$3g|2Q5vL@a$E^o6-+#imP!*Ov zJb^H9i!YsJFEo#F&q#CQw9IMPd`HX{GJvtQ1qmDE~Boa zzRyF0o+)+j>``Ixzm1&y<9q;tS-jp!W_zt(5w6+Dmj<1tJEg=RIEIg&Z01mfp`Z-E z!iw!5I$%Gyd;G?;(ERTlnoZfH_|*yIA9{rt4&+2~9A^Mgz3*+}LkGGDB5Vd{4QXZ-4Ql z&wRIp!~r_76lz%R?S=r+nJ};2?86$WPP~u!rFgiU?DFlFt%jW0&K}t`;-LtfqxHyS zs;{XL^S<4IaQs7*DR_yhY=YNL_HBqUOYYUwtzBr-NiSH(e4Rr~Y`V+UUpQmR?gxcz zqRw95S*1QB;C?;uc<=d;Wi~7Z!8d6Xnr?PkW#|R6^VH@wR9c!;VN z25o2uzQc73*_~uPqQY-@v-3Og;g0>EDZbHAp)I67G_5q$j0vdHOy8Oc7~1IHE%EtL zt-xVc9<%bXUWEg>3iliS8BE#j>$@2KggX~ z-5RXO%yoq^pGq-Xrzdx1>-#&hhO{Pk{$aeQKmD*s4#tA^L_W$a9ge_zcF)qHjAZib z&cSfD;n$3N{Rr$A87^lP)imWn`ZTg038LvjRcnfrA1IjXDgg-F_DxAar$}z^dh^!0 zg2-&;4(dX0mEHo->Z;}f_FhxxihjEk?F*HR9}uj)DWWGuw`T=ZEO?LH7!t2(O`tjN zhi6W&EPy~@A^>3?o{IH(X5scKwDZvBwS!z&au$P0R0?NJSgVY)m2K8%ZumY_HI%AA z?X58>`Hjl1;au%&aS8tg`>{DByFn-G$+#hQH|^Ttt?AR$BU0{cDUWNi&3Le!;IdBI zQ**Qz1mbB9H)^Gnxkm()9l!YCu6;9zm!YkV5d&S%@7nh?$1&i=kTecWPln1XKM(2W z^c+mYoAfb!vNH_5r#B$ZTOzr>y(kTUg2!fHNDkWXXL{kdU!}Y#;dOw>rEuj~N>YU+L% z-{^730jtiPAztd9@_lIXWVJ5kPI~~&nEJjWj2e5}neYi{z$Bav>?mRJap3L@;zLtw>LF(cZ=;tn~m!}|e(kyyS77qcUmtLD9 zM`L}N*~=C{&@qu6sB!a2@r9^>K?RZ}mqM9CKbNCn@Sz`%tLt}wj0N}Wqbhrcj@u4v z4{inmgc1YclJ?lBuTARw<|o&$gBtfS@29pbx|Tc~fP&b9E*g&#;04%$7P>#~&D!-o zDZ0Cr=>s;mS^Nit_0q?Fzlha}tI~PGSFh>7!Z+%ZH4oY5U@?9tn`b&t76*&XEUbP2 zETtzmrarnNq7xEZ5TPISHLN{9r?@ZozIRW}>O!9aWNf<*l_6J;?{gJ28|zbV%?5uy?M#_J`?LRSRzCMRLP=$+n-@p*&y zU#=by6Cf0iMW3eNfXF6;??DspwXT;8m*c*RS9v|&eW1x+!y>!7TX|gT{#&mcGi{nd z-&sAw2OLd8DTU=gr=v2g8S9s>pUQ*x5KYgnIcf?Dn3?b*9L{>meSC4@I*!*Kr04S7 zLSQ(zwsM{=S~==G55*8y zyl3aXXB*~bjTKo9X`-37w>W^j=s2>u=O0b>9y>gK z+3%rbjHF(SlX}#j9?KK<9G+W4N#=;F?MgT}-bO)_Tnf>yKZYJifSU?k#Asj%dm!!> z?mqjNCGUwVzVE;NIot746}C^^8@db&7wSyChKX+qzB5<=y$pvZ?;k!FB9`mvW3W2;C-` zf_=ew8si8E6X)tc#N23%c6)j9#jck=o{P2KtVBMK)%rYeE;}3?R_&Cxd>; zkd}RHvhERlG0i8m_R|833UYQzv_DzcJkxLj&r{fQz8CmleuiqryFoMV<;{028_9C0 z()Ooz80Sf_DAb-!pW05*cmgWf1Gn00^C%Z zeU0c1C)(911VZNhS>=Fi6uLrR&K*%Ly>sd;G0ZKWhyV~sjN2U*bGEfVfQM@r7uzb^;vx6yWlO`b;#AI7T=R8TliEX_bLC>7j2N{u8+!Mulbu^{auOzu z5@yz2?KZeeT*>yo2)H0&q&)iPR2p+_OgvojQX>^B6SuTLvJ%Z*y;hD^Tjwx)!BJYo zMO0AE_e<~^N;<=Hr4)v8+|}#}N^7@($!oM1B_C5Wr{RU*QeYcs^(s>-!wxF=3Isqo z*ekeV9LB~{(YU-M`S@Otd3X!$8rd*n?evhDFG=|1MDd+YhXJ zNKUAKd*x@krX(%uRyXBXKOKtnyb=kYM+1-|fen##&afu_?bTz81yPZw;|N^HI~hAcoHOwlC1WS35abZdcH6E6OLtjoWx z0&UDgN&F`Vg|$U`L>8Jr^mWiZG+<&ZREEc(e6H64FGhffgeel$?=2|*fO6Kc{VJt# zb{ditGGJ({4Df=S4hW+a$x{pVJos2e5aFMNG+6?|n4^FdP5`u*11Z?K1d4?w^B{~g z+(f7>xh-b%HIgGD!MYY64cyiTMs@_EPY8fGqiX1nVcY8nFfRT~MiCowm@SUU0}L`E zH#uN~+#xrXgv5v%9Wf4{Y^;$qIZUdZl$z!520x>fqlIyK9x{N91^#!94Vl2M>4v3k zL-2bd7=ktW#9yYdk*#GbQ~9biYB0wtm&%VtLYx3d#Poeah|Jbn#TL#oj4xvd)b$%k z7&9DTLyjAgzLeL~RqlsA+uI5jTsRCRWRXCt4|%$3@CfyB1A=!7NcdM%-;2H#Nixef zGl{x_rZiDS&36kqRpGE^Z69{CL;^NRJ9qoA4L7hjQy{sr5Ps8%IIBl+gpzEc3E;mK z0;q>|(A|(IjkE``A+M5xIvxSbLJf?fQtcH$X!#M`j1YZ{O=REr3J$*+;=Ys{lOV;Q zagzGTahM0>(Z^nlan4N^DFXX89{L>b21H$(Qn*K>Y%cLjGutU^A~GM6?Jo2d|6k|r z-}V(V!|k`3AC(0yR6P+jJJntY(a@Fr%xn}-@LtiN>GwHh%${an&r=u=x^t|Gw7>Rn4{<2mP_$+{+BC}@DMt?ngNNee-4TD--d@X7>S7eg3sLgJ$L6w z>PDJS_IGPhtbirjm@*~xnfsA7&80KuR+gZ8n=`DR!DYB}k3N4ej6~j5zNh+EyCR_v zpV@oTTHoD)d)-3vcAB7)ij-&-q8U$=vIksbOFem5|5HGodX6K+!ex*MlC)rRLGjk+ zS{vdO{g`~*zGIiIqXg4mdLUjhJlZa`bGD>;&ovYV1jJ?vm;9hWDjOtCq50s$PIH|u zq9aTDNZcJA?w8%)kw+tv(lKsl5Ean$)lCl5W0s4XKhl#xg0)mEeccRJ+mUYFIG>6< zkkJ`>Pb-4c5x-8g)<-CNuO&B*>1{EJax@=Ri+J-BaGo2PEZZ1m_hSGTpUz0lmJ?qc zKK;nWh$p2>Dhs_bJAlN@n;%&j;TZj;&YsndbJlmskg6Rw+k)Xqs?>d>%=|NMmv$(Y zXXg??GrEZcICHt4NA-3tQKD`YRYF;dQepK^NkC>VRf}z_0w+_1{NE$}w!9GcXxwxEJx+buL(^?JTV+eU| z#+Pf5Y+)&9_C3rcrmuS6*jAE3<`$)Z4lXAGML4(aJyI-}#E#(g6y@wl<6p~d?iio? zc}8_RjK;x{3%V5MiTnAzh}*g!A}V<>ahI400rqrmbEfP4nH__!NG-I5 z6I-Bp)Dar&%{f}xW72k|sFsm@#8rsk#H4Yq8LSRz{%9!R;%K?xCYK?O(KRnl5rH@o z$jF_n9_9HV6GUTyuz;@fkiU>-jTxW8o4z7GgcYaPgQ~`LDA~>A`h8({gW?4gEh4F# z!hWx>Dxx9z_B*(SjDfxA)6^jF%bhtykxqM+8Q&a2=`6>})&8RZrnxH)u%7taR<4{G&4CJB?T30&kY>J+jmEzs=RRW6dF%ZTv z&-JkF0TNfdp<m)MbF**H? zN=JEm>ORi4O|A`~NmS`7n=kh(983MgC=YI>oan~44?v7VOk5L;sw4_rbC}MqO@uKl zMnYe!o^3|6Ziz6sCYmFT$eRJkJsdd4_A{sDg;VgfG< zu-$h;@-0O%gnY*ijwpeON>k zr@VY;s44VZ=cEeg%!Z0nd4z5=;jcIUz;k$dXJt55ZVNUC}W8!n4XsNH7_=`&AR{#+bcUbL1Wg|x0YhJ)i%orM)dopodyDH;gBD(CUHz8H@+Tsm1~o?{8g$F(B=nRZn77-vXU zBlT(&%mozFFBqKeJ{6)K$KICTWemz#;}v~yuWci;$1lRQ<(#sd3hhGoJb)oh%=F~^ z8UmJuTGRwR`tE^h);!fjW)o<`d19L=C8+s^@jJk-)v}BwLKu(>*LZk4g&c2-ZY5vH z`M`&Iiou;66_=8v{|!?h-}W}=*$1z-c<(KOmzfAvvcxiPtL)gt*^2!eV<|eP{~!aN zqx7?!q|tJrCT{6|FflFLm@emKtk)Y;wu9i7OxHfkRyhZUAt~7`l<`$5OuBS8Ffr5A zMZ9?U9XTT|J>$pVF~|%TxqD(Gb|aA-OJM`$$}=S_1DCS%*fJsJbKju&TIc15l@&V& zU8WFT2e#x5pHt57xTc`CyzwH#OjG8Ma0CK6=>NF1-+urV=&(SwvgwzXQ%fKCiC86F zPca3WzgOAG(Oly_W!t zus(34K12S7?}&v5fa^rQiuLo$XCY}hX}zOMtLVU zwBRH=v(txWaqCI>plzOe4kl;zFOR+ zX!&liU?s%eR;wB5o5(Tmc|{k;ZKo2(j4=p8%L9pB#d-hS)>!SNRFuy9q}CvTBfl@f zHc$88U?%zi##yg?7}bu9E~4c#^KNNFs&{6Rn zd0d)G4?h0w#OvT5d*76-#2A!BWO)6_HW|;PP}+Z_<4madYU~G|1!N*i4$uM*vHV|* z%-Ag|AeeX;{8+|1K<@^zvFQCIL_~1t8~5}05ZxjOl%z@$54pc{Z=VroH-qFSr(!>< z3j(#4^ptejUXkCaE2@=In6%ZU^1!*|7vv)L%g&RI;p@AE%eSbI^!1jT(sIiE;_ebT zj&Y-}WmYXSzg=ZfA^UWL2BUOxqyY}LOSXL(%DTtz?OTWT>!9fU%DRbiLDAc+d@b2 z?3ncp5s<1{$6`GC=*EUlq68u&yBzHJqs$=#H%9ugJ%HUwRbnRJCs`)8+4BD4<6C6m z^UEnQ-A&YGkbNo^g_>qlywTgP!4M0|3W-udN%bw}(Sez5wEmUI#08?+dyhJ6qafEw z18GUHgI_3*FI@YtT>qbSLK3tfr~PC<$*-@nAmM8fsQVF7BOKS^cJ6VcYh5n&)LS29 z{6Tb)%3o1x&v+}Aoq~oub4Epu6Jm&ndYFKWd;Oj&Yj&@lFNH4p({D(^z=K;h-L}@g zwKIC*z@AJXfpC-rL1NP9#RkBCUbTb(Nj;6bSr#)@LFdmZQcZ)~dD>lof^vQ*kDj~Up!DL?!AGpL9u*tJVz^)_???I95UYAW3 zXx?p!y<9vNiMZ6UkN3*}U(%a7$J1*C;#Pv3P_F=@a(A7c$|$w;d2qe&PEuiywJbSi zYc(chKYq9f_+08uy|;!Cv*dCm{TO_lRF-_0DbM0(`txgurG-jhSM{tzC#eja{?R`2 z8nGfq9!jq*ko2+RZLgRWCx{T(l?Br6>J00VqeNaN#;|=`2I3UTJP0&CGF=k?WDjj! z08I(@L$prPHsBn)@5!c@g0*?Ts{6?cXTJ##TdcVC_VyfZUgr^3u&|wP37t%CxHEp$RcFTpGeLHxf zk-+C*T|A~XQ#4BEP>Am7Ik5zxwj_#>mh`sWhMGSudk0xrTgF6NRw;ix83MJWLS>9J zO{7tG9V$n}mnEl{QVchd$YH^~K_nOzm(usio0e%CgRbL%Ei(0fT+CU3MDL*vHM0#2 zzi=&KzK{ujtF4+w&_E1f^%QA0a=}oVJp?3{m2Z8YeRrf|098+nA8F6SdN zHeU~KkQZfugpIEKEqG7UO9E};A4a69$juD zBAG>lKGwY&_~$h2*2}>&7eU^RNN;giBNQfq0#Ho))Qn~)9KR8 zJe%RqFHiFo9S+_!sJQ-661|hH@)+?eQbnR5fz^c{K%QGs&UpX^AM!x5NPtpMS`cLY z)1(x#=UZf;qpLm=E_0`3%c6Ok+4cSjgUT4&!vcU6c`G$+2M=8?fhmL3X%A?sQn7e7|xVk1*Tw-GS=mTU_S zR00A!H{cOdjm$}o(oY-;;4A)-$cFwPU0uo~j)%#D3GfN5KH3)_K$JqCk?;jg#|^j- z3Rc<)46+>3H}1fBu&01%^u2HaQ)t$N&pN+);!5}B*xJzT!F=8N+E))HzmZhF?;ER{ zFk(_KXAH9}4O|OI=6J-uFqsHR<^Ri*f(~AHyaKF{_!aLuMH&HbA8Q)zGnQayQ+a~Q zZ(!vR)NJMcq=)SjWIJ6wICz9Mw$q!@&Jq@i#)f9Ozy0RX8LqS ztnd^L%ys!}5`i?))`mQ7gC}SmsAa+Mx9PAj94uQXTNtBCxxtqKWEczXu$x@8USF)@ z>N%_yGHg(=*G4v!yNO8w>|`A+*1njHwdH0@YeX-mxiZ7cvsnnLi+r8sawua@*weHE zd52=V<(vP6t3RlUt&QiIEo)nH=g8PSssm!A+udNNloUV5{Y#@`r3CORHcp~Yj6%a$ z;ps<42>Qrfrah4Z`&%qER!~$QTXdUpkKX@d@4Mrv?)(2sl!i(fMW~bthsxd>C?`br z454FYXQzvl*>aTKFfz0Eh)`s7gp5P>-h2OEZ}-)GbzOIN-M|08|6GqQb)3(5zhCdy zcn+8*C8)OpEv})bh0-byCQbE7ookh2_q0ndo6co4HO~BGVy#(UHrg}a$JHOmlIJ6*a_GNxo&n4>AB1*W2O!p$+8^+eUf!SS?16bC8MEZ6{M403yJC zS2LOC|0o@w$pCc2aDUz4Ux#3BtavhqqmFqz{Z1-;P9o2_jzX7uXvz~uVs4G9r5PGD z4D`WTIUm&V*Jpk?g*?f2{Ub4zU2wai)OBd)T`F;INa5b`n{s2L3UW{4fazU=KghE zk?}CxwVgdNvi8dd^<%Yu4az)Q?}{6b|Hp@XxUK=D@p6~;+qwPEpEw0+xL}$7*~`C4 z=Kg(M14B^bYOQY16Z@Y(K?R=(>pJuNKdiC-dY*q@k~X$*DkZIX5Sjj$6@vba%?@|% zFg-lW_oy?#LZV;pdl{*C<$WYZqm0wsI@$c`-@oUdWp*{xWjrTtAk@r8DHBH4_e|ga z9vcAPg$9ARa`Wq$ER*AmqHwN|h{gPWG>ZQHjL?$0wt2lV{mlc$KcAAg3>n%n8%UCw z;90wrGQ8RmjOdLr#}NGDKdGsJ~LMfb=>*VUDffM2$Y)!3X=A&OJiaGdP1>m?r7-u z!MP6-kbA>5_4b8d?2Ab#T19_-t#`ynN!fEWgiKU^uT%B?c5+~Ol<`@6<=Gl#1&knM0?5LW-Y^6gJ9 z;`{IZ^RHsV;F?Agew%;%b(1|%viB0c{*;9E(|uxm0t8(D?^XQc!T-2R|Mge@_bUGL znf&Z0|FNuf|1UuO=QH`)PyR1J{VW{)=Vtu>3s6MaZ_sAJ zf;ft^(pX-wzLLTDtw*jJxN9ph*53M6svziDT*?=4DWJ_xYpH8mjVEF}gj1yHRyBfC z0WD&MqBUco?v+$PI-q=FkZ4IpcBl!g`A8WOsIBdDyS&*52+OvLz;?4E&0L7Ugahms z7Fs{LEw)Ws^}xkyjGhd;7%4(p?#~dC1g*vmDOrTk1e#o?2*(qlKIkyk1CcBoHRh23 zdLN^T4+BDQ*{vfCog*}12uNQP$#_I#Rjd$d+yn2mz> z#2Nq)Ly$V8x|U$|%G7$2BO3SvpYIvjV!0oE(?E-E13|euMcq-Rf-;sCiUmi9eSN=3 zjIMII9|T;1#Is~WzEJBIFxWn66kv|(2H#?&lZuc$lC%NeEIphc-z{p8@!4~L%kT=K zn;|*vM~%>F=+YA1ADdeY6M;wJi1i2)YC|!5qOD4>psjK9@XQ!7&(zJywp_RdmVoKP zvwqZ&K%l6(Tut6FXzo1+oHHIYUbnbHkJ_wIo2SBf`dH|t$lXwa4ShTEjO4#ZP4SBD zrqHJ!WLjU4s*s5+R{`RlTNu*Tq|<5Wg^*E~UyM{bcZ;n|+}ol8ph+8mW*T5eB>Q2a z^#t|HW&o|hd+6E%5=M*JFUx-fi57Ws6m3uUDF*1tlimE^?$G!V<5kS`1%foKE(f1A zkS=ZG0MUsVHxLZP!8p}oAimFwd@oWiV!fbjoe+2B!(mdvtC5)&{=4(#gMO(qB6}UC zuU8QLK1WL{H5ppkT2qB>RDkHxIE)`;-#sm1kOo+~^dp~W?U4fXYXCW&MvP+v3*PcN z^7O1?guCGdWO_O{45V=w7@G;bUO1Hw@@NSo_B?Y?Y0E41>nlOF@LW4%>VD9&T$PC+y?p)rk-#wngb&8RidvPE}Ewg7uPHuf| z^_n8{adEvS<%ArK-WNe6~qut7U3XSqec z;^C1CalEEH6>%-EcPUc4lUrM)f0o2mK0O7UdNvBZkHn-IZsN}0UDLot5q=f>6_^Mo3pQOGVO-#mp+~!AIctknRsZg|* zDso+of9xl=JLGWP12RN*ePCoU zM9RAJ%h5U{0;v@K-fgZXRDcTstT2L&=SW+y-y+smjN%M3KFs9?%rUA&CKq`6{Z^8N z{3-Qqz{^z44IitcCT$U_qs1zV!O26Rh_wD%ppi|Vi4{Y_i`Z*1vY63KnMf8AbiB8~ zEWyMovBs4WfLUv#)rhD1%lBlX;ErdfZny*e^xa#Hs z^%DisTikVtnJvaR;LvX1;jx$u#S3nOUNBeWae=XE6ftvqdPp(CiYWOb&y?0tIxVwr z+FGOc+V=eB#sFNlP6G4Y_+Dj!P2aTuK2Alz*zLxK_XQdcpz~PrH0o}nu?-y@gpS}) zf#~axHZ&8#Lu8O9mIYM=RV02(0Pw8Jthd>jaTq7D zn}HBc&b1Z9oq-evUmm~|fuLULkPbytE2|zsOpu)Zp3(b5>XelZKv22{F@!6bJOF7n zIK+HXb|V$lAEVR`5p{9oT}QyXyfL8UD%jR`eUuI6K1BrGi|4J7>^wr|IaD1%3;qeP zgQ=^1DsaiQNGvA!jJ{;)gnSsMx^NScJX!6cExP$tWu+6wWmuHQv;gSTCogZcUv*8W zuxbAZ*(=CRD454YnGUG3r5(4T9^S~9>9z4@dV0FIB3QYp0^ zJrvl4M3@aXkddNZhAK^t60~$2$&>AyqbI@I+UuIbjaR? zmUmaoM`{YeIwD&t^muSs!?_6|@(_4SIYIM)d!dDMH+^$z3UGIA1sa=&oPgp(fVC4* zkahHs<{PBdJqR4ZOHzj{FRI^oB*Ds{ZmHu`RLTg1nxbda{{`apjL)@dJD<%qa-Xu_6@eQk4ithkms-FVJBy|SK*q}kL-|kb| zhTM0#fJ9=^T&(Po?FvKp7(d>YlktsBHy?8Hp%MV4HVKt#lZCFUO9t3*$=+P@mNHAq zeAe{rjT!?76Jj-0GjMvrj2O?&1GhRjjP^(&iuUp!5*G^fBGD)xg|929L>S9HqwUd) zwB~GpmbZbW`j{f0G65hh88ke5C4DPun`A=~d9eib`-MfAy=pmL^2zKL-N5M{J4n4d z#6(^KBg_G%3;WgEU?3F(4P$P5^|7_sV>BHPV2U0!a;Cs>)|krI8Chu|$P8K_R7!hI znvdEXXlUKBp|?KNnq{HO70;dpJ$55riZBVLE+K@8QQ;w1;|3)q-|-sIG!1jfSrc_}(&zA1* zEsCF&p1c3nDp4pd1O@~ah-DsfdWjocaS?ss3xV0pzMHkFAZmqy5kj7 zsRI*`8D4>bxdt5!_m%*b9pO1U#o8!wi^abg%0$+Ci{8o9P50y6QSD@DPs6CG@5e&` zcZIqU;hiTWFHN|Crw;*6K$QXG$#L@O_X-u1vaB%Iv?@ypy(Qe5Ps2#rr3tl~g2(+9 z0`mGu$i0qxW&vMW6_-`E(&YfV@w^XPV!A@9fgY^Uar3VnYpA~Ms*ZCJ1yD4dpOUJ1 zR`xU?*jU?5rv&0=Y%7rVl>xR%@^tb7!(M7`L~Jn%+{3*0kXxSoqh!rxSo>kCVG>I3 zRi|@@yY&i0hGDE_R=1IFrQxjgJ~u5a#_Vfh>vx*#j(5Y7+i*< zmqeuCU9Zt*v>U_cS?Zd?bIX5KeW0G4?D4%v5`c(WaIHFr>&hJ9XKG5gC?ij;TntPA z9qZf@%U)NhhU}Y^+3MgKQ4f_?1r>E~u!)M6ty1PEbDUD1Rezwem-lHE_6#+;Pyvv4 zOpUXOqD}=ISeR0ePo-tlD8kgn83)eMW-`a_Kk^~FC{}zPzKF&yaFqdTBN=<5#3RZK zp-@MSQyH)%wD^nuz4z>4*v~TG-1GV@17(sB%$(`TqACwH!ZQ~@P?T2&e{^f>y{RVW zme_=7H_}g7WGe68qrAh~RB|05yg&nqElVhi6W_QBl)?Jg$Ew0r3rX)45+--O9MVfi zvM2Fd4^;82_j0;jmd{95FbNRvfTZ%;iU_qj=@FkT_dM5PkJ5@cV9q~82&VQij%Eb3 z;d5wAd2h!~iwu4Yu~)|tDG}vygr?hcg&T8P&%hYZf4bw+1 z$vZ0~%08(^^O872(d*zXZo*E@xVcExP^jIySKT96zh*Ki;fwL&?wx7bLF9YO<=81h zo4S@Y`I8pxotviBVIxlUDJ8-|X?&T^>o*Zru%H-$_-9}M#)A%`=CiNmt1lN@%rTje zhP-^NH7M8qA*v$KoVLa%vO%SADlkD%gLHs3gS_D4>FB*6CGP~ttF^XkdTm{qh{{BG zs5274suift?j{7@c`RPa@YVHTh5P6U6dO* z@n8JnTp+Qk!W*rYGOayC!#)Dmpw%*woTZ$QH_3PPCgn-*9oJDhs(fw)&g&Zdx5V@W zbC26c6TUpAc~?e0O}))t?_g`}ZQ64gT~L7)%_dqz0l0*1rvUXho3sDJTCnfZNI9?H z`E`N8?u?;jU8mQ+`o{7Gz6O!-uT&lx&G>S!{UzmSj8yLF#!^DVwA*N z-tz`gFS264BIX0HdTRF9W2{P&8Tm+PE<3N&+S$H4kFKKtpGp3xd_Mj5n?CYa%1h=I zUnzwTLF&_7^yr5lYIDTW~``+CNA-|8|nDb zThz-Hz6YPYJlY1*QL4_DUe$sJoOvcgLp~DAwb?My*fKxb$~PQf?1p$usmI-!CsdLo zzHt^#e?BUH@Lgf7FD>;v9`+$s;3uTV#9qt~Rg$R#(W?96h6-U;yu2HGpeD$D^!hSC zRXi1%1BhV5cQIB+J{}MbS8BsrW8xUg&qh=3W;M4oU#ZS|UADr;(E4~>5}S05pM`a( z%<8QtO~<@+XC(sP@NJ^ee?RplWyDIwA|>67^fXq3JtYs$tfzK-&He_rq=1sPIxhYs zOves1Aa*ueH91u2(nfIUmUxUUy9xy*xA5*6^XP=*^mot{HoO{D&(lW!< zi&`fyr#5j_Xb|P1^9qTpBrXk)xp)7jWUvu%kG(}xMTOtFAW=66bdTye`yBdl559D; zM2Z0xd1luq=BG3bO@;FX;|3KH4Oy{xAS}F;RwOk>y4mcS*YbUF9%fS|g7O(jIhpVG zVV{b;R@fB7-;;_`e`NB95t4ktb^Z^^O}-Oa+CCF%?5EVyo&tiqr1ahyCZFg{w<`5Tb8TV5|2 zDvJ3$RKaTSuZ-CjnGANOxo9p>ZF|?Hraa|6(Fdh(m=h5oG|{kr&)U1Ge5DMW))Qzs z$Ysc#8wQvjo?4Fc2+C$oV`|1-=f(?S#$bYx)RuIw@V3{*`{_1sx)(I6;=`M7O}U9a z-MNj{A6x{ab})skjNP|aeR8?ShN@`TYBz3RY+zop^kU26AL2SfTj;}o6WDV7#Vvs+ zROriU4$e%Mm2)l^CwE6!51vho;#wM%a|^~ys<$!eKE7=y-^>x0A;FUm6r1Uu@Ms2n_uW$V#ZJqJCf@SgBY%$Ss0EZ!dNn*Cgt7U(m5#Hdt=Y-60x{!#bz8OyM{EB3t(980-n-f16oM_-X|1+aGV z{OKRZRa<6Yf88W7b!PR&y$%dVCa{F0d!vn{fpoH!i>IyoKAEcZl#G#2m04RPm7R^J zyisjZ_M$RhU(ni(Jx0U4c}BHGpm019hZ@FZ;v>kCEBeaw$3iz0YY_B;el#F1xEj-{ ze%bFQ~{i=gLYTCTk%)M~#3lHz_7BtE7oEegPM*$ zReGbKG3g*b%4q@YHyTvemU*eHgwjU(ifgU(WRNrYGYDmV9>cS{s5_S+@wS(&`r1B~ zJ`R|>Do_eoAao+mKCN|9b4pl)PSJSos1D;^Y$4KDpzv}X*665YrRKHiaVC#J2u~x6 zO1zEv;J%MJe|#DAkF8NrmCUvAMj0Va#V3SC;#R%J?*J`9&j1v-K})0!_SU8jS_p0$@Ysp1@%__(Acv}$b4!3ljCi#UYVq*@i2d9 zi=OI&f+eSnrsDG7Qjv*ThtJED9Vr48vXdG#w#9cg5JjdQ8YlI2)Y$kwB`H(>*ntcAMo9c{208)MvupF+Flh?Xh8E73$Hq_A zMdH`QkXom~iGwfl^B01SM8^x(-K+_(FAu^iG2eH9J?p(SsY&;EOa`V< z1*y}fMW}8SUE8fe7@B2hd|dRz-_;`heO7P<`Ha%FdZZEipN+^LeiC^XLfuB|0%j{I zcXY^-Ge;`pZv-`U5KJy^x{2hLUDd5*J-#4cz74TSlcb#JkyDmeq|(WsD!-E0d!poG zZ(L;Hu#X9v3K(p$4J>gm3o{`V!p4)ggKepSmx+mOVd@{NF=@xoMM?M5&IKy>n~V~Q z&jf((l2Th`2KkM0Lb^j$8D1!+eK}e-EEq{fq}Kb2_l%^g1}_B_tr#>PHu0r*Z|K@_ z2hu!jFRP?7vv@P%w9cn^uA)-dQk1S4rT`lHVu$&4ZxLE>#}0o}@%StuDtUSo==HU( zpcx&Qn;)-gm9CCSE>ZP(R+#}oI#1JH-S|yZr$07MTC3M3H6uPxz z1H-`A#Wfdr)O0o8Mp>=qc|4|BGZ#YlSEVDZ9Rs-s<3Oum44J|wa5yP2*!x3ITP8xZ zU}TpOUtKPo!#A)O`(1*%TgotZJ&~V+rOKQGNQ{^hRQ51HzL0TjA=pUEXI@fDc)xq0 z|5baL-`<%dn1$?;J~8NBC#xtx50Y&gEw==(T?Zd4z4kdSGaNNL)L?1($jUtzp~ck| zG7CbHAz5m}=59wyLY$q+<*RRUOeE`)_;=A9$*`)*;^mVa;at@RTrk8G=!Qk-KWv6>2l3`J5Ub&9;V}IIo&~Skbuo(@2~Vd(!<2nR z!3z_Ipd^X^93B7tCxS1;qwaJdNH$C=!x5KU(c;}h*-OOeQxytPDWPM?3)lOCkbH(Y z8Um$o4Zq!mi3TR5w+PHYCLRJwwyG+DEY^#6uQYS+LdsjLz>0n1P zxc0sJe1x)62zV6qvq~o22tkfmiIwrWs)@s2^g@AoaAN*!+OnqJH|foFgz?+$nq7-_ zHt}Bes@QO;H@NJEp@PqpwU;8nh-+gU```AO__pm}xkF2#QivRaK~974c61AJFM!6G zZS_^UiM*c2SOUpT_J=RKp5DmVIv>AkMD@1a zUJ2z-0dA$u(>%LQ!E4c1E~7}Ro5tbV0b%3~zKXXZW5b&pYzV)Ut=85Yn*uT>N=mAm z4+;up5%yI_b*ANucc4*U>-4j*%|pEqKE!o$iiqk3e1;X-iTyifGL&i@{@Y!l91335 zDf< z)#8>YJ{!kkyhuVB%4U|*HVlLkHf0eukr+&C@A-3{mM5SPcequA1 zSF^OM@bxxLGpuH1%>3Msyo<4K*6ZhHy5fU4%jKPN~VW@!nA=ZJ{(tfD{4zV4(@Y;FY-&CHd zda%6`G*DDZl!&i@Ex0ZzI8`9;V|2}t!o5&|a)W#by{4bO)!YZgP)9yj3Lav~8s^=e ze(7-BwFZqyxjV@c0ZCeWmVh*p`c@4GMx!hx&WW$~q*)>Vv)a2i8psm^>BW||?mqM^ zi!DPcBOQM)Q2GRQM;dIKw=aaQ9IaDHv;*yC#a%NSTo;g6a8_PSQ*TO`<)?J4F?n)A zP8P;tGJ)qE9QtXNPRNF;E`05=SGM;KZLYmOjw zXb0UemTkiyNR>4$%To8rCyqchg2_w9gq;Yzb>2Jbp-)g^BGuG}mpM$v8}V4B)lgW5 zoGx&vQFJ3FAeu5$w5BcVq8S-X<0}~qVJ>=#mDH{;69`z*w}bjJplCmCq2jaD0Yj*^ zZe;8yxePOBNFHx97sdqQ?{bJ{=G4loO+vZB>7-gvSgKCvI0~h)TAdxVFHDTCm;O|} z{)hMLE)8P;fi{A!D94OIaE#Rb&5%^Vgz^*Z*IT6&*7m5=kh83wrVo~ygS15p61mVp zy=FPVdS2TBNho6FpC<(;M(IX%nbZXHu%QuYnHFN3nWt;{`5~@Z*J(7mB9b0rljSxt zLSyx)el5+-XN>N96MOM~9HDPPAdE`Xu!zm29|?1@rxOP}cug-x6#)z(VI;L-c4fE8 zV8^B7rE`#$by|L!J4ND>CUbMsuXZbnxOG-Qqs419ls?)cJR$D=PzmQ_a5Y|yC(&jl zDOXFqAYnoDm2nGDlGNH7hH8;xuy>>ZyHPIaF-DDpFBye?0!)Zd0H$b-VnPFULQ->! zIZpM>!qIi0^<7hBV^5DAqX`s@C!*d#lr;5D#QL%U0TjjMR2~KkP|o^PpzYkmiU|pE z>T;5Xg|I$t_%fl3!b!7_?&mf9i|M5IpP-iF|`GC9A0!a2&ho!ls~Q`1Z31cZ&c$J!&Ynz`AGkzXj4yifuaMLi5md z`I2Wp4hgA|H6&jW7)1bC$jBk!DX>2t@?5M?EE`HcR25J$Sz9=U)+OiV+*LUaWtVh7*G4m+X*L=2fMx=TGjMnsc>R& zwDPzO42!rcFdjN0FHxdadna$g(?1xAa~Vs9*FkUd!)> zbNnOgILz_asxjNh3Bwe;^v#dys zQL;*I5Hbb47^hIyKmwKT8n`Ra)eJ*qEj?yDb1pJjvX0}z4^i}I$EDT7aopFVGmW=m`wQ3tIt+L?SMScj@R%5kX; zEyrC>TzPhN4)5KsFn8y14LKK#nY~aY%atrPCpj<(I0Q~7?H638&@}f-N1}imEPRFZ zx16q0mrk*6h^t>h-Gy9eQ_$N1%d+#0!fXy=B9?VnYWwWf@JM4Nd(qWKK7x!u9ZFx5 zA3&ycIm?YH~IkY7Y5jw(55abu7x3>FOWs>WaKk_Q!hKG{6~8I(_Z=_(Vg= zonz~BVhZXnBY_Njn4FDdLl*MMw0Fy4*r0}wk$acVCn+q0TlQmm4)#z!NYB_~kxf+; zK->65K$YoKd*Gy25p+})NU6HRY(Tb&Ta^Qv#DfqKupmBia##I;J*;w8vL!uSzm?))-@b_Nr-TkD`u2)kC%HXu^XH?|{1c0Pq&3>U=@YEDGFb!zZS&%>{1-aHk@Q2s6@!G^Rz8PJs6Fbn#UW>ib1 zTY_Z1bQ2c#zWac*(Ewk^p7MU5%u*aNrNua&N9cwsGBY>1adq%@{)DMV=Fuy;P+2Jp z7JM!=_RWCeFq*uhyu%ph1c(~0SGQr82eTG8KEUbph zf$KlIUg`4R>I1~2x0$D!+S!p>zhsrQ$Ca%MpIqy;V;_yCJUpS}PHuqoPu2LP?~E65 zG^|l=jwUbaRr2|v!lGg42i#c-V$ zh7-?@rtgi7rml{Mwsg?6@Aa<$8-4_DD5pf%&sFMp{OzKw*Q*dmYe?QWRG^m01`e*3 z7%O)7e$h%VC;conF9L|7ZW%3a)tbN2A*BIUB_?(!Jy|2gAs_GCs2C9FDk9d$$jQOU z;NpYV^ea|Y6!4MurA%{xnJ3%U#WknE=!m1j8K|2wa)0QSeD64HZj%8vXYx{VTZz4I z3)I=S6Cd|8xR;g`$;EL8k!O{!n?0hHLiBakH9wjFt?Cq{!$8$QKD}m92q_So)4a-# zUZiSp3ZLnhvIBEB8mZBzRSnYk2XyGFk;hZdXU$nVb9NC^0Vt&?oWamO1 z^~>JT3lLO`O-+GRO}hG_wq4O{EEvsub*bc!5r-iB*J` zHG>Fo{62BYRY`0DIPqs?W#CH||bg zOR@WwYl;SWAe%#2UmIUH^pb2yA%EsN8?S?*@ALVi^KsZFy>$P)63*9h_pQnTIV%RF&y60v;AO4bP_JYA~{XpbSLh)xT5`6r@xo$v)&Cw_*#^_)4q9t-rm! z4q;s$%HvMTl~ZM zz+~s+$SUDqq6tyRbDn(@A^47V=po%_@K1#|5LjSDi<3WIOn!6~oYqd|-MCTeu{M1q z4y?Z8%5+o6EdoIe|CafuQ}~)TfCoVO^(6K935ZskKS)>Q($oZWAeC^uwO=o0C-t&k zP7BiQm9S00vv1Zsz=?mL1^YPdj`F8d>ZIFt>NcsiXCF@laQKE#XiBN`;#HFG5h>|>CRDYl^X_fIih2;CdcNBDwx_PGn*4$v@G$J%uyz-z^T_2S z$=;!{hDIj6FU1|l9r_-v|J#-pk4z{A=;0Gj*Ot_DW5o*ZO&>s2 zB$&PFKtrfHtn=*v-vUS-4-vN8p!+t)lS2K38dY`PyLFUSRbWy+f({L;b5FWX>l|XL zij!1IvZ{)aJj{-##gO*DBvEINIvCijPS@vS(gtPaAc*$KBE=I^!wp4T%0tF7&p2g$ zo$e2*mYvJEy*uT#8Mf5U+9u5IpmG694&TTogwkV?4Sgo!1Kl4%YOlqv z?9(_iP;dwlcChjxiLx}+W}9EF65>r3yQ}6op{+RLQ|akBnr|(=+%3e|uLXmRQ*l=% z{fLY#FzPXl<5|d(@0J5t|b|s_(a>}J1$9jg!v@> zk#BwK9(v3t4|Oy&f}r&XpdKoTSkiOdVW7yH&kGVb?3(mPDy2bEx(Mn7hv{VHq8&fZ z(j%Yjh^=e7%oK|IXA2?ic;xwr9WH6JWL9T4lMvMp-&K{zO+X8xHg3z@c!$_d{Kf1W z(A}tR$w#i1(7wll{+K!$w=&Tq79zy+Cs&h#T%}B)*GzQBmd<;5r$eoc6>!_U=<*|G~ET*wW?`OI4 zA!&b;|GYG*gcmpq2AVXL3bCIrq-^o|HjHMTWap7izkdPurdC487-aw0{;z~?Fk58p z<^OYOi_=nrio(l1jb{JUU7!Xb1JWf{*K;F(vLA92#T5_xvU;bOrb+sK~@ZT;{JZm33H|2oV>hA}_e_qDle?_uKKx_iH0c!;Nc*nDb%3Kkon5J^lWP zSymvgCCioPfB(UMdqm&gR-^`q1=z+{j2iyWLLJ&Y8yJ zNoR0`*SXKUF8?s-tW$)0`%C}f`}O>AqweO%CO}Lt2IMVc=!q#BKjhw#+GL=j@SFQ= zk-1(YY8@l6{Hfl&+aB+}ZTF$CYSG5we?5|1Psjv_U1#!sq3+?X=PuwlEA16-g`=~c zuO6IMOY^pG=$YOb5Fp(h!4#r34Cq;Ngguo>(#XCPz$ijMb1^6?H3p_OBnSWXD%=G@ z5heZ)uj@Ph`u_iTNg1@NmSKJhD>fJNrZ}beNS6>{E&bhAdYkv$nut#L=V#po_rL8i z4-?s2f8=*7;`=AYPJ!r)NJL)VZ-Agbeg|A|+BQAGUtI9t{;Ey{$*c5R+k@B64{!Px zS9sM3Hj(X|_?6$`82|nIa$_KR%sY>b1^@Ll{(Z?m{lm}|SZFnj_Xq#CO9E+?`P8x_IgV?4u>QI8xw%e`W2Emx+Hl9O+9myZzAh9w<3e;oub<9yavMb@*t?Cw`M@8o#8cDm~w zw_MSpV9yfAMnX(fxn7xP5!0HqU_vBefBT^emlie`+q(E1M3{f}`V>_nD`<5xhj!!A zYmQDJQAR*=2q3%iLBNQ~a2eHniY|mwJ{oeM#I!ca>OKeX-HHPI8!vFh;v||7gqi>p zlpr)NZtHH<|J3HwFzAn1BKzfpQ{vKw8{$=#x|!Bh8_rN5E#En+1t>rW&ePjdSEous z2oIH-%;k*rH{Oan3rV-mfe_c}g6iOzCTsr_f604$)Lq-be#;fHgiP7Q>gh7;tHD5k@K(U}WLMcO7EkA-$f33z=8B60!%;3fcY zxow~i>=S$0Nf!Yf!ZXBa>I)Kw01h=A1ee51fVePxk=JPtui^CV6H5~yru7;~q%Y#Q z#_D4N#C4P;;FiRlc2cd+Q&T2@8tZ85@?%@BHOST@5S3zGjA=dWGEtazKWu1m`+Wlq zPDx)Ziti4-+S5KPn>DKa^XMEY3p;LT=AELGIubcUB%BM>g~kCLffYVOmcY}yU5ZHp zclJT(?o{Ew`qeG^gw zGV0R=bTo_ZIdJ;$Dv)~2pV=wC@s5fN;P1N6ZQhoBZ!LchY&oSRgknBg7xUxgL?)70 z&pj8yP#Te5C*=Ml!K*^;=;34^MEt-T9HpIz(<1F3{de%$q_dvi~4|M?4FCkQC2^O z)5N{1jstYKWtV`PWd~1H6YUFWz=fu+-MS`FnRqKLy&_reid(LoB3)tW9(7yHw(o)R z-%)zw58_QId(ExQ>pPVCO?z=;Q>F5piKGq-Yk3?!=GhKm`z>Jp%(BMQ+g2$|Jx! zdJcTQ+>J>)>Qf8IQP5N_guD!8m<*dY1U`>VeS6-=(SYfv>Fy|H5@ku#9TFFz1E%uAQ%KI z_V4uhJ42Vy-J<`AU}BRoiVTptFd#(R_3`h|=dO5!!?M!XR?)n|oO#{Bjx4PZmcluO zWzFK)pM`ipUd@x>+Y*J`kWNTzBx{@17H3vGi<%xbZuMbL zy;P=QZ0=U}Wb{V@ws_d~nIWRksLj9`TVA&RlAgG$qXST(HAB#^7z7%$XLI1!Dn;A~ zqxia9<@Q|ZO|@)sDj|FBZ+q(%sdC5dD(+h;$AyNblKx9Z%)ky=&bvLuy~Ee8!&+C0 zP<8TEo4ri8aWMXSdA2BB@AEx4xN6U0D3)eeV``Nc8!d+R<{)VK|M)ik{gj9o;I%jj z8`(EYy90zSE6|AB?KZ4~6(xqhe`5C7>7hoq=+dGT$GPdb1(ix!Ga@FFvo-mL?Cpo8 zNSa#+`Am~r`Pf?u66o=3)7Qi~OT#rUde8m1)bEHFY!{xM5UG~MeU1vkPGhpKrd0_1 z{8~wK!^M-6?6G6_i$``|2^V&l+ji>U3z2g69FM;P)MBmOQv$e|27EMBEl2$b%;c&>n8vp)YamSa_Rlq|D+AXtoGw8a6-zinsts6e&B@hSwt|?X26g zbr{w~gE)yW8fhWKjTv{rLJ%{sy=0M~9@xkl^LinO5e29Ve70mrnFIvmhJH1gbPa-+ zka6>=_x7uBzDiq;ATlnE`pp;VD^pc5FwiuJHjpFyShc(FbLZ1O6eQ|A9`?9>D#YoK zi^9^o+O-9Pw@H&?xjEhA{YIPfr;Gx}8PdNzOfQ?CGf$r`JFym)B-opE$~7qS92~zc z<0pz_;wf5R+Nd;-F03zx=daJ%%-{DR4A+VVl2rmh(I>S+vOmDoZnoT zq{lbBx@E@9=oVMJa_h}$mSrCy(a;sy+{Kq%1eYf5aM8t^(vwLe)*i>b5^`mi#@-c4 zWA|vi`nZ;9^C|Rz&T(kc!`u zNebnQFTi|%4bx;niM?l9X!b(^ zx|zg}^yo|@fw!q``t`!1+X!*nGpe%2^2rN;Nk2xyc985N$Sy^rqLH~aWgq~0dd z{F5&alaRRf9J_z#PEY8Q8^@#{9zJJPGck$_E7+gwWN2q(SYH%w6cP3&E@^CSmVN&2 zc(|2$mbvDW2QFfEV^f2+pQYHONSC-td2^ebQq9K{tMuho9mKch*I#LIo(ofSm@}wy zP$`XXPTaNUEha)xxh9<7SfJMB+g$aq)zF7`6Ui@9ua{gsrJA2WIpVZ3NPDr=$Zm9~ z%sSPk@?_pAyuQD9M<=nhr{6uIs=Y&5qo!dq#qqTqqr6?W^WF$+_E|b4_KSaf%ob5~ z#=hi_J6!i>sVRyFUDS9eT1OYn0-f9QWwQs_rn)pDq+5I+btpSb69gm=Pk)+ZR*vx< zC~{a0rp)|O+-vrQ6Zc&UfSEetAwI%&zji_GQqWobmVWjw$=mLmNXQT0`Nx06g+bMx zR*uo;hK2Q5TaM&_$#{D~CU!u~Dp@t9WFbx^IUFWldmgi?a0KYHswA<;$c8;m)X1vz z+(|23&cHy+sZEt=Y(z7VXEXSiidFH_ZYI$~z0!{A?_`Ud&6M3GD<&Pa-l^876gJq; zGM&-$uo)zjH8xo0-#ZShE@nV*Jb{8mV(T78cDk1{QG+>+i5e$>vi}rZr7x!&zp}2k zl%nS`ewuF9+W1xbBjU$x&M_zEK5%78SJ!zP;@ZdkK1Rnd!l-|^(0MU6-J(OAMJD)$ zlbT8rC}I>iRlSt(xv{pgs5qR~ptpB3>0a?o8~<@%z(l@?BinyZV*3%@l8cX--E@oC zW&~s%yIYhFw&es;vRltIyD)Xc_)u|ZwST?aAyK3Fkt;BCJ@A6X(s_2ejs~&W20nvjz`7+t2 z`n~OdY!WVUuBq6=B&rGETig265!3n2Y1Qk@9@C*83Y7yOpHbOCb@F=Kt9#@5F5$Ks z-_9CT-lmuq(5VM>vtI;t|JBH8{$$EO-|xR(@?y8whrpdiuSg#qQ?nWrG0WJco+%e@ z{`qrq1~++Qvc7&qsdMf^mAVJsYYFKLm!6uh;U^60WfRZQYFgMGz}R zLj1PeLo?$cz4a9bb@}73zi2*F?Y6%5h<_^L0x+9cl_!j=pZ z`antsYgVPWW7r@Lo=hq2G(*2b!nd!=Mu=hnr1kKqgg1Y5j&qZ-7mrEfQxT`R>=~i< zFUdL`Z`S|^B#}im*9aY0J=3&dZ1E@vp|#_EX0o?R6)lemMI@=oy`(zPG7{zANmr~*v+NA;*{lcGED}Ue3#XfiL74-$scNyTvOWzQpgM!)@+4D=(l_GXK z?p>?WEX^y>ReU!+xGCnc)cm-W;|Z&^FFI$F=9jI;$Fzc6U9P1{o4uLSXtVj1d$wQf|5^_LCsJiDdE|q>9eBD_z@PZ9NJwLHeLqfYQ|^ ztx(S}K2AZ$eVR2q=gMh^S1$@-R;ZM|BUBCh?6j_Urn=0-!|vQT!ut^_?d2KOg5C3+ z@mq-fIYmv~cT=L9XQ5kIdYdJL*UbBXD-8Z`EKc<@CaDWRZ}?uSY4ceJ09!Hl2^H1d zid4Q~({Wy<|1~y9cB;SDLNSM{b!)Q≪-;v`onT^@W$MdyPIkeCOa@WunEWieYE} z^i@wKi`Es2<>R30fR7RH|$&?=|=mRmH4}H}k5@t44?eJC2?LIXzNA8Hvkk5=X z*OS|ucviz?UkZ|TiDFJiMlvIbe+BK$e47&m=NpD8dg16bXO?%PS8mS|?CquYisjsg~P{lUEZn*W$QoD6t-?L{V-5JY7pU4@T50eUpy;|nBthyo!D!?x@@oN zIfU=7*%A}L=>64@&!JM0F!M*dBw1c3{n}&gCqb7XF%Xi=a!xGDo>OY=zsNQspk9{C zS!uMN=0Q@F(q!B{FFF@oZlgD@+xa=`{-QNS|FLDFm3i+H=j9rbaJLS*=PZeej?pQD zmiFUq_)aY$Z`Ul7&yxaad5q=X52C-0B>2<)VQ_lyTH5d5wTdGvz|}{81QSAo&JxeF zjx#rzkG)XpfH-=XnpN?wNa;{Rycyf-pmMDHO^4||iuY$zjQv0W=wc{@G>W9HH6tYU zbf3Ol)qzu8W?YGF7Ksiq>gQsT{c+hcMZb3tw_p~P2M4-D=*Ef zcKn%*d@H(h?^|Y~=1tS_mJCa!#pQ*FHO{V5%E7Zn)4KTKrwI-_KE!J+eR!2Il($mN6#PSGxVPk3TA)|anzo^8~xSo=Df;dsNwx#rWMfeU{w&+qYQ z<9`nqg4mo7r<~xv`8Ta&YXD+>>3%ZtVt?CA*0%`9p;P+tXy*v-amXKQh!4`tu_}9| zBSeUivuGK&FoLMKB63W*RwqTzGbJ#gn`Opf7o3dThx-$82a>h&?C|w~jMMYbOJM1# z48+bnZ^^j$VBZ6CIVjOM>Fc>SW!?OIv^&^`mXiZ%m zdIgi^x#z3I+r57VsrPJ~6T|1u6ZtXVX=OS z26H6BHyp#GV~iPH-W8O}6F%v3nN^@ZIs@EDA#+3Flwc5sOy4|&`4&lqne-^@LQ31yHAWKQ z^!#*I__C*{g`+R?UJ;U-%|+nxez4&jKw``lCz!v{iqv|f9oiYtrE|*7Efk(Al3$m?;qeDe3zgSh)WMF$2+==*Z!H0q_k{^Rl6!nJsHe0veJ2|_O zi?NPWR}?dH&)wa4?x(vaa|i66L^+NRO{-9zE<0~s4cG)#=RTrdL)@V9+w@}c0p*H3 zyHP8(1l!?8j`4zmk3pOfH={)2qZ?*M)Zg7D!$f4654XOO+LKrM3T&8zxug4=B0B)2 zWhB_w{v4yhTeYdTIn9U|GtIb}R4=l)wWOPx#kS>J77SS)+hNI-M zV+%&hTGz?9FW?iEho4kO+)a!W>GGlq?HY_5x#}cHI5ASYgVN}Ig=YO>81#vCXEsXI zC6wa(tKWr}Zx8KrikH>y16moYn0{`W^Ecxk-owoIi?<0QTBh%>&2)!D6A9rGtqQ2> zH1Sy(?ZbE}g;>Y~ImjnHwNeq8FXd63R(3P}fPFXGO~aw0uoW$AFRzies1eGddX<&` zeMeING)eqaSFMIcOL?>~P0{YiSOwq0Aqhq&0@_8}Up52ig%RBMKHPCr&D2n}Yn*RO zl=mlzH~CgdvyEO%GcqI8Fle4Ft5^?Bo7RvTw2ty= z)|nrWr>$()4xI15fPTmN-eggc&}5!ne%>u!vwf(Z&+@Ah=K5yig zs9rYAx9I*oSg>>jQqVG|rnusIm$m69B=j6QWyUVm3a|JMOS$iam}m<7k0F4oI+@_X|8E<9F^bqxzYW7TirW@)0Fr3V!ejJr(pp3r}UZ_fydrt z!^^)d@6RtJlIV&PYtOked)~fqe8oB0xSYQ{Od`Kep}(PkHT>RC&s&>wWiL^-jZ`|l z*@K>soy>=4L>_lnkblj!NKky9tzB|nX1zzPr(Mut?tN#Y&3etv`lw6UgFM;#NL-Y& z=%FJ&&b{8@bFamB6lEda|FL9b7lKgT(cr)weqg=aYm0?n6|us-lKA7W8*cZU`ry6 z-;`rtHK7q?ogrsF?J@+XE9EYdJyMlIFWOt-{7oKv44={r$B^&7XJo%P^yA=AxCdELwCyJ8;Rr=S&Vkiv zaZjj8F;cBkb6r);W9F|f zZKmijA2=_b{W0(WgJj${Ip2>+|EU(2$y_us@--;jnxrlwv@^DG0XWRkW9O zRkmCxi*h=G{epH${?YSFj3u0*E5CoHgfEfJn5QgsnPp*33Od+&JORt2k!uAhNIC$c=DacnRtD>ZiK5d)1dMkOZ+Z4Kl9=z` z@EV5XfEm#C5DsmjRxjOJKPo~84(e~`N(Ad-4LSShy;#Ncr8%uq73v#bFFRP}WHF+c zG;gGKj`2ncEv`gt1?#nhGT(UFl$>6#nv&usR@*n2EEVzayBPJyHsu2HUiYc%KNpjt@$Z4rOX4f#hg$;IL(VE*KwIeqUE(h@sW;y=kUc55 zi9H#%p^{RQpj>LAc|k2N#+bR-#CwO8mf&?SxmM-pO{+bIGEu_z0~xQxez;62eG>`x z>rdI+_Hx~3bX}iKQj>|ryr|7?hC!Y$e~q*z;?dSJ65elkphnUp&?x4E7D~!FcP^(w z{X0-1I8XBX&bv;0*k^aa6DcG2DzLV&d34|U2T#qeP^Oa=hQ}u$hj~=Cw03^eu8Ho# zu8QR8CYt{FOG4TFs(q_s(K{0b={DO92B-<{-iQK;P@UWwyo>&;2$|>aQXLVF0c|E&aIZ-ZY+YZMOixkUS2g64LxXM}gA5pezZ#u`Z zYVxQNFt)l!nx7abN&UQhbo4dy$QO&%20J890w(k86Z-tP3R3##XX-;v@V{cD-l4aw zS3GT?H>_ADmZ4U<%G88at@pSxZFhY3oIt?*js+D`?A$?}A6_HnD`G&cCX#6gv$uP4 z^_NH95(cr#hq8pKWZZ6rP_;|sN6pS+7#E7)fDeetUjrVz!*0yA1zMkHg0>SMplv1# zl)|rT*-C!J1EYw)?q3ujaTDV}+;@o)Xt>GLywV*Bhc`SHI<4|5_6GpxMJB5zAR9R(#B5P$n>9SLO*M zQSu>Yu6->r&ASt;OJ4J~USs_Jm&H#>j(qn=s=SDBeC9ojCq2LB4wSp9X`n4FTsVY& zz0Rwoi%S>&0I1JiT(68CpP$pzu`0FkKC6Sh__nm_odLs!*wpaxeGcX!Gin@9#QRrq zWdcXOgFXLPxQwsiNW0QNzoD3P_hMdGmbP%7Wq$=gb=TnhGRF##962L9;&eQ@62S7_ z<(&x(iW7Y1Vd1)gZd4Ch)v{!vJHpe8x&W-dhAJ@(tB-#GzE%W8Uq1IA!Fv4uN2}CF zCf3Ys?rd2#YlmeQTsg@;P0+hc{UZN(-iPrOqcRSMg?V~)ZUdFqX{+?R`smm75$bIQ z4by8P*Z&OG{&CfNkR#-jljIfFWrE%ayAwioDRtWr!IVM0IMSL;PaBwH3TN`OfnxVz zo%g2EMIE|D_wQa%%Zf4|D(hV>6mpn7uTjfsHB^=~>JW{#9ONc&+jo$GC&_-QP3rKu zz#;KdDQ(6ZHOD0PAn%Y(8+;SeF{XWpkVM(>cDLw!+d1Xq9jS?Du7zFKnQN0_5nGAJ)NvpB*PZO6yK+_#&H?|*tQ z9?@F`CFIAF05OVksU%{XkB~QM>O2@SD=_UG1CLCYZ4(J7ewe^>l+gqo$d5HYJN-D{ zr2W0Qsq9w1T!QurpQWR@O5OZ$<;hNF0er0!;YIRg6(hbqoCMOEMv#)<1K<5Jbi-~0 zl!pcUgh?+rb#;_q%N}}{71j8AeTKXPEzehWSGI)3DZAZvheT1~#WXvP*pz&6N2`_1 zMcZ?M>dm5_)0`-8WSD}bCH2$QgNS$L1RR=h;%6f0ZE>q6d6o%^=_Jzl=Z5E*xQ&|4osYxe@eDxgV@yXI zuiYR7OLkatjEfvKht{#y{$$0I*Qj^;Hyu8*v?TSflcYt9IJY@muo^YoC&Tw*s-kOi z1v^-Z&rNbcOQXx?dPj@nH#CHa`U^l;9??q~3ceq+AAOB*+v=h~8R?37c43PRj~rpX zq1R>6hjzm`weRGe3%Z8d6)_T`?rjG69cP!K*hzd+WYL6O_nau@a93Vw;VA=Fxle85 z?xKkqFEIuozAld|)?a>-qew0&Sy(J=(nY6r5krT&bz{6MEf#amEPFIX zaN&z=LHp?!<1aq+OzI)EE~%!ew4t-N#hcB%7QyEcZWQDEK83}8YuzH;Rk=M{*s%ea zU>0V%7r`K!lz9s4T3sXG_|VeO^dnW-C76PVc>HD13Y+Bbe1cy%u9Hh6u?4lhG3@#3 zM$oKLjU5+6MaEc&HUtgzdcT!tHO|O{EeD)^kQzr+s64i5H)f>!ipTW|n@>@gJWf>5 z0B4HejbI^dk~;b9;ewaLs|%HOsWoW#&QqJyYuK^bCkZ-1j@OI6Y>0b`qshyng{O*d zd5t<@7c`K~nxziC6>?=OOWoN{C|Ae?u##-Lx*Ik_K67F@B3AO{!A!jSLNr570V4N-@pUvFz1;)WcOp{~er(vv8cjKfq) zc3Vrs;?i6N_3!AwNF%5kbEPbA-;P+SB*slh8mxwqrjFw&7BC^~UCGz#LX3$!{Xk})|;ZRcz#YOHA>?fJBru+0UqNZNv>SBs; zh_FD3#FQLJXBR#4u9R5(7xG=^%2Mt)jEr)ez=b(7$`9joENz-Hc*%KC^Y*l#&Pmg<$>)6%a@Hk zKrp;^OgB0Md145!B688Jm^nF!p1VA$3q=u35cI-YaA;HEytq*_cAWRO8~gL?h74>; z6(syiYxR$Z(IitDFD++)2T{xI7gI%Z%ng>Jp{s~wRQfA}#xMn--k4ypO-ko7$2QEL ze{@FSWk(`r^COU^V-N;I{is;|NH%m}GJPcU#=aV%=xs_)%@%y%IJdybiDeD+bC3$9 zs-zXjYX6e@~v zPF+i)Qy;6{XzxeDSmiU883Th42cH4|{rzO2?Dq4EmwXNCS zyzv3S6*6kt>UK;frv;oM@o#1GlEle{ZouiESr_~9+F&nh0EP|Ms5VaTLhboREe861?tS)Nrua} z(xC3png}?4CON1C@vuA1vy}hK`i4NJG}>+Yc3m68@LDAMrpXJLO4Yg$l(Zj-cxGSx zwRf35A~>~e?wj*3zqUoM)R1I5hWOd*+JRVPt)P)+d@(E2=4+K@`^91MPfYc47@k5c z)(+IAM)JEq&Jdl>1T%gW_Y(J&*=WoZ+CQ1lJu;*yzCG44gX6vyaz+{GR(xsuf<;x% zW}@i=DCnsMe{qBv1PrQu_*55qZ*o;1&0_7XoaxR+l|dte_2<{6c_ZRFiNMaz5hSwg zYe8HN@O&domtdajE4cK)eZJA6C+BU-dQu#JDKz#7x(0mxYec3-yqE*~F*6~QRd<%Q za)GHTKF6>{4`)L@YCY;~O8Gu*3M-Y~MsZSXfK=3!7~s^<F(qE^UxBe)Ix@UA$$g7K{8Zu?cNoH#3#b)*4RFs0$FM!_w#UQhtlm;7au61%Ab zY?&%PT~ySo$9#F*)~0xv$WIzfFs-2GK|y_LVA-^(xU45?opzDU(ki*bs3v_#GXbP|7I z+~CDsn$|t>;tD9EN69CytzlouPO^_fSgFB^Ox{ztDyq4d1W{B%gQm)(1xT7jkX#N16ugWj-;0ER^8-R&87CEFYQv4TkP1lqrJoC zE*0Ke!}jEs4~J8=*KOJQa-p?8y0pD96TcSC;T;J|5)-FR!?t-jyKEk~>*YF9*zfA6ha|Je@L}-)*>E0=Q zKapsA73FO?b0RY7Z9~@}PCj>8RpDUJe$=IQ@`NM5786K;^H6R6BBo;bCy)ZUhxE&i zSR=?y`-#DU4$&VrlGyv#@GcNe^@R03q#?#3Hp59$$I;S zOaJ|`w>+61h5B{BwDZ~xfuEWYWEwAWaxR7o2IlBM-SyPef?Xs3Vj5Y=bsN_NRT9M* zk*Thke$7ES$CZhX@55Kt13=$3@0b7JGmKan0}K5nf@SsO~nJ6Gt7 zLG6*yKk5qmG4WL>5Ux+sQOr9?(=R4?)~#7Y?10^mGr=IDlopyGhC*?4 zn(B<5uo^{aw1D*$AZjd#Lh`F$dQ5edcBVbDI{AV(UAz&;v!U~anw$0oKBK!SiZ5}c z6M5^pDmUM;evahLtah00xPb4}RrZUb#XwOjX)e8}ONWyOzFGz(jTR$^?&!oKN*yff zBe)WdpLYK>T(mMuJQ8DBm3mhfc_29AB7jY%jG@l6l}!j7g}!jeI2d1sd2jEWE7hei+-u@;BvUnkAYQdNiW^T zfD@Q!r9TEN{#@q&2^;bq2lz#AlW=VL$MDP#lZCxRpMCJ4{SsX<`JZn3Papf^Ye3%S zfWQzYF2Ql~KU~fae~-};uTuEmt^Moa{6BeXX97>4-)jF6RjeiNG={O`2Za_{UlJRr z&C)J)i>N*Nk1L4L1ONU{Vj@d_M`4i1*n)vZ_DvVIop=g(5-|I2F3%X5Y7<7=S0;4+ zX(dHo0=}+s>m@MyjMLUxOJ!S6rGS9Nt6``^#osk<#xouonGGmGtjlO2`sJ zd{nl)@yEuDAU9U609i{zx$8#LIig&&S$7t*Rw;W)pqMEL|NRks|MB0W`44XZ;WL>bc;wr|{{Gv4ERMf? zY8ZqiHj`ujTJk^hFGf2&mTdGf@*gA7cek8#l(EI=+PlBIiyvHO+!1&sLT1hXf#~|n z{e1hfZ#(D z2d8Uu1PDlpuEJW8IHpeY=bQPrn_%SIKTzbrEB$aYzI_&mPU+a}E04%posUPIz+W(B zgs@}Q>U5_(Fc>3TN%VnU!$5W&|Lkvpv~(S9NK+$V$q~Tw?+V`eglYhB)?S* zfQORMCoaghJ@ov|Q=jb_bpbk%!D|@-gbWX5Rci=1!SAM_fRFv%8jO+};Stc#oqutLmAuhWR%h z18ysM2O6<2Lor#ZHG4Wpfh7d!Q^9&W#-`slw8Pj`nGIvs<>k_+Y zTWHPv#%@Y^)U5Z7fz4bWZ~NNwGuQO`PWIlQSh8Oj(&n=qIF`x`q7NpZe7PzPpS!_^ zS4{#lbq(l~Qw0qBK;H`Us8@;WLRJ4hi0VC&$knU8N_b`|5jTRL|z^m-=w(96hkJ=5~YY(iM=2U47!Jj(ayIS0hMWhUlx&QH4`IRV=Cjhv@asP^mK_2+$i-?|ro5WIu z+N|yMlc~%ZS{|YY?7<+zN(Ig7y^k+dd1OmWJJVuSC)-=1eY8N2YV53eQ2c8SkJXSC zR2FAxCvB~uNTDFdTWc=Go@F_GvqeWvPJ#gn^xtmYG#gf}uTSwD0rIF5IPDCU zKG#a`u^cLMhH}JoJH@=%6}X1e0>)Gm@{!z$t25n-4huu!1H4nTE%U4+7zYpJ-L!X_S5%>)~}z7 zw3~J)gSH4SU^U1CH6Ute9Gnd$d3;TeyWIc^8aErPhE1JYKYc*r;U?X=7E^mD+3m{Kz6@n*@&hcKCgW*7Q)G(`G*+!9r{Opj z9>aL~L5~BumX*kn#cjnvCz5w_KeaC;?i1V1DA5vFt5%^ThJmk;g$|0+Mk$VTUF=kwQBMAX~e#bx&$?gwI?B@Z0U5j^*EiIim{^ z^szrGdTt_v^r1vmx5O|oM~Se{!_FW;)5Ga`~U5L`_Z9Yb$tYmBg4T}CdzX}ZWOB^n^fG{0bh?R zbihC}gFZfN^d|jzow6d8OpQ*PNB~Vf09<-kkm1%o==Q~#sZrpU8eV75bmxLZEGER~ zZ%^1iE`T(ts@N9$pjgE0G-W0MLUkdEQ_kBBI$s9ZhBul~EaO{GbGW~CYJX!O-)I2( zO;-FS8h5%*C*ZkL#$(>2#GzY3cZ4&@>`D~^vPbrV-ro|Tzul*lYsD6WYl>(!6}YnvM{yX$4~;B-=jD5XPK&YdH))HUmf}0Iv^Ak`>xt(a z{$`h}jF2^An0u#wF7>2jMB>FJ1!mm@`7hVFg&k&t;R)Wvhjj>!_amKlciemPO`b#G zmD>5bqKH46@T^F6b+y(+Z+WYQD9k}W1E>;T#p)VZ51&#Z0NP>(WMdhu&T?Q|sSWoE zA1ofITP*=tp%uk zmZ`SHOJ%T(&%t*W?e|wsn2g-Y-i9r2161ZH?h6E*?0Wo=mTcp+rfgHAjXbS;c6 zvNH#&EGZZUD;L-2MxI3v#NKO*fRSqtJ|d6@Lf3AxQPuA}_P z+G3O2%YgCoJ$MSK$l*cm&SH~2*`O}tzCR*y;a1YqmEbxviVo<3sm5(PasBjdtk~uB zlJeyS)@A6$QxBQfXR+ChEnqPG5Z>)G-9|=hf~`4YV1z#nVTGDvgE&ngT1XZ8oL-oQ z(^Rz40D>7Cbf|xZS2x%MqO0PDX5h852X!N%v3Qe%NU%3fJ%?;{${DEq$-|TF!5KaV zddvnL8&;~+kg-iTaWtGMX1*S3m33ysNY{`aS3RzJq2dW@?kugE-9Z> zD6HEkeJw$t*t$(5@MBBXUpAYymW1S8+_+hL%S&xmm6YJR90VmS`Dhrgaudb@oD+1M zk7}f&cjOtI055A{5|W+58c=ox@YI^C%-GV6eyK3)=GcTR!~h&SfgGcy2!Zz4I7C)^ zY;<$`ow$T4QTN5S`?&SrA2^*629#P|aQ6bOL)$2*FoBT^4}P`cK6Qn*#0ADz{VEHY znRcNKbA@3G`1E`kTKzaRb^1MmIy?lDu@CTs@%CMfHATYvw6ks5FdMI#YpmO`JO~Wj z$C$2V-k;1gk+?1j5!Q%^4D>T>v~>RF?G2W=$Ov)IimAiE89VHk-U0W+uZbc!Ow7?u zyxOzF&3MIti2Oz|NQOc|)m-YhZ_YhcInlgZr^2mxDH4*mR4zqNX<(_D;Q{fcDQnPY zXpWeE=wNGcoN8lkMHyw@KOX8A?Lt9IS79^m*J*Hdb!Kfc+;xST$PR^ZC3?V2x%t5{ zC(GCV?-S|YgFoYq{r4cRkKIVoQA%bW~2Qkd8 z3DNH}m0f&9qZ6!}ju0$y+sXRGGB|yk(7ySu*kIOe^pP$jv(64l$tWO)c^?=cR%UU$ zx05@G2j98DF-0?Y82ad;!hMu^^KXNY*LQrioMf=+C7R5A9&4*B$y)EM`EENRrEG(G zvb`$W!-GB(dh$reEgfgu|qE8Sfm4 z^d0~f8L@b@h~%GBe&jKx*tihrG4bBl?1?;0T)&^`xGa@?l)t$tM`ZyEfi8=@{EzqNp&5Xek#=OD*0IuIy$<(rccY zad-!&o3c80Aq?6j^HT|^8vD&|w{1F6GMymV`S&ePd^A%b?6A<=TAMki zQGm&ECLirpz1d-3PCPr?Odpv`KujhJLmDg&4i;G_)D>9<4VJq)I>USm(f41cT2Kaq za$p%)Lr)n=qX#;bVm<7kRI}N?z4Czzv$+LI5VoMZdyqp z)Amerh9XAzLqEVoT7V5OPS^4EN`8AMoZlylmaN(dh zJKa@^yEI~~!Gs@Z`Fwk8<3#^Q20%l=ac`-qO`$r)mtVm{!C@MK5tL2r?=h_v&g{Vs z;Rb|by0R1AgH{eOp2cL8vjuHz#~l>neY>A4q*q~hGa=%B z`<_uaYM;*8f9z_l0F*|9qIh)%QI8Kz%}y}1r|?q~*aMHniRA^q=E%axE!1kZr#;54 zWX4^=Ce=-2$~YCWhb^-PjU>}=n8GyCM1@yfmICMXhnh{OCfog6F*1xV5mycv=DBjb z72z~HJ(9i$DW;nk0U*s^PS=0?l5&A4zdF*gz?6EiJ+>XB4*^R~`;HJ=-A<2$*>sKT z4LmQBI=i7Op@Du3;&eN^S^-%!Vookbr1%9$N%Oh&0b)7T)wZF*i^(wQ6tZFmS~KYu zC}6GnvZI^h5}<8_9MGHW*l8~x65c&2pM=wsKIP#D-XPvdSNiP7Hbv^2$E7hCDiC^> z%;k1cr$Z8TQMf5l5t~w)FtrVBFa~D$3WapNUx6OOmTr2<{X;NQQs>d=bI_ivl%bO! zif%Tm^0lxPp8oFXJ81higKtY7<@n%cUvBX=JJ=HPPRvC)AS)ny**C^LTb+&+K(1gA zj9vN^LTfQpJh`(kpH>Hur0C?^mI3L{vvkU*xw~frR68%_vAcZ?>=wg%#cf4_Fc4q%nxiQl z=n^#dXz~tL-)238@0E|ZbqdEj+nuJG?z_><8I?XSxFM`FgLvmc->mt|45HX!V^W}N zX^>+irIW%F6mE4YK?@}o3(!+u6sHS4A5M2naouS@L``idXi7u3GT!S--mM-ZKt>4b zg=W&f+Cx0Dh+}enoN!13U^VTd>4Iasw{#lx1Y4lUCt*D zG;wOP)WW1|dOa>Nc_dxxu=CZq^wVvwiI1X)0V0~?$#^JZs;=?lPe2(DmA$-l&lh~e z7*NHeD<}G$kq>M7%E(z>qB;i_M=aM2z`-a_5g@tPtdmEmH#Te;j$}oe`RWo>)aH$b?|1b7iI*cG zLB!KBMz?%I*dZgA-4rxWi2wqAGy9BTP~wbO{X>T+RwGp_Zh_Vq?}!zvgc6ljbq~tv z^L`W17bwaPReBEF4S`ZpVat0kwUdmn)y}mGlmLFc+f&#fwppk70YUXLr`*OV-X27n z%7t(--Ju=}O;<=a6XaqoDP{*iSzt)}x*b*bfiHa|TKj%e*5~+9Av^yCCH_*zBpv@! zqm*n;N-RVwQg#F5iP4|d>{I;t5j zaWRQ)=7_>p6lO2*_DtzW-LDT}PI@d;D1@5Q+jZz8uET?sjwxId>{?iRr0n%Y>Qi|SU|4v-j{sr)aP<|xK6u=_Wa-!{p&%?m_!PLA}=Ub z@6OzYYU==U6m0#st?B8#Y#qhHEQvBp%;}DN=0Roqirj%OL`HaFab3-~HOYoNxF^rm=qS zu@-TwGEx7cMWX;T_V6CLFbPIE02ShE>fZj_(fK{_Si^yY>h7x6B0xU(V1fQdbDjc( z#<%sr{N75S2IN84$qYE|l`78spc|}9__7sV@uDiR*1utQf{jukw#mK;fg^Uwqu0Cj`R5$cP0gNA*-S1 z)Sq)CaL-+Dt$js)u7$>mftTO!?*oXJuWbPeDk^GFhX89I=!F{c@$m!V1nwH; zoGnN(tGBrT4hZYU)R_$?siVgLh$yJLeNm{4m~;hjBESg_yib)ZNrH#n=Ktv)X$0vR zo~Z=#e?tB~r%2dY<{gu{R?JQmug!Qf{%ZW)H*lCXKtnesnBDsXAbRe;Y*r4PDj@L3 zpt#;3UFl4@`HocO@Wjea2aIPm5i)^!>waKIk zUqI_osgO5!)(olI`x|H4Ob+q1bb~@~W8SL*oo=@QD~DuNt0aOmbYvB)#%iWf0Gd&G zSk{?7gngAji}tU5z7mTGH`4R3VkBUKIfgU@_ip?H0WWd=XiMe}kM9)_AMfr510KtJ zVjSt>_QK}X?sO0h(B8eYaS`RyPP($Wq0-Tmu?=Wlyyn|;*N>HbJPY}lxr1o}fF z`p@VWnMKy|FjbNDXpO1=EMO+Ga3Y>|-7j_$efJ$nZ>4ADxLYQHMyfJ%qcworjQ0uN zZr!?gzx#vSKkT?)`Rjefk{k#=e#!6yOo8U0b#Vbzbbz0m$|(7uOgz9N zpa(u4bOb;2Eabwivq2t08N_&AN66{R;$8KeJIJZq_k=2e@@vfuhE{BJ)DGJv^;eTvBiUfQ8(B;h`dlaqD6h*$VR zLkb-%YW?|Y%`<$P<{GmN8VD25fkvn=7nWOarw9T9bk)?*nD;BeO;+&2xoT4e;loY*a{|6sKG4)aH*fW^zdq)y)HqhrPR?%5Wx9yZjHH%F!c`q zfkjqo7LHG|Egj5m2jHW>jjMjT{-g|J2VPFW-n{wU)&4ksd=A~Sx1wje2rk;hg^>1u zP1cT~(A4k^&+6+AGeo9rLg|TA99p+|ZX0#t&2Iqg7SI;Xb<5e(j^I%Zu557paa`u1 zNEC&!AYo?a14Uf1Zv`o+aDDk?_aL=XNH&XIg)uTgCOI9ed&GqtXM31H0Fx^c4`7UP zwvK3{HFocIUUOQcg}MbVf5bMfx6)xwu-bWZ>Vl3#w0SN`5F`$kXMg;}Rpls`4mJ}mx*J`r*Be69dHwysW!vGG) zbDIhWTQPmmAIkt-S2wo5LVr~=8*DRuJ2S8hV=!=+hyKzG8yFST(XGj$9PTDA><*!a z-Ffk`e|)MrM$}C3{T>3Y%W%WjoyfEZ|2c({$e?1ZqA8XEDZfc0VS@662~guo0UkK*G_yR2G9$a!)0}pt7fw{|EKE4RgBYT&5+L*Vy?p5o zV;>Fykm?6&ig%`d^1I+W4`^@&Q2gm+cbY9Ef&NYlPB$TqaE5{LbXKAjoSKE#T~;SQ zwOVy@!NJ=)!)u0j4b2qJwl_S|NX4Yt&-JN7Y}p5$$8l@6>HS|V`||5o1t_jgmnSNs zhU^A1^1y0mI4C^~MOrOK4HSjCl^hf&`0@uGHsRC^!`^3rvetV=GrZg3vQ{|>EkP^3 zHZ4Kz!OHyelJHfZRH+^`Sk}(cpx~VqU-j3gK~1Kt;%Lo(%-g zzD^4}dN9IA4=p+ihZRSOb~ZXEo@5=O+(d<2jVr}5IHCDImveIBTd+aZd?`9Dt{IwQ zec0U|-i-|0>PziBz$<`FF`V?!g6MG%Q2j8?J*61OvhGn>c60E$-2pI$SzAZs+kp|d z1}RDaWn3fD(hBme(JuX+E{+x$MK%0HU7`>~y&-%S8u$6=@G@-us8LVGHY42|!q^GsbCL`DX#Q6x`!l-8kOJi(L#Tv>zbLissx zc0B`}yoP5MTQ&lYa1L6-HVbFKnn+5T`rdl)!y8gPy`6wj;?|bm$}H676|R~u!!vZk zXW|tX@*rp)TFBHf4iy-bQ)9)2f*`@PBZWz0KL=O{l;7OD1|pSsf9q}BTDcE#V>l-# zSdHR3F9di{&`qyxgDisK?iC7SpjUMp!q{0IG^B?H|=&p^fSCL=gi9F2(k z2x=Q&A3l1fo9;f)AU+Fk#*rSm$b!_%GfO(S*OU10!`)c%#SO-Ze>J_Rp+~|BuLtni zY@j7M0V^9967)X$)#!~M#C~!l-W_|Q^CY+Qnm8Ghzr%Wl12Yag8;sjQIMBE_4U}G+ zCqg`p zps?sCDd73q3G9St7!QFat@0c4>|S>K_=*N-_;nLy~)aD+GGg4wqAin?uxZxHg8Ju zT@l@vBwhJ(p8%Y=o;-tjOwyje9E}LeGsE>Bzj()M3HwS_MOKt2cpAf3I*;v`Ghf@) z6sWeD9~~N^VNv;zQka4|sr#TDSKN)MR8I$577n{sd6fIUa=R#b^-W>zP5 zHe^)0xlmIO@*1~Pk!rc7A4~ppCR1kv<{DmunLFm3%P=pNl44uC+@;eYW+m2gP|#*f z7R!Osomo$zZ2&GX>L@FsX~r5t+Y7LO7d5r}dAkfE?utccY`_{li-+D*+M!f?4Qqd1 zl4F6lBMs$QnuL@bTwjB#@=a9Xz52s2zr?X7t4|%y_5g|K!S$4|bN5fQP)7Q!xb0t= zile3N-0JYN9_oWbCg4s4EfD6t%uUG~DXM$tULt5Z(p(@eJ%^m8U%~!(`?QBkGraBA z#Nj1rG_z%YVdf#XP8LUq)4V%P%C4Djk};Z+;kZp!jr^2DY`o+vsgZ~?DnTg^H&;vY z{o-RTaVvNymDt-rNl?y^l|7G9BNT|O>*WS zoxq4AFFcNr&QKgDCIH+ob*jS zA(uWAu<01{q9N9mKCI0b8iB`aYF#7V%>yk^ouO#I>aBt2TCTX!daV}FYT>(Op|5w& zNz+qp*){gz`?G0A^;sO8@wiJX;Rd5Gp3W()z05bc-*U*Ib1uN$1T+r(S9D4O(n!j= z4VxyddtyXgufEFlelqGs1P1NCJqN45ewtdlXHBmm5^C%2%Jy)Q|}0Ba?_4_?ZH zq)*HnNyv*7=7JAwp>qXSS}MDCNeA{KDl4_~Bd|T^pp<(m@TkNr1%tYXV#wHt?QDqh zHpS7|$!qFDcg#SNi4F_scXKGTC4acs#7PO|O)_T3YN-2CXxbsaA8o~-MvK2HZ0nv# zL~?tkFE85!=?isj$%Ypf0!&?9bg=hRo4dULiR-)vWws57G)L7tGBwrWLAqAJTa`q$ zV|PM7b3Oc=BE#HzY3i#i5HWF%8c9foArGuf5vO`vvS)mfq_EL|#*3Z%Ag#Y}TKehz zT*rrNc;xQkEwn|y;X}tY7v9&{V`vS{E&DCg?c?1!F{^OIZzM()Xu61h?w zXUFHLgWt*q-@61Vlm2%PKK$0R;oCQ$OGz-PQd|(3JJV*YH6AW`PN3m_os~j}KpHQ8 zDQxdl(tre|d}w9ZbC(_JPB85T9*fI>ur4DMHNJK)*Y1JO30_$z(6;HD84ebzdE3zz z{VFhi*=ncZPBh%IX1Qx__$3p3XPKtAYG3hFFhNtBfDNO9N2q{R@gUAv< z_T*+ciEdCg;{Zrm0~Qlwbj3As+pvtKspQt$B%(aJF%x(|1k#UtN&^{L>gi)9lq!V5 z8i}{i>Rs#wYuH3U)O=EVb7=`Wm0nvKWpq*|^x270NKU_mrT!e69v#y>G_yX8B-N5$ z!$HdnBV&x=kp=*| z+ah2~{Wo{u1& zfyB2R5-%D=!fGHf<(5YuP?P&0!t+esPs#G$*=sD!XD&!eU1Flx8JgME+?v0eS@1Y- zL(mnqjT2+Q#*|kM7gU&KVl}p2xDL5jJQ{7f`QN=HQt%MaeE4r)(xcNb-Q|9iAlZNS zZjrE#2!2vr_D8&k#Y@$x0x!w@usP?qck*v{&8QTsGIIW(bcjc7k&xeMKtklVsk*ZO z{b4m$EBVX*EN?(&9A<0@S4De2|N9F#e*hURw`0YWuIsT`i=QT5Enwb7ub&*fgAKMn zSGWI9L|X7;g0B>!2d#v{|5jl=Rw~iEOl3YSSu(~e2@G(ils~nzMOE#;(s{;U3kb7~ zg~HXF-=A^c_Qkg)depCKd_%;fa<`<_!F*Wfd>y&?2mgZumR5={N9)zXwd$b8*>%zCR(YqALXvgATC z@Nj75TSvlQ-_)|27qjEa#*pp!U$69U??e3zT!z0TN%G%c#$PsIa3!p}<^TP$KOXJ> z9^{}#yq7Rdh=$bXUj{{J{)lvw4!ESu5l+abjpS7nnH)!b3+p49}m&I_dkrNHtn>yGtP=&dHT-!z(3Ye zjAl?f8O&u~czHy#(xcoR$mBwsak;JWaNSwpK?)#MybT0KCIH}F&^NB%uwB*sMeV} zZ0wK1*LVLzWj z&q_NKSc##J^@m%^LG)hi(fWdsyCic(PMbLZBGa|FIZInTD2cruTv zN$qy`jD3`XnJ1U(KJ$)ciR`;Dm*hW|Fu#2RSq6%Oa2j;)?kNxrn}%!IJYmJ?Dc>Zg!v9v z63N0mz<^o^R%VQax6na>kv(S6Fs>6uGSTvxAIra>4{u2VK@P)Q#T;PLr{S7l(#jYJ zmcLX==n9=Pe~!(p4aWzg6w{oM`CIZ7M6&hE%~&{6Fc;+Dm%ako0mU=cEh36y)s>H%mO`V zNVeMgk1z0BCHuhu8EvyUCb-c-gr5rss_~V9O`j8%IUwQbA*Ru~18W-%-Lh{3aFhwc zCWrZAY#%5G%|Vjn(01)yWZK3iFM+!U_iEjd7TZoRSh~XYfu8OF_r3uS%;5=t)>@M9 zmiG6D)VG)R>yH#OLMcTvuS|{QDSpY0TLYS zhrL>5{qv~L2WB8Ei|x>D_p`u!vKBS|;dGE)Soa#;fyoSDv+;#6zAI>MCu|K1=sNs# zQhwqi^f}A`8NfQwz!P?{*+p71+#4Lx{rDcn_e-2ck;0dL8VQmJ17~&Pn-d}R?dl-0 zWLJMvvqA~7yyaQN*Lk4#Scft3uPPp+Rl)~V4Jx67UMCn=7p|*;&venmcEaAeI53`Q z*uGnv@Zd=+k^4sf#hr7*ovS-Yaytuwb9Xtq0?3F8{U--ft_*jo>C)#;K@-5EOJc43 z-CDK*#L;H)D@WHHYR85A+HwKlL_X$(LViTxzj)Ch_!nKGNi5P0i1Su+4jdxGxmWkW zm~HNKz$J}WR9IFOVnll9VJvJ5T`?{mo@*A)cIaoo3{x6i7U5K%D>fvzl1DjtD z2*Tq_pS$RmyV%dbP-7;=>vgt&vNdH63{kCN#7}fA0WI9^@ zQyFMICQHLvRtG(Iw<|`U`~qtDbNMFR$O_o1>d?{9ygf-FZrgTA3SN>{J~ry7p~w&R z_(kcl@43J(_kL;*EQaM$tA5?x(i{REzHwP*jQEX$ts#%!9YdO$!l(tdDH&_^Z!uY}f-oOSY%!J$28ZhSy z^2DVWMWC4ekFl$cYjXeof}%15B}4^mL`EYaU1E{44WvatI;3+5ii&|rGeU&H5C%%O zsGxwPIO!5bcaHj<$8Xo~-v7`S*SkH>C(e1-c?)V*UDz;h_Uc7ao_`OqbT&7BkCws1 z%&~e`QbWJ|>bNf~S|f&_leYjrf8Jf8J&?|Z0* zcy25~qQ_5oF-}NG$u|(;z{)=$lDVZD#`Rjm^_m9?3WXc|v?rCf!A+PSVdC?(B>Zg` zu(10O^~>uZJ5O-d}!s zx(yNoucOYS8^cNxIY9Gvt>*GP*MZJD*ahNe3wQ)+#=aA|5X<&?*sS}XFw}p!7XM=} zJ$t3tsn`Qlo&%_hJYa-i^|scv&>Zi%n;eia^ImInV|@Y!CQC4wzHlH_5S=04RBi~{ zuVxXz(0>HJ2{j$L%4-Gkf5HgjurHa34y^a0!D`6TkFmCag`Su_EZi5cxoXO@y!cJB z=WbpIK5?ZxVAJ0Y=xvt0MdR;kUrT0#zM~%WAVb)^jv{xvx`K{GQUExhZv~m6_8sx; zyfvw<+|wXE#$OEPS^9h&n=(TlHdp<)CPQa)7cBU*GGM&cz|jqe3s|O;hYtwtEC795 zF>N#*CM}vg`iX0JjZRM+O;nC0Xlta=!Do)RMP%~D^Bf5kMN&>}Fq4i6O=}o1_Uy9kYe*$&O8_$}b<`W(o0>xMfB<3ZVb)*9 zuQW1IGb6Qj-qh)aJd(MI^9KgxvfB~&F0RMWskD`G7Lo=Dw*G+zyZ=-k1XMPkSa$L& zq&&Q7AgD_xoIe^%`bKcAm(p|>WQb?&y;|`WvUEgRJ6SDS$_!rXDkWJ&hx@lOm!YV^ zdR00F>SpgR9`XJZ=f9}WbBy@V&t&4ImV7qosG`yFyl)PCXC3wdvv>yF`*|IX#chYI zV$D!v!S`1xm-L=p?6BTQ5H?+wm%fKC=iSHF&3eSXl@tb*x8R90Y-Jkrc5QK9{UL~E zSCxsOOs_(u$uh)!9k#3+eOR9vv103~a|Lj!{;1wH zwc0c3F0rI6)qE!T^>am1C#EXcPq>{s(`=n_Jd>b ziW%fO0K~FeD)Fd;n3bqL1PYsw0$b%ax#iwFae;i~ zt>}I3-QHBGRutqYKW%AZops|Yw2>#gEGuaTL4ms3o{N&@gU-0*tF;0b?_UxxM_;%g zi7RS3`^J2@aF>%$9M(*yfuL9W$^Dgp;g7Vt#M^0;4kQgTb$=7KbL${s(jio}Y1L}- zogb5sqtXr~*7!APs3{@R$$I8Ily*_Z8G3&b^Fi{7WM4cjGl7WLP1fnsu7bNx-R^ofoAZYXRt|ndknqVOgo(9R_rETW)R-JYCTeaHR%HUX6MR$t*^k-4rnm) z`TC24u5!tE%l|D1+T$20}T-iYL3@0nS?jc(Zj9g@Q*-IF%BE% zJ&FzOrI}>TYm}1g`SGJ4{L$~tbRzl$l47E%c*a`aIJlqn?UfYX@swvKq8hEEa9XMT zOkwtTC?8(wii#~XRZ>!VQrHn3pyyndZj**34|?I!L{fS8k)Bz)wY>X?52J{>bD{V~ zy#=iKpxGq&jHWR}UuZ~|f7z#jn<}aFo0O2wl-~-E&ZRiE!Obi8TchH3(_v1WoHHa! zAs2DO^;BOkfr*Sc_xLF=dPxO#Kn?tTr7&^y4((71zC7i&AcTB9yr6h|c*ha1inN1o zZIfwd)dK2C{ZmNx`Ouql=s!~wTtEwGWr=ji`Q%uRU%x?1lF8xBB2AA(ESosMmZ=vlY^ohbdl9+4ag3U^ z4j?Y<0UcwXcyLQT*#D`;Xck*^OA%s(5?O@U7h&4loPI4BB!^O3M2)2z$wVtV>ZU7T{ zD!0BoRmNQ0+mdCm`Fq)T|~XHNYT$jO8EQ<^TTa z8C~E5#rPmc+UNWrfxd~97{}QR3HCCAi7&(JP6v>0Pn11gDFZWwRaz~$$SypFcIT`9 ztk~9&-6h13EoNz~$X#vT)Slr=ms~MaD;US0i7ogg!xiHBmaiSRQnsny4V&kH+`#mvU zuIMZ_uAgp8SAU{S(hc)7si$WuQ{!Y*-A}u6wS%~aboK0;MTs-9(O({$upL{EYaL$6 z`Q#2`8I-$J_Yd#lT8n2#ouGA@I}qa`m>>~t3SOeUJ>v5|@RW1yG7C@7%hQ66PHD~4Tt18A zHjw|oG=(bd1}(fYImy&o%9zYOQ!lq?=GJqi%e-cqK3#KF552M9q+ zP7}S+xIp_R2O3Z-UL%}porT)zoz#4>%z7a|Mw{}vgpjrQuOWC0{_1fAD%2`9@-81!9^QvC=F_i4Oro?QG{`lz$w*+lgo5^q>hu;iik1 zx_zJAHvQ3gSo8nSD*W9}_8tw?PH+OFhzA^U)d|*LFPGbTig0YUBy!)(jeV;(x9d%s zbbRre{X8CmYo1JA8D1~nSP<%&a4P}msl(G~D`?8*xyqr0^ZO{$N@<S;L`Nbt!r_~ff{MPlgES#ZOkx7 zK~ovrHwg?lS3bDtOH@wDb{E_-Z*X|I#|ydWU5~hyf&sZDe?(O__PqE~7JgFHElK8?~ zBC*_md^x21#V**`O)aU5%vL6KUB*2|t|9r17&D!~&IIST9(aKLxKzpq3*?xd4HEG2cEMaAc-8hp4i6Hi->3Z-BS{^j z4F~D*pQ$FU+<&+t0AxRBQ;Kx0a4j5ll@H;+diXsCd%tHkeDWrEaPpv0_~Oqo)8%xz z_Q4bSZtKg2lyX)N4gLFGJr-#hR*ld^N|t8v~56 zUB!RWn|s#ycq4QH)kl1Wk6ZClSv1cb7d}W5ZijhnBiLsp&`rrQ?H9@#D#VD4*h7ak z753J&yqmT(l4f4wwYl5G$`Bd-rHEh!&geIJ& z$J+#19{%HcjP7Cu<2XaWaCEFLE0|A!M zOr?~}j|2rw50lidePaNu_RfPQ7w}1pm*{g#udO`h`=ECGa-5DHFXi_B9PST4_pu$@ zVikL0rCepTa)s&r0STR#&6CD8r6)K*2MkCL*iaU^)ToN!0cw^qPHbo`bhTOqr-Vl9 z81tTF-tUqYU!LW}+P$t;pTCZZC%~sp88iiRuRZWdt{%87Aub&6di}{RN}p$}`aH6@ zQ_#LM?T`hep*BylHEpz#>6U$rH0g!teL}s&_?MIMGKD@*VkQ5?UK@fBA780w;sEWn zNteyUoJ`){7ol5Tk>*!&;mI!VNzPTEZ1t}^V_H_i`&}FY!8)L6XP%7`Hd8hr?m1xdR-)MFmdJD+xQNV9(xI(BKWVC3gT zrD{Z-&YUJu2r-wwaDM@eeN!{I+Kn?_3QG4tBen;7mkAKNS>HSlsP8)f-4D{08(Ey`~n)04>A1|A`nc*6Egrc5pIIgz&^=!69Y{X4>~7Vp8mXxbU_Fo?v#S_Xq#Xg6tZQ zaT9Iv_4NtPHBfJ({8AH8{tR)lT0E)x$Y?5wZ_pW^@?9B>*vbaeJu)h0&Tq%;skHe@ zf!wy1*9~THJbTi!8eAz5HY8E5Mp6$>U4xNC+3-%<00?6r7|kcgg@K`@0b&j&v6tpM zLN~6{;l8X5JXHviyaDZ&i>6{<89YlvxFB30x54aBeE#`e=K|%+xxvLYnm&J2#I`Dd zTlOs1aBYNX9ABh2taN>#YsLXF3N6~2RtmLv&XYrDs{o911l9TbsZ*ql0{prU5)3dU z5q0odj`efEkG{Q*PlW4Vnr*9Rn`MMLr-aau{rA-8n6xQ)fd~T`Wg6Vz{1`!^0RgoK z(^iW1F#&Hne-GFKb|k;c;6lDew?1(9Jn4Sbr2euTAhJ1d8%ou-*?G?b>LFeGiru5J zWSSg%@=w4opIG1>;XmYoi@gotB7}f?D5+I5p!9(>EUb&(!HC+uol7Rn+;U7F<^^Sg zhl?U5ClD2rS#cY^fZWa={UJQtO^SjNfk@iZS>+@gM)DwiAr86$$bL{HqrNXp&m^1R z*)8?DT)6v<3s>+h69%a&eJg?`po(t+X>zaE$%0&fow1s@R86TtR>WL|19sEda62r^ zlG!UQ?9jWFFbI|{-|+1X+)=XQQ2~Vy;5k<~fC$?0nhnPH@*il0ef$$RAZs>2FlD9* zTD5&eN?GazBKrHXIBua?)Q!Og-qUQCu^M?u#SZ324~t%Wd~m-HA(Wjb);WmFxq>bb z18-Q&S(b2zL&81_2p#d$b$ZZ~p4c^)JV$%yAXq35$ee`dq!DJ}qn85!;vOIONPg;g zd<&M^F(LzNZ%dB|QpjzK&$UxV={95R%WIA39)}7`$Lh&07trG z@x+kK+?VGkTXe;TGK(kQ0j{gci9nPorhcor;7(oL!~J~|2=x_53JhB6$?g~1cVyTX zDz*t|(6q(|x!f9+0_WBNUk)5ly7N^xk3-fgi^`k@wM(v(v-t4x$YHfb>1Ov%x4I+(Mo#xQFdx!RE(fP~J78`OsGWrwU?xn_M*Jb2nGdE0s-HeBeq;A( z?^P$=Od}YtQl1aE^GZ+5jkPPd?|@m{EQ+v&YN}Wcav^Mr`ymyWp?*-0PSlyW$)SFF z=Mos!WYo6!e)9$V+Q*&Uz!WO!FPGU)or?Oh*4JSjML{Yzc#|q{a2YRa*NqK?%G5(7 zfrSChrTN3oWWk7N@Hjlqf zu^f8c0Swg$$1uiHSRjT2t19eMHob&rqhVFm`zrlxXvb&1^2DEuSpAOC(uekS94dd! z+QA426mX6M@%6UQ9eW@X`Xj4}+Npg@A9ft|(tX}?bQZ$L8Ku>$s$Ud_p4YqyWi)U| z$>$|Bz6d@K=?1c)AW;5WQarbo?9AQPxB4xNTYbNk+P8_49T9m&;9J&X6%k?i!7u+= z*8SI~jpEO87&Da^>WOGybm&0I>M8LwPMv%B8cblVD?66A9e=1CZ;l*^D?I-!4oTq* z!9Sg(%&!h5g-X|~xRSu>UO$!C<&Z1-CPvAoF@Y{np8ej`Ar^3nX4|N$TSj6lhQTv= zY4{odnI3WGgRZZh=qL#urVrV9?$*uq*F^xEly&gQxby16@8-p1E_PNBU7@}Le?Iy1WAuy< z2qdcKtw`pz3Y$v9t*EnaS&geO3Sv3@q>U~7)-jMrI>j0y=xzwnu02xoJKP%!ilLm? z7zTK015z%dUNp=^n_6oGem`%}=zZFUYw{NBsTn(3gb#EGETobD83*D`TW=}ZQ{H^$!*J$ne(B~M_xJVwN<3)b@$dzp;KgofS^cP3z$)%{#k|BDsjHeZ6#CxQIV8!Gp9 z-_oVJt|pa_E!E-=p)3WF1Uo99PkBPD;(T7o#bZ|k^Sga&=a-VbaIbL3byPERMpIq5 zkuK67&UR356h*3}B}9=hwx3nl`ilDQao9uX#)G!dz1vRhL(Ox!d^zs%)9k)f^6_=+ zd2OI%zZ?lzo2ht_OpB03I(k^^)vRZ9ptpNT@SFXL$8^9kJSCfB(kF?#jTy!DRaivV zQ_@Mj;uIruHZ*o;Y|RwY!wQ1m_H}d}GI7v~X>$^Y=~brfkI(O*<&40sHo>pz3$)<2 z@k6q28dHAcF4-E4<^^nSn5c;O!%_BV#8rm13Q3?|mFR~zvgs%@Rr0=t-NF@mbpwQ4 zhE(YNtM|*jL7QU_Fj${)A|+&FEXU30zHcL_dJ2Th%lLkget7_mexs^$Z`&DlNx%y8 z`G!`3;XT?yr6e{q!}W`J{_ruM=3&gOXo?mWP5w)CXD)3m?T9irX+8SLYy#8Wn#>CdzwoYw>mbT; zH@#Oj#zgPG+@G7k>iG`$VNLns*NqRak2OQdFRRr>?&Rgjf z9e(hGNXlab|gWf)t7WqG=0S8N<#pBM3`=F z_4I18Rfiq#F!K8LKo#pkA2GQ)Jw@Y;13IBBz#ADD!t#0#YR*PJ%tIrESK!FxJ}1*c zRmpYLw@^7Xb;V6Byys5+%(2u?aXMN~{b{%NcVIxAifT6JJ8DQ{$QJtJbm5JAu1^1p z{pH_zoHJs9fY3;NPAJ)%I%=U7&VLL4l-zTa&j<#dd)tB28&hgud6!Z1120=PV@>p_ zxm7#zTmloFp5n^AdVY55ew zH_Rk^{N7ugK7GTy`xim+e8N=1oxQXE!XGVPod(WqbBzBb2(tJ(pc!{SVB@p(=RPuC z2;OmX{toT~Pgulb3ijIsK(ULR8I=nHP$MkOY;p5yj&f;UTT>6D%Va_>1V!-}ZlJHNku?fQ{Ls|4=`GuJJGx9Y8up z()%goCy)Dt(blY;9TnPd(qJo{d2%fhj+C7N95V*o!7!He5|Mcb%E4Iej1A>CS0Zear;D`rvB!)%HR?cwqOv^<9GT2~;-_n*7VlTwpZ0@3^kKH-&Fk=jtLA=zaC=`nttCHG`_dgfG)ooFPg>84J;s})qM zZMFN_3hI`hj9lE(eemyHzj)L?hdOkHjK(JK)6>T6yo94x#*hdjDiE|&I_=m%K`p35 z8RV)?KtGAHUWJ1qR{ULQp5DF*(1*+)o*l;w*N}O?uzmOFa@PY<*Xya%MW=(CGD{Z? z9?B zjC*{)dQl&40#_UY~XKnoOK@-li*$-D^+ht-n^Py4E;xs8|S+4lI=)A z=(M*}@q`4`^u*nz;PM~-n1XB=m7$rcyD8lVan?K6lT(4&taoWu3fsz7k2|PW+l&5r zkZkkB%i$>bM#`1rOh@HqZ%7k}FGfSe1Q@uE>|JcX82G^pxAWtY?_ijoJ$xeMpr_r@ z>1#UQ4qccZ9~-GTz6wD^3+QRCnhJN2I4P=CvHX3S)Ek9{1=n)GC+f>b(Vg%6t^e~L z{s&yHh(}omUm*7^k69Te2GoKvuQZV{O+!7xC6*u@fJ+r8Wv7VQgU#}1uzRH-h61>3*aoHj4 zZ(SRB*H)#du`C-BL%H-8h|n$dMI8NY6uB^LozB?P%@-5by!P^JKgK=!~ z3$_fUq0>@q$FQkFVJW^d5GKQe<-#1l96S#tWLRV3FF`(r%Uv}geKI68@yeHbdTW?j zKgeJztMwTZG9aN-bNj`YKrrx;IPae^T`yA2Iq+79oG=K;#%SRLaI*-4KEvrMv%qOB zWnP}rumFl=yLQ1;8-1r>Z)6R4(W5-mcjs;FRk}@{?v!Hw|Mq<^x3I_fHL@e|*sE}g zMjj5taPu-f!??+L8KZJsdq0;sfMxYHuMicK<__A!TK7-IrcnobO1$5{AJ6D{7*$h$ zrj8wZp0{aE=f?44v^HHURVaTv&K#mYK>YvEO|uRE1Isge21JaKtigA1^CwH*0@O;h8r> zlpJ!U3M!3P`wf%5Hs+xb#pBEI``4g8Bh+|+W+=th%%D;iN8eTBq~wY)QM`n-eNjJx zDK2RS%~*{OO8J$IaB&Bv+^TwYLvLDZ!{8=PNjUgWSBj-)SB(qGu133cFB|P)rcdfb zr$g8JoiaWwk=xm+aPUCOx>|A?tv~6hJTm9Srn76|jwai#r1ZU{qNI8yw)NNKuXfEK zH0hXx>*xXcg=DAm9i*+bb0un-;TV2&uCkVz!A0PwDQ5_0b)ij2@A>G;dl2*Enwbt_ z+p^+R*%?Nj*xtL#tQ%?)6|3+tW6<=#(0@#Gyaq}~B8?FK0wx7`4;Mr)!5QlochO%r zDMmRO(4c)nKC8n^1{=Bow^|}PKtpJ5K+`o-;aY`{JFC%BygFPQo~awD9iNEE%vtMN z;D2w!J+wfUe;rVDcWSEahb&-U?s&~F`mOv6os9qpxY8>rOo@78Z~p)4)CUK&t3bTV z-PBd@%kW0Wf#(0rg}%nldQde#?VZ7ibn&8&vEo&k>ynh`<5RUCspuLCqT{X9*55kF zh-kqYK1P6UMISB6WhTG0g|t1*uNf-n0S{HbqX6abnkVpI5R{Co4eF6=fb9Mpl25X8 zXpkjJ{<9tGIWK2&4L0rGO6Ai;;Y9qGbkSJ(GazmmN%QHHTk0I}V`6Im4g!8gV;jbA z3BvJ1*k{8qz3v?(pH=Od3yz1n44R>W_pitu;)6|N352?R#~LCj9Fpoa1`Qu9Er@GZ?C)z$}f2E8*?*hsYYm#tvf)>fE}72`Ax z(kU$|D12B^-*rk+V=K8`9v$C6S}e#@lC~vE4|7awJL(cm9CsL-d#>=P_pj&sV@7u5 zp|R+L>|ID@1d~4&_srR>x*6a1wO{{i1`-j?K^6b1wdlMSCimb?)?>Sv@(Ti1ep*Ht z$BK7Rzr|3oGT7m{-aAa1XX-ow&TKE=Tz8^w+*RO#{lGiR6X#VqZv?t7HzC|N9dlA6 zwUu?tlYBoi1+V09u&ApMux0G*px$AM)86&K3{(uNlk`<9K5RN(1ixCeE}chT3Bn^qua1szLE?1rdOU+kLfk>WOTB2uaVM&omkcl0!ayTkGtg!d)On!&Y(;) zj-)0#u1CM)K~a*63xk78hH#(1zOR?A<-Pt(JdV#_HiDrX!@c2sa6{AWFvBpGORMi- zzC~KNE>4^uSJ`4fjj~0prP4>ptE2dN@1_h|vPCzEmZE${jNFcpq&*syc36<|7(# zUXn)LCz(Gve&JgS$~jL`zH3ma7uJF;)&7BE0|c%uttw?uKlehx526zQX3fVdrUzC^ zb&qMWvAd7MI%?5Z)(>l8l~&K8PdMVhu%~M}`pPtk`E}WRU6maIQoa17tEgcnw*I+7 z=+%&<9j6P;O*E*-)daL+?32%}jLZ=qzH)4# zY7SmyE5Ieo`}2Mx&0V#WSyH1@KK#35@}paqN>?C$FY=f;eAQiSqr0#)7~O<^OZNC! zpqJ59w#FrxKXu0H-vdk)CwH#RbdWt}`ZmiCD$8#Mh|;)%bP0)nanL*y41@wiDm~Hr z8$j0-sq|v+C*1ACO8%Pt1;OUnZKI%N(Qxx5En*ys9=cntmoGD2Rr>gt^|dCp=m7DSFGOLhr8T z=388S)s%AGM&>Nql@zv5&FR0gN$hCZRPr$D{?}Ocjz7T-unN%)%B&$pl0C%oGqTUl zL|;^Wj1a7-y(Df-qSj~Idihm*t8$}_c%+PRXF?#!9^v@<%XCfZ!7F0r@AU2;@kzyC zHKvkcbZ=p~uUMM6q|F$mOgVneg1~w&%b&B&Q;P6G z=0Zv5dndprV0A*$u*|Q}9|+?`=-3Rw9+3e}Zc5nRmkuDWae3?h4GD)RavzhXT!X=s z7DSi4-%fxf^V{9-(heGLN;&BSED3^b0Lv% z4v?E)A7MfUE}t=^utEEud;oWu(tVA=2`~*#02Sl+Ba1V?R<`O?@Xk&N$C@Pqg|EPUgQZ zK1I4<53Jl6v`lV6+DaUHsoEa|OQw}M#H^o9fcHfy=CoMKzHsyn-toB+VtjO^7+xc= z462BB{jvox^v!her{Qr?zHr6Z!>zOk1%8{^eXg6(A!~l(gv`Bc;NrUhui%XlF~4V{ zUq7AluPy+;Gef!m;sU@8W&sk`m08e_vV&N*x(y{Rpm*~T3FL8!@(I>U<3BQDo*WdZ z1oEu^O_0N6tYnwl%Mrd*gjHtz;B9Qaj0dS8*$OAoH3m2PJ*UxCgQc-(yUc93+<$s< zc=lFtIOWJK{`@Eim<-1`=Y)wI%rt$>NJ%Kd%zEGJbe&l>fpAbvLN1t#L}KdxL;v5| zYq^X^&6&7-Ire+05d%dEwObs`5%m!ir{oMFu z-qnM)5Z0ynK4F>UP9s=ru<6Wm!=12ratZ~mQC6JKufEetpAZID6n<~$m0Uv0jFMH z_(exaR2(FZ9fRJK#l6CD`6HK^j_b|bHvUTk8_baX2FI4XYx%^a;dFpJ8^3^_#z7KE&B4*(el{$SL=gY&V zKSfAZ6&17<#__0 z8WU%{pa4TlQY>HL!nBoYhZg~o|9P2*@XJ@L*`JHu*zI{KtT@esno8~1X!IppMswqr zyCK8wWsR7~s*%q~a_Do8p%$z2fm#B^GB(Yph!0bOEWp<4hL*jcweLve<0CDrK<)av z-=|^IM4~L8smP=(pD;<#GP^8yv`@fr(zGbPcG~V&?jbgs7wW$~^MC)lWd%A0EJ$Lk zfE)RE>LWdhEp0ZYt}A8K1qMQAAx+tYOW9bdG9ECvEIV?k#0~Yo$^W+?@_+NHBpF1a zg=iMfKhs);_7dd*cC*JnRl~kx+0=2fIeyk|7&aM!j`YS@(`2dO0b5Gugg&F7k9?`# z!h0abq$vmFG9MbxRH_;LSb*1<2iV0=qzLDbcC(%rV=UE!v6P7X;Jm$f+S(DnX{Cn7 zFp3iHH%RSDVjJxqmS@l5{WYTN(qbfi)ZbfN;3LWMUXo#>P66qADtAQEoj20=NPp4( zyS^D1ZUgOq3f5Am!Njfh`(L#G_x_>%zxj9VzrKsXafAGkLzIS{xS>am2HR`0W|XsM=shNHH7}GRm%kPFn$`9BPG~{$K;v=2)9`9fxw>402zxY<3&NdR zI2tVfgi7HP>dZV$#gyp)dm@2b4fojraD;4*X3Vibh;+XOqft&)`Vpkv-vMdEce;)p zpMaRa5dUsBn@`3SC)AzKb|9FEM{H{Q&EzMNl4UMFIn2f~&oYLmDM=yW?`T)Lv#9)q=3vgE>ZX;C9&eQ-Zg$&XMd?4 zt{Az{yKj~a_~c3p zj~s@(knP-OU=;dgOkOPsy=+LHVt@$7z%tpQHlsfw`d7@l9mI_qIa49#GjDAbr6(YC z88}ygs3wqQORIfHzZ%K|t7lZ@%fI;mwh;#}uN#zbi|2ltstDX_?m=NL2B6~6$kWM2 zmkLrPk@_JWaSQ98px7}QGfd_1lSvq)+WX2 zOTHlWb!HJy?IkL&7m_b>A+G4mzA83FP@E5=5;if~=7u1OIaC4W{HfVy7>>kt6 zNhuYttYpY<|3TC`+Az_nX`HTXg6dfjXV4tLRbnEw)zWL)gv1~<0fwDcd3pMp;LWJ+|O57#pY2Cwx&4Q#}vf- zT6nockwn!rBYZWv?*URk+n>AB%6FrPRWYsUw4@%_!*UU%(cpm4HF|#-oEn-|b4V@% ze}L8Fk!Rg-d{`4TV$YHgE%tQ}an|TU!*i!8#`(bxE~?L;@Eq$L*vYhva4;S}^sU;! z(>{r{KiSJ3kHZb!tdBjEorrGyY?vbEcOQ;e16YC|iXm@Ttta{9150t7fh-1m&fSK2V~JNiG3BPXOQ5ArXu~Tg7uqbHQXGQrjbL5q|xQAk~Q+u=O50A0yA_xQo0tvN+;Bjg3`R#*?V3*> zlNFWH%9M|Y5(|-(gh4*aza^!A)ExDm%z|~G&7eS!m%p@0$>0`(18Ony2{NJ6a6<6r zK!9{k$=mQ33$}POF&x!3BJN2yq8n&3W-Q&Lly3|c6GA=VEL{yPMkM`ird583sQ)d@ zzYtkB;UXkN=omxm)s zXniPM#PNqQ)4=`MD>tt_)>-(T_h$}#-yuRH;!p-Q zGo-+=FxI2pX1{+(Ns~NMn1s9HxMja3SxPpX8`#~@1(S5IHazr3wLoZkvunH;0Ss3O zm|Ko8+deKv9t4B+%=t=Y;Si4DH5qfo3Isq7z{!XdZ|71#-Uh(01FeA6w`scZV#$|t zrXWK+cGc|z1N*giwad0E-QeT+Enl^3eiK4Dt~09k<5Df>QSi+kFcx=iOi%(}dqx3O z8=~MF98d;N1YnKHhMX8iG?t~1s=oi?28cM+`2 zHq0OWOU&XwtxQ%)y7Jqmz^tC6$K%z$9N>8h`4^v!LY1vi1E)Gz_Z0%#PY@Eg!|Bvk z^Ecl>@aE=x90!A&?bkuX`sMlvq8DTmKVrAuiF>)-Z4!j*bV(shUv-u&Ko%+@Gvcjz zD(k>|bL@S316bjCBT)sTq;%Ok53Uy9?H0V2Rk1Q|Ju(EUth=;bvnRqTntmIs$6@?L zN7^|rV1}*%a>6XVN62s@wI-CoCe7%gQfNe`|N7(rlfqgrHiA>$uORKj&Bg_}jpc!q z-prncpak2c9U#tn(_<3&ef_xu%s`jvK@G&^Ey3{$O2 z8yOr+W-d?_B;0%XCjHwFi`n4{z#BfNb|_7@S2F<8tl zz)fQkCPBaQG|&Myi@Ir%j6C2~J(lNo9S%a=YBno4T+E!Uw1=5E+rCR+bW-JwjG9cT zu>s+wXSljNxKJD*+nJH8a?ipyf{dhdRPXuIwH6H7NJtUlVDSTE2>QNpJIZg9Q}IMzN59}l4!P&_0njgq36zde`h&;T7Wpm( zl$al=YWNZq8*pNEXw)_8ORl9Y2fcsP3rmx~q3Fjh2L^4#Z@+v*FvlAfhzi*=^I98P zH{*y;!>+&m&R<}gf2^s%O13kZbmda6Lte@UE?l#Ok}a-Umx%UZ%b5Ulpe(QqA(s+b zcuE4&bPBoXM&JPS2NJ)Yxe5tlI8SQ*ZHL&$arUNqrKSnT%@fXVwnS%|!?cY&IN}@4 z0L}Pi)B$Q4j!`wrBXy&TMfC#RvQUZTBf$o7_M8xjfvrPIxVQD z+u`)tla*yyLW&5UIV;*iiLGt0OmSEnvifSQaESIlcE>-y82ohRM&R_Qf0Nq$-h;vw ztd3vZTFGwv&Ug*BdW`?Nq-a6EmqKE3AVHJ5AU>yLZHug?x_}R4V{xaOf{?*J}se0tNsg&SD!*g;WoSf(SADpxY z6isvIBslYTm(T|nW0R-g(#%gZ1-ar`X$s+p*6@ z*QP8@s;xoor01!*Fi3ONXZ^X2_E4GdTdMj`x5&SHIckKl*Y=qf) zD?VDwj1|Y1j!k=kS>QF%K4naO_C*%)V04Z{+qyWeWkrRH&5sDG#$d#7qQpjHCfu30 z!H^?Ms?_5lxV?D)$#(p}=9o9g!x(09t2E1HZ{%TRP3u$6Ds|lrW29rivFuz z<9C0Uj8=pZMDort>bnI&yx5-Sz`-Ir_A@()B}<@A*z|NJIrXnD4K2Dsh?L<@Y(eHi zrqP>f5B32rgn&##GV#idq-ecs0wxKFOZv=POy4>E({QZw7axz^`v=5A6st89G|2F% z`r|pK^7y9%hkE2>fiQrEyw|6 zS?>Y-YfVE(rp@g|ZA(7c$j*9jx3ot}W`61r;jC5YZ?RS%8^4BLq(&GG0a0Wik7lco zMxS=@*b9d=T_%jGya2HnYLf>lqnr?X&DH^;l9RNv>!(}CzRY{GS!^H#V<^aDiecG- zS?I`nfI+uu5+5cbJNwy%FQX6RS+?eI7??zLxjl&>o%o;|LBPA9@0f}(a$tH!J{&~i94m9LZF`yRk{ zY2ZpFoVx9m5=*?O;IT&cXh1b*Y5>)xN`&-{PY-e!XkuwW8i-U3xwYIL53|Ew6v$C% zk+A=Hofzk1s~$-PjfpBGujQT5oU)|B1n>@3c4G@Yqg$%#;-7}?jDZ2^a{jm{(b;Cc zV8{yuXWyJI&q7#RI|xpaJk?fL5y(6!oRiWJ3jF|ay+A#ZgPy-IhGQw@{rP{tivH#7 z{@o*gVF{e(cEb@yVG-vc30N>a!~x1-h}GCaJYkxrJ1|$Ip;T)GlO~(7`g~jyfAf5( zw?dB0%QRDrYGzOlat(Vf!N92HP`3QQX~iDc^>K^IYD^Fct|(f5Tenwpb9ai4l06Ke zO0mQzbpQ$BfbVM^c4%3b4;#C*B=tr*p2RomS^&Pc9$o~Zw>s1fLq$5kGd5C8*p3aH zg8OZ*^THey%ciUF3lkvVTH??&4A2f!uJGlTYN)@LEnYpzv z58ySzJ_Ln-Tj*$*SW0gsqHn;i$S>A6@na%4FM$<93P)*n??XWOSQ3QH2M*xxfV*ni z7~g6ak3`VCe-TScLp;}Z5y~TA?_riogS4B|@1ovoNCz1@L7k~w-O}&^5j`N3PtOD> zOon7q(Eji@ucrz~)Df#IDeW2g-L?jk9pp4yn>3vO9c!B{ThP9j&nsb**Y2@Q3XQK) z-ETyB36_RpI%yF3pD$Ch@bCB6e|a1hVT$tb{+({`hH+_}U0goo-mgHU!E_*pT?^c_ z{=fPt+TozH1gLEGt-U*lw+)~kl_P!^;n9p8mI}W_H092MQ(o+OS4*CT1a{y>fY-}n zv~Wt2Kg5QWwSY&c7J+SKj))!02O4aL1G5McMRu{ov*%2~FZM~d{9ENbEIBSqAxm;? zW6snTs}{1i0N;4NgEY;mF7o+zF%*41l(4QxaU;8IN$;R@l55b&nV*8gl6t6fzVmoU zJ!DW`(_XlOLxbAGE4Zt9~l8{_ZM{P`U z31Wptaujp)Km7#uI|K4y5|6b)a^=vWPE2kIP#qV>IW|tWa!csJKu*8|4VJO>b^;2B z3Ke_~?^J5Nd~z#y(}MMeK@HaH0Z+r1pxf*}M{QW@;(4Cz2&3kQi#OqJ@vDBl12K&c zXEv_F8t0#v9u78j)=2#BC16bHJ3=)3cyF>ca*A{z@=}Y{BKZ5KyTqEbsh~l%fPZ6} zz~iHcqsuiS>$T`~C?Q#MNO+n7$mnGyTS}2el6s9qC@M$6Mg15tex$v#6#Xl6VX^z+ zKpvDo1IB~V|4vl=7bFp-0d}(+-;oZ33k(Q>9CnAkL3z^-Wf^@wW+4Ni!E)S&px>FY zPru#+Z2Nd|50rpTV0T>L)LY00Uuu^te=3GLhQm!Gv?mBIw@r*bPCjc-)w2`~OMZ+? zg??oKYW9>Sok;cRRozA0bUW*F{mWG7t_z4d4O2NFOIWY zBqd|lgTf|H0kaqTEmo=pJn?cSI4OtN%rR#s@b0oKS=M)v& zO;0|cOj?P(ZW(wYuV&yV5%oK?^V`7s+a^r}O-a*CJcok~qoqJGnI$vq20Y6^jHf3+Av=D{CrL`8#bJExQDy}%nyyEodY4`Wrw zwk?2)#ugELrHO*FJY8LlfaXlO-VGw_iERO$SM&^A7U1cM;l^j}AmlI$jO(j=WYiWm z;C?6@Fxd*qhbJTQ5EA8|eoxhj6FVW$W~mQTmJZ34&dE1fUhg8X$wDdl61*D4rsc)Y zfuJ;p%oce)mAm zgJceeQxCX5y-0Z8dq;fnVD$2_MPpH=apfwPQ)iXO#j;tlLl2y`K7V$9@wKz@p;2=I z_1<>fllUIes7{x^URSxybCOR4wREy)0ZW(&$SiJy%sh6lw-ly3451)}ZjZ|y#1q79 zbX>t=w8uzv$)r4t(G~om$}a~z*-aRYz*aMO=ZF9y&3ftdt;VF>r<(rh8F>Z> zOcdxR~%BUf7C3K#1t{q|k5Z3Fis1xlb_ZdV6+ zMc;kj4P?@n1QgAV4OEx%I7lS>1}AX)+)AH(q_1RR^>6vNVe=hz+PLR7=LX63fe$(~ z$@Zne>%N(NQh{ZMi|n6n+qv(U;_WST^#A<_;Tv>xW&2wMW~+c+WI9Y5D>;s7M7$G= zk)0WN?WC{sB=8cwlY-#Fb{MLOCxq=YRn~$r;*+x9m+Vd#a#yt2LHJ+!<#YB0e8o z`1XOM)BdCV??Q9Ih44YQ(k|+-C)jUuj%Oh98Y!S;V*q6%?@3xjt-6~|0nzWk{Hiv) z0hQr5sAlDs!X8v8Ch)lf!Ng%}#G1KB$jnR#1bDsLG2T|MXcO2;ZwO%Q6c3A3iD( zNG#)wC!8z}fT&;9xTB+icV%0u@hpn27L$*J%6|Tu>b#`KxNgY2Gf>toYR8kM z@&U7xi+_J>!lHrTG`qbA^7_}9 z>VQ2xq|&;Xty8?Yny~h?PO826gktX|1CmI$_~0`L5QzGK-^XmbH|u!=kQqA_Y41AP z06n7`_p$kldZC60Z5;z%SjV3cH92p=bC5OFvjJ68O6d+-aQUnf*CaY4!wItU*l`FN^z2G>pRT=ah;K zP-tWn^H7kCosw*~PRe61RB-WI(B@lmpPZ_12f)T~puS;68g8f47dKLP)_*{iMUnP6 z>M9ElatPG;94^e(WV_S$UKMmZ#2{kWpG=Hd8&jr#vtnHHtLlR;o=h$rie7ZOTyFgX zbZR}PrV9(I#|764Yl{L1J{MNY#*Ol;$fxI9f4cjg{`(95uRjFF(K8-025G>zJ52IF zPw~$Jn2^I#$vn(5GPUHf=UX$q@eHMA=^rXgou9b4>(E=Q|eA-Nht+ZY<_sF!2ghnO*G z$hAcoD_3d~s$F6!4C5-AaSaKPBc9LfQyE0_=kv$RU%%JbF<9?6`wO;Txsc$5OtpUjI*HwBF^g4yk@^<4>}|vd2M(auibU3 zwq?^MYaJFoImgC7w@OQHNCuT9s0)s`=eZq9WNSh1-8H`KvsvZ-ex~;hv?eq;uJWsJ zj%Fx8L!bk+6^$yVsK!)*uNd)sT2tZ;z!S_ts@mIEh5V^%ETPejd#;@@PGG)ed;6`rjbkr!hDRX6>zVj|y)x>-m&K!;yYC&@kF9SEQTZyPh2NL(%vulQT@T z-FrZ|;l4MnSRA_{^=~e<9!Zrs#m@>!mMN{MApQy4c{h@~$1YnPlks1(2$_`{h2UT} z#@UyKJYpR&+xi&?k})KJODdwZ4s!qQI9J&KY_Sou?y2b zm2Gxe?XWWRyl*{emQobwG^0CdB{SyK#mOV%le6=qo7EPxcOOM<%N{#O^zkgyL0!R) zY_Bu9uyy%$c?~`2$eMh@@YOJiEy#iDKT;?!Q9M`?`s}F2F*ZDxvm7yr8q4o2&PwxTLY1xk~0R)l>-#6|+ zyk6HEe$>J`O=_2*?yYK#rH#gQbz8$tloEL^oe8MK*azZBzH)8+wY*A_&sO5sG7fzO zny%{T&JGs1dAAP!fvnL?Q+-$%$_C#I`&+3Nm8bFSXr7@iBhkD?!M~+;MdJ{u!HesQ z@&GqoaTRPcw4`~JeR}ry^BRt2N->~RvEZ-rvJgXbDqp|-HD{&5S#uwV(%pIA!`dg) zK?0Lc7l6_G8F$M9dYsaGxka^-!)dILfBBsC+I0^q+ompNCrB#Px30rUQ~H9ptOgYVuF5GF;aR?`N$5}XQ_VYt)pF9o#`G4 z-~lh9K{&x7d|9|A0i$MrD_~%SoO{i;$yZYjp?BC^?Fphq#wFP+-y7}PIa6eCK>NA0 zPy07{EHI`#sH*i;uEt)DyL34MO^^c!!loI!q0X~F7xdS5f=mUH_#UINj{iYB_van@ zQ6EQCL$3%gc8G_hq7;7CRGT0+;qk%`te@$$@dbPyl=%6+V1%rUZ>VSw4LO3Yd1^p! zVBmIs`I~Y80$N`yn1hl>O&2tM!P8>VBK`j9%Q*X!9TG z3;pWVDr0+ADLqvm-VupgPGJ!n%$qlU6wRgJDqKU!`EEmvw$^0&={X}@;x3E}48Aif zIe+&&bv>7>gl6n`*eJ=%eblu6^PqX*NY$&6$ce|+yFH-JTeM+47Erp8Pro^jw->$L z?kZ~4NK|eZ=bJ?@nK!*iQy^_lllD>c62uWcRk8yu-7V)Lm8T%u99BtV=s;S>T(6s7 z05hM4Od%@4>Q%2lttT>RwIq}xtNu6&d;U*PnSWq+7Ae?J@Bk&OPmGA7WClRQ$1%wS zEAwf3zr&JdLxT?d{Cj5~Te1@gdE)iXke8`1%*V{967ogGPk%~Uwm4ZRX{yW)6BTWh z+uMn*LGDCG0WZN#)-on|_Ca-9L77#x7Wgmv6r(gmr5UwmsxmLgb$WPQIiY=Kf}M7I zu(pMrFmr9pw!f=70iQ|J|9R-pE&C#FoEv0hWH>{Ey%RSXePy$6lE&Bo|DI9&dv^Mt z=YDDKh3Sdf7itO{wA?;Nh+XC>?OjvzEfN%Walp7v4)MdrIY5Kv2( z_Wp#$7i^a3f@>s!?NqWhR*0+ubS01zz5L?iqB6FTJ+Nsgevgi*OlO{P!N@j|T;L`| z2O;`?B;u?B*+KyJVuo!IS^j%hOLu4HzV=&+t>;iF6vTf`gEV*coeM`H{Ety0%-MIe z^|q)ACP^LCMd|wM@}kaJ1d*D{0jojwEvnU zgs7Bs0OqVa>B$zEF{r>8VqsXCTw-AmVzD_wEJQc4Fo>YZ#Fjw>O(wPsLSnTDQ&Gg0 z;mc-S43p;KmCy2$7$z-d(S*olE`~{8rji&YiDA-bm9lsPEu=~oI@|vDk9Y$u0yGqF zphbX&VsFxCwa^?H6nm3IfrkH&-XyBImBFlM)hY}zL#&dh`aWjbb)ChFlm*T~-&Fx` z{tEYXuiGYc%4#dP$sTnKIecK0l6Pn;NP1eS_4bXP*Vh5Bu~wBDD1=5r11Ige!TGe))uIq&OH ZQ;OqJF3eOJJ=`+*8Sg!?2QtHh{|iVsPwM~x literal 86526 zcmeFaXH-<#)&+`)iU9=`P>>)tCXz^wq6jEaKyoN@kff5cfP!R1$&x8@4uxb;0VU@g z6eQHHc~4S=;0W0f92^{iyLWEO z;NTo~!ok5^#Xkr?$>}Q#$HCdhX(%Xo&qz>2(9GEEvFt-lZQYwXW?H&3BDa{ixHxfe zF2B&$(2%)9fBA#vNezt;jdWLzJhqm3{@h1K!?~uisj{xJHl{k}WvHs^r!$0~-r?X~ zBO`Vwsj0+|W14Yo2-hl|Q}wBKw{n?EAuU8Zuvg#r$9*Fs&o1ucczH}zhE7x<-`we@uC$(=u&3*VYY8&M zyeolNi_<>Ge0++1r4lBP-n3gN z>&CnD1V`r7X1%le0>AabP*Gk<@AZ-`zUb!i^`_&@nZz@KPxSlcc&{->|}9fR?K zfBf*?h3viEt)x-^8|8^z7ys*)1r!eZP~G5X$gadyv*hYN|JSm_yvGf;qhIdje`DfBy-!)Te-UMyVB_Ghu}) zeE)odCjy5KzvdZlv6zq><(@Q_6#Q#%1k8vCx2G8{O!0qPQvuSW4V?AqhU4eWEtcfe z{QkQ0-`}%k9WOCjQ)9Tq&|3UI-X!)3n)0Y8>%ZOfB0Ri`IyOqX|G18Se$Zd*^aRJ{ z*1oE&TQmg!a@X%M!pk4~dJO#}_Wu0Hn0o??X#sck|FyP148~Vt@N(7BSdJgQ>aWkf ze423k>Thj-t=6BP`@erOb`oCRZ8J&mUz_;9|L({Eyow{gmi~Wk#;>LS-!X$E(yyrh ze!l+#oF72#FTnZF+Vppn{slO{00*i30>2o}_Yve5!}&f>{zWeTH!DWy-7jAM_hR#( zQS=LN{$~U5`x5;Eoc|1!zgOsAfb$D*e&@5lc>OP4|EtV?A1QzF`tKvK*!H_D(0hdZDGVo&ghVkZzcXLUp z`NGatMxqh_T93A2-K#4S{c1~SRE3k_QZ=cR+o2QlUiC!>|Hy-we!L-vmB!P~@xs2- z0sI!LU%3-xCEL2k;A2NpT2Scl#iMw+e91W&)oeaLo60C05?vp(rV2ghLT*;d9BDmdJN0!U zx_S4acxb@p`a<-0wDT_Ou)_+PtxNI3T=u);hDBq+^<0AW(@mWE^=ZlHTd=sz{9DGw zUjoJ2&>`yKrX_P2)@I(7gbDH+r*gUIIufnE_7L?*C}kjyqL-?nST&e zD@vE~YG+}WEDNu_2p;_W!B~{>t<=VCYXv>)un8du^PGHa4Dl`JiOP(B+_X~-N8jc z-4;D%P3xq+yR+ad)jnvo`ZY0y<@kI%t}DvXZex)5d$`>~;<6#Kv>~!sE~9mDLv%4M zYanmyH-VTfydk()R*T7&M5VIgtV?_gbH~(Xx_w?BopLlRl^mb7UN;^p59z@d9__C3BPUdQ7whxbVmw> z6DgJR_9GG-pB8O;eY>}ZFX`mDnB-KGDB;fO3;1pEesCcSXO#Qe|hD#yJd+vG1UZ*Khw1MsbK?}ToboZ3kFL1n z^~%n2NQF3fEvUk$m&;cdhHqp*3>&%}Ai2XFufRLZJbIsZCMQ9oHPccXQDZGHb>2?sUSYBK_TfQ}KI9Jdu$!xD+az%NlIKElI-mxFAkEW%9!M6Ya?)#Ml z`IXxF#h@$)T9eYH8ns6$l=i;$j3xAgkLwv4H!GUBXIT3)hd94}dD$)_#vrE_MG__J@P6hK~5_X!wDq|%SBWHsD5qu|XtBZC2 zk2mFVNoAZjqw*S~mC>Fg@6vmcZYqdk?_$wvSpQ(tH=o@tHa>eK;isnO)Q};VDp4|< zD~7&1{VnxLos@K52$2oRJuU82rfINjyL$-@+e=H~uvm3P?_E7zj`3%^nT!yqQU1n< zKbBfes~qt;$Cax)#@Yc@C^44q_?&|C67HVeuhQ5o6xn-rq)A9Mx_=LvRVG6v^;%)8X%3r$Xtv!}P48Lm#YPC;l$^qW;U zzB8)MjTRDthEo!)Uiv4wYQ0hHN@mpLwtL;fF&AcooP?8CxD8#Ih!bs5H zbN7irPNkIdX1fLCBnijtIEgE2kQawh>d#yIUY7J-C1eq>v;eTOvY^^p{z{``HDo)1 zZe;IIKmX3<5M?M50PZHUzX?#IK2hy$h-?lnIE4(y+_uN75M@16eCuZ)pnTz)?edo{ zRwG%!NBs!ym`Aadu!8|LzT_b!D#kej7z9)?w+B_s%7Xf9j^pA@ALWJHGz?L*N~y?u zTHuPJJ$G7-=6g5rCw1`sMx=yG`U|pHntC(+IFn;5V{W>&<br=b14(8Bk}K!S(gaca`1_cdSxb~Dqo??5>=!whZN ztycKib9Z~<2FHLIy!YOv#Rca*9uvsVDcJn&iaN?g6M++x@r);bw&n7N->1v@-`KTT z<9Iak9;uzI4jYTCcB_;5mAFUqr_bq{A*hT7RE-fV=>^1wx_b6xUv0^dwsyX{W#BTK(LxsuU@Ug?$?QLF$~qo z*$%jA-i-5{5lT#qq2PX=m2MyB{F~9XI=ZaaSGdJ}0_RJWDbX=@oN-mDb5jKhm;`_2H+={K+`)#1|Jt^qiRm z)kK1t?AQ^GTE2_TN)n;8O^7eYfmutQH(fLr}x=l_65gqY*cu)H5b)7pT#i76=R9GD+V?ElY)3Txx z#lzaPP-R|_^?XJsGgQO$>T*33M?dj-bZKscj*ohu9t?aNc2hrOLIesj`t>h z=4PKerKchh9nWLk(B4PULjJoSG$WIH*~ta%zen%Qk53z zYK;8(*6vsjS}Np;iE|8EAfS22gVN3*Z!_08J-4BeTU8=%zp6bkkF?qLt)*-1pkD0DQ)>j|vPtaV|4@KBes>qJ)_zf3ssOSdCwJ|w=tvbQ9#O>#QKsWU+4_-^ z(-mKr6jZ!$wS(3ou};|e586V_fJxs;iQl1nmD?rs@YP$YLa|wW0*5G+csCti}k?{O}m$;_NzI49qWuhZ>qD#w|At-=ADi6;vOU(mCZV_+&Yetug`isC&=B!3IV(!{CV2LRs= z|3ZA_o~}spVLMi#02WrCe9gS2iAOl9=8vOfB&xtmPIM%)>!GR9Jep;gsVb|>=L!1{ zSDi4K=sC40Jqt-}K%7$WgX0Cg`*4}tn;{^(=UF5|ubp?qrlA@mC5%2*y7Y?kKqLFO zB#Y<}BXGPc!8d)-RQG^5vwg6>GP-xYiKp}vdy=#rg^h6VBU;|?u#L!>;-m*R4cm0ohF8q?5L=+_L)`^PEF5%BSC0zS*vnr|z}`b`e}is9-K3yXhW^Ewn_1Xy z)D590EW!7Dse6?4BZEfx(iLc4pLO&bP83F`MfomzZ9NZA+OE!hWlQVCK{uCr1M*|2 zR4{k52|*{a<^J!t=?HGQY~lj{P-1tx+hBT* znw@jnVTJglbGh}5hAWL6Qb(CeA7bZ=hc9dskCL*8cG5Ag+!LW+f+Ae;tuHLOt*Lg7 zd?$IQo+lflHfMDXx~7I1sfN{4qcRkJ8@uZj(WcO*kYJd}dx0ChKuA9QZJCAFL~+lR zh8~2N`HbO^DjUQa%V*owo5@Ghy}d+qFXd^u*4KI{U}eR3^A;Wr0o#g#Nzaf_D<8?M)Xv7%d(>yvY4EL&|Wsa4KD`gLtOB>@OPIDqzT%&(Zn)~I@zsi==+f(2V35z|Xzo4SoJvYkq+!qt zD2AHRrck~dza&|0S#v1rSdL1B60ewMEt1?%=W4cbsaCo=u>Pe_Z`ZA^GvaC z$$ofC-FvgoOVMcwX`ew((wfUO-U`!?x{EXtrac9lF`lO`>51KT0-`6;NfhWa+zov& zTW9Ci$pv}(iZF%D^3CZ|wcah28vS^-X5BdnOJp_W(o7?MOkUfm32$bTq8y|NjmeIw z*c;GqSvB*m>xjiwH;8o7?!It}_hqjOCiRICjDP&)g$TQfOh)lszD<@2eF(tcLjOhMinn#|5fhO1UhH}aJ*6mG5n4?bU@>8*4L{v>v|nI-qg$R8=t2Bp)rJFZvSbE7>`>6}R9ks=k<3QgdmO z>~m~s*jf~DCgH-Db1E7x2c|KGr!S}43wU1DzL=?aaOtHKzhPIJ;&LuSy`pgPGL-te zOFrFnIrLwE*vXnH$g25BJPjR&7CfQ)Hk38KH)d3o;`-wS#7h*4xr|RDCOm$CC2_2{Y^O(2eg&FmhSElt{f81k0iesk z^gSpt8HTeh7By$}zswiL&*A2LQK$c?P`0X0-`W#Q*y+bJA8P+OMK&q%DB~MyYv=Z=`8WP5O*eZOK}-9hr$W3|ho^f!_%UJKCY zeT5}skQJcUG;_vU6D5J+n0T1C93=KWlng+xJ8wUnu%Ur#+5S^kp|= z-`*SK<0lfYqhq!b0;b0X{bZb=SkVo=EixV}}j4*VFA ziX~%C;+4P=sP+Y?^^(&!vn{)nL{7s&fVDa>U zTV-gr5_^XcrH!t_a=9t3c6~f<@8C?I8r%9aU5pYv79)Yqp0xL78Y_wGuhuN6*^55) zByUW&T>f~8BjN=d2@1Wt0I-r`tQU=RgYCJ=jaH|P-^-+WoO^ty-ADIPRH$55>vD;% zBYWRT=pWXN1gg&TNc^OkSG!EOw}GNK=pB|iLRCKzs_mB#f=r^~ThnL6@^_BXXA6+7 zrK*Np4gY*OtB_|lTd)`!xMiy(q+fCbirqA5CNlG_Pq!Gf>}E4MCl<|6vAx_lt(+%q zhDoh^v=sF|(BJJKLF#=rz!inEvoRw(QxfRQ*_?aZD;y<*xjxO$NYz7|Kv1-R8HRpd z9zv5OKt>SCD<3!c@@!D+Vp^19=9>|(;z7SfdG!w&^ZVF>c;@nDH+!3%LqXNtdh);s#&z2X1RnZxUD#y9Pd}Rt95r!NiPg7mvnhFueA^Ip#t(D!!CjK z#}b6VI{xVcRW$TOH-it5s%G1B_qb(lVzZq22+m&rZS0xgeA&8sRo3w{&CoBQ=f!XN z-cp?_GsY`%KS8CwzF3OpTbZ7TN;q^M!?qz8yyPj+4kLi@odS2Rw{G1iXGd;qhphSj z*R6?3LD2qFBQm&U$)G_^X7Qnp`@%g~=iLcs8TEUNxZ#~FUXE~sDMR9R8A?uh<82J= zD&(79`|X$WT04Iabcvq?dL7+8ay;)|C7OoQEUwijm4ePz;Z-U7eXexb-;M~Nl3Zi2 zf_W;^r&8+Qcb0{jrUPjqpHX*&e72nFS29nf zXRj77_ZrOkplrJ$v0IlmBwa$wuI{QkEL9_1GYQDNAYr=87|0S)T#t3w z;|HLx9=_lGvO@edCv)Kzh~X;p76 z&`qFa)NBo_aMs(N_DO2wI{cqw+rNQFnZPHv6Z{6n-Y}ly17*TOqQ9JwIzR@? zBctap%;E}wr)>CjEJO-|z$nZtR&a|Qw61}buaWg=!*)N8VTU}St-CKT79`8UjxYg$)or8v`3*iQ5lJv zhLfu%(6RNvPDF!39dE1`Ig?qEDRrP?90UYpXpwkDHZfm=9E!C!H?aw+4G6Ky=T<=^ z*4>8|&O1@Sc}FN#08fi72$6s6htm3AnK)>%Cs0`RoF9Dnj-Yc;91#XUjmm4=oXHwa zFE2E40A^cM*g=%Xf*FfUBUScl;sa&0$Z@uTLf4L6nS6VCdR=TWjU`%O;`^hlRSlQv zvos{oHXxE3r2_|)vC#wSj@ZuAn!!=`5R#3IJLz$9XLIWleL03WRYV!|TBf`g)&OQ- zs>95fMDWr^r)z>5F-s$>Y$~bKo1L}(c9`$-mkUTQ8bLOhKGF!QnE<&}j7Tz# zfYTAt62IvxD4R>#@|aSYnZWK$X~+0a3V51nV%vpr>bBDJBs?EA$YtRBn>Z`z8Eon>H;*s11rf$&I zmzb8-VGcI{E4-pNox>w0NSZq-UXKV(wXXowxO4mWlJxj4BhyAxVeGk&m z^-LAKLVH`c3{RWRJpZH+uc0(oVC1GjyoX;W++rK7q?dBva$3JP%D1a&jrcM|5_X~E z#ly!xR#^xqEnM*J8X>L?zkGNxr82xJ&kdQ{j?B-sYF;6|u^|w0ame=hmwEP`Bef?( zUS5<)&1k}OD{A`|W3TpKB&_nV8w2Jd1_OHAGPUWx^NV@WJL#XLp)-*hT)cm_=2Gx$ z-`?Q|f~eNQ^3$7M`+R!OtkfaGI{(Hex6;9k)aI=+Z#QkO#_2%PZLhJ*qZM>&(srAF z6b1#}pv;@!Uwx!4K7N{T^}&sCNX9m3CR#`EnCY5886ApK7wSI{tf=K#e5gA8X1A)j z#GvC`$~hK2aWC3^S&-vv=Z50_xj+<^ZKw%T&?*`Sp}KT_{<=?dv-9rCY7Mzr{^T&C zp)J1^VIW%%^pcZTqD63{$l4s+sW35b)aa)e%$b!Ag#W8X@?3y!{jitj+k~{ zFBwJyhGow)>pHOaT_06YsPU-W`}0`_@k;7;>$~Tm2_R0R^AM_m3_{!6pg;iWpzQ=e**QFNI)~@9Kn5ns# zk`S&=m+pIBd9N(DmeRf>%~VmLL|iSt#^msER&FV&9t9rndzR7KYjIG^DvDDZhmo%3 z^uAa{CsQcmhA=)eTj8>s-uI{(yd5fDV~fjmNZrKrXnB_orj*o9Ak$rBaO1s;g()@x z6@RIaBPzKEfXv*CWhhLzo^70RBbvgt>Vu87urFEX>>>=0uQUR@HBP5;KpXVNy;n6wn8Awn97|BE9(&Mb=z*tc#Q5rf1balv|q zLRGJ9@v=69!x%fU&Q2Z?R2s0u>bA+&cylwj$8|}V5jGDF8`O$WIlekj2AXzJdM`3L zJG~%f9n|H1lRM5CnWXnY``8YXiy-@A#gQctDeDHQc#7>ED8WuryyN{)Lj6w4+7rxE zMk9ZQ(KXPNcLvTL8nvE*zQfeI&!v%{ZZm0A3jR8{0~n90$xkb9 zAq`5R8H|#rpxR4b5b+a-E7A8BgqGyJ{VwS1`IBa4UYUqmHSO!l{gX9_gEhD`!p@0( z^JugU0Bj(x8d}KkWxX%TFa}o6&$|D9mNnx_w8QecIEf0KB<1m@uh_^$bA@v!T(NBvYmgYDHssuCiC_CNMIZU(*cg4G7sOynYHBT^vO zJt&5ja%Qe+nnv6l7C-+%SNi<9Xk^m7PDyF=$z{N?lP9xmt#7(9ae?USv?s0JaG&i& zqA^9&N;YqCbo`DHr5Dm}oO{CKDu<8}bAjQdP}WD?Kkr>B(9!3b3) z5hhy2LXK!Hn15wCm@J*u^bvMR;rs;X)DS#qlwbN8picR9iL}sDu4Pes{qr-E<~8X8 zf*!{kXY}kqSZ;%9SP&zO$OhOud1y8e-5w2q7A?_P0b{CmV9XI1ql)*(WU!+2#J$q! z7b+sE7xc)u7fM&Yjg+qDz3${$2oz%sdsePhlhySKR?n`USANr>Ls|qKw>W}Gumd=% zDmCm(Z#t5lgPgjyUU#ifJpORLsM(x%4}sdUdiHe0MKRsfM9eZqK*{@NK4(c?_*$N{ z=Sn7M5>rr=jXLP7ZD0m*<1R#pL+W;u5DxtUN8t-ckgkyqaejyO2yM-RgXL5mLMfDo ztbY=5PaxtBQL}Rj*}s(_DlH!M;|Y(njD1ETniOUCAg{R37n&$q>w{<@OgBsbM6NKU zF9Idh%Nt--4rj`=28ExH!!CA(TDeC~aOOO5Dn?jedzF$3~o2;^D} z5n?fTs@Q#>$;2ug0cIs&fMr|^0$+sH9x_Hl+PikEGA7&D^oeNaa`hFf&M~$4$GMoM zad|FATokl;(#o38h;z{l6K_}a0bhHJ;iaP4TE(OyeM%VVNZs5<2u~u`0TFr;?O~qw?by!xaPuI_tky6o zvMbIGF{&)>vR(y3YGy8I5Hvcn&J3T2)wWzz2bl)KNo|?kWuI2EpLW#neqdyiY>@Wg& zWg}GiP-AN7V@~c7me*ZPOVABgN?fFBwqJ|1mRg{K{?OthZHNwwVL{@doZqzP0-r3M zz=Cz|CK-%9KVQ*0w{nXDTxN!SfaiJT4r6qvkGoZSV6c-UV)aJT(%p1H^gE%;MkDV% z88WSb>gs*=gsC#^(Xi@3Cttl>uO~w4o?$M1vM?-vbb~0JPWdE@>!T&o^CgOz*J^%y z%fnQD|#!}L-I)!q!Mjh@ns6{d9!0D55E2beGW zG$M`+=U7~s@$J?NajcTSgK=s!nj(++}&U@?5vbq;P_O+NOl%aOY z9W*Ko&i|hRc~69T_eNdNUVRcu^`UvV^NZ@4d>NsC60=D)T(h#Z2iy-1C5!P9hw^ZbYNMX7N~nd?6y_OxeKcxB4fU5Uau$21!7<+5&nmP-Oqrj3qLZ)o=!Hkw?mSWc|l&Q?Y&eS=47NHn@ zC}>g{hxMu*tLd*}MF(V`YEB>c5a)<@lIGg!^`5>qmgJ?qr@nMUy!w&IChvxGP-Fa3*9_@X&P=4f+K4ROUamhH@+dvuzjqV>2GKF?SaHSzb@fboGky?NOixFw`W_4Ka!Fjr+c``!Slb5^{q0l-nZQ&~!@d zp%7twE4>7Pq^^QrB{BwLKr5PAX#nCdq-T|(uu8KoPo9A(I*LwD0vV^s#M5@9_H%4f-i+i_P@kl`#S2}ED*J_I zB9U{gllKjQ1KuS%Ze-GORg&bqzkZbMMHN@(TiVRtD$80v)UC2K*5_O-w_^mS@U8}S;dk~yrFl=66^(c=sQ{&=)RCalZ{{BU>jXk!EJ?C{W zAXosk(5WaCV=U77>_WuJJ(ch>yiW*c7C5#P(ReeMt423WJkRFQBy=Z(du>FS=z%X< zYBVfG;Vt7WwI$Wg;K>Cluvnbdd^g?F4KeTninDXUl~v*i{@snyyk4vpCUY$q0FGZ} zGv_k=c%ex@{;_jGo}m0RUG!2EKiEdV=ec3F2YOTw%_{L+$;b}$8M-E4!}Y-tMvXZ{oSth$x5!xy?pb{RqtD<7B?-!5$=E6y-(KiWI=cqZj&E;F z6u3~?o5P83z7JJ0gc@9@m$=pH@AL{A&(fr%b23l+nF!wNKION+y$vF|^-<+Iv)+LB zHDRN-vYp-j`kLSalJaK2C?e9sV|`I?^DOX}G`?l+oR~^qXw3?hyXMNfMCv%_)7A^~ z_hzC@Zt&&JFs3Q=J9Q*W_m-TlPn8#K=#w`)TwAw$re9I{A-Esz9-_3-@Ir5n?A?&1 zc%GWyxaFgiJ3`?*<4?iEel%RT-;W-U@eh9}85m*N)^bArG31$y1cS3Hs%+(>l>(k!lmK4VH)ACf z#{}pDS=3&F;pZ1%aOU{tQB)DSGsQFfRT5LG zGk3CxsO9;mkJ*~S%mm%(>@>jN(j;Et9hD`!JjwRkgL0{M4@*$su`b;0Y)&ru@sKw!aJVS3Jn_F;b%XjHlK27 zM(r+#7t)kvW#okth%2Uf3%0*pW{W4f_+mY$t#X}bo*a3z+_y4IRItmCZ0uepI zJ8t?y!2k4frED7d>tKsp1-U^lZ}9!G8_X*b+d>)_^@_ucGK;vkcSooewb?_#By~B$ zmo9k4i*`?Isz~wHbzD+x9l+&_ixT0l7*@KYlxn9V^OCv-Vf&_F-K3C)ux1g2uRDmm z#jcJtJnUA?B|sZqWs*+TEqPv3!<(T5-BRHOBrobC@hpB8; zMj1wxxo5LS@(P3S*%5tBX#@L0gz}@47_bl8JKDA%6eTgsC51@a0aos!cKng`b?B;_ z^v?SXf4cl=?o8IkUL8);;~45S;U}?VqaL>U;Pcr*U0^S3X%* z390>T^!fWcxU3z0f8FaAYHodoK;(!M)?M1-#E&JFKOJDJSKu*q{A>fJ!T(6VKVR_o z&3751hC3n`Zsq&?&%Z}}Taw_o%s-wP_@fK6b9?eh!R(CC`hRIa|MPkTqTxAp)3Wd8 z^u8~5|L4a|53i$d@76eo$0sWVCCuIIm`3wWn&*Wb2+3Uo#l4 zcZOBFP<2@7AItAj&hQX~fkY5hOPi^A!He%Wu0DAA{}$aP>LP?uyKwr6b!+HTrrwPD z&D?W=97>4y=Pwp)p3;H!oD_F~DMJv@qp)>Fi+PSqWv?$vy$%>xvAHiTyY-Jx+=oj6 zhYt2EBqlufGByD_%=+fVP~fZ_4l(U6`^(>ZxeNkq%Hz%=HGUKkaBK)Y zyMVwI!r>ye$ixy5zKAdeQN*Sf;ct!PXB|y8xBwGRN%7{;4^FK*A!oKEs?aaXS?l)GhH;CCW^o~{>PuhEFecP26GmctSR?M zg@LXpg+qtj1`Mcu(J8JG%v6!?i1#2e@;?*%f1(4jVs@?qdr>WS9e-=Nqk#wjX&D&h z_={6u_lasz5IoQGUt#n=-qkJ;Vn&LL!LgC}42&7)%X@NQc+URKQ~p0*{wJva@hg|8 z-yqgs3X7r44cbHDu~g8uP$zsJkH>wwRJ1kdO5r8J=TGqurZ-E}|o z6N}s*p%$Y9Xh%yWO)#T z&i|E~-`zuGVFVWIS^mv>!E0P7FJ6oBz!ttM*#duV67-_i5mUPajD!)9+YoGO@X8oohTU@ z-UX8%Q918s#B>YRIWfbxPY-`{_>0l!+*SqvX@}!;-Ek(;)gUxSDAn>cv-cY#r^!Cd zKLUM?o;&~a7MR|rEP8cAbk)T_aqNrN8u# zeUX1|dIqlJ^$qOCsDDzsBo6~vD1@eu6ap>)%C#{)wbQO zh3H@aL6WVK5}K%>N24`p5b~}G-MLnG-s4>012+_NFicB~yV!9Z3IGrE?tpBFP!rl`@0O0}-PNRgAf0F!MX>F_dBF77nG(@( zTJkQ4ZtCBL6bQUKt>s1Q#%6KeHCd$3%mK?~0x(`?HOo#phFj3!zh3B4F_S=Gi5sNv zxKtrqC_djDCdd&S3vdl}6F64iWcKb!Ns0=WSJDl#fEN^UN?G4W4ER$mf+r-9=9@$q z=~TmSp<1IKRM4Oa;J0$J@Y8I{Suv`D#?1^UpH z#~}20v$4t-TNomzAkkKHeKlxwn1YOcPQA_3g3Jz{dlQ1a%7Is~C z+2I@okpRvqR<=Ro5=bu8{3;GI-^zlk?IkNKP5TA`qhH`;G&{FCaw=5j8LDw%U z)lYY(p<&9g4CLxgFuhWGqvjS2&!TuiEjiC}bLvs?ENX9e=UwoQJ-CIxz`^eqkU8Qc zOzP*@qZlia>xCY?5p~nH5)!`ksHk&KT0cw_$s>L)n3_&@m)u#7w9lu}FOv{4nRc~^hs z$g5xm6|y`#B|(&nm7^or5)$sbpczm7gkkhZcFDY>yRrCr8EgYjpO&wN!g(ZQq)tq- zdBjH{OPw!_%RDjXy>?8~c4}2JYzpVW5>^4U*k$B^kxYe?W9wqDtWvgyOOB5Y^=i-s zk>gVXMS09=VNJMJo2!PsdHVjP5buGPq$v9}S5=E&Yx`63-MWP$<8N1LV@VXx{4jnL{+GVvzuIf^ypES zrq9m)L&wi#kv(l+N|nzbYs<1(8d(M>JCJpWFJMLqjoU5?cxy%`yyA-8mJ~ z6{S~2Lb^M8b6E{^6~>#R&0g1LGSJRg^fn3A4E*>u6ae8US{Yja022iPra?>I7crYW4bzvP93D}Ay>>6rEWfZ?`5fP6@E zXUsTlh$;J6J z&uuuA=87d_EQWKmu3J{*c3EN}j08s=!?xJXhEzedxM?oegK=+4l!`XxTzl^sYz0MQI2#Lpd?*n;Hu{9Zzeqg|rT|knRI$$RY;T_6yt00N z+u6#}V2nw>=(8il#w94LUR?}UIi<=4fZ|!f4JbY`F#;~xc7y5z$Nr)!(N96+iNG6y;$u#cH=KtQoto`Rinn9h zXO+6ji=!c@nVB>V=0{H}b31Hgm%>D9JhN)9DU#<<;i3Lwk*v-6u}?|=MEh9Fte5+1G7eMYZXK2GIH9Bcc4~<-&N3yF$4sn*_G`}d z733KmNo&`=9(l{!g_ix@@i^Rlcv_;B4ETv+o05^-a!?;AWxE@ye}a3+{vqd+RYg|Ke$fZEvgg=IYd`*C}GPQ$uAX15l1J9{%UJ+N=&Ts^R89 z-NV%0PBreyj@7og;}7zg_1H+Ycjh~t=BU8}K4xFJ)cZMert0c#7&mk-SO|i{E35&` zHrFMun$TYSZPLmUYC*1vpSO2jM$$>R1C`2ic;vh`**UK=8K0#^cj8rPZS_8~{3#d- z*qzKqxiR_Qwvwi1S%w_;(}& zCSk%51WCfE(@@zoRA#S>o$kDQJorG((x!5*&fP3EwXGC1|I4GKj8C!cpA>Sms^3nx zYdw3}{qg0c_K~@Vjri0WL@m^c)WPqMpvc^$ zw%c4JZ8A5=i8x8AhqV$)%09d{w0^ z)fH7@y@25>lqb1-uQI36NN{HpOW}qB9A4oT&)w2(44)rj|H!V10~Dt+?Fkz`n6MOE zA7(QW+$C&CquKcv#HUToRUhaIMhg4(*-;GENuE1Wr8%~q>|)_$I!ba3TpE%R<=v;Y zmm^>814gm`=sA7|#Z~>8u8dsR>+|@*F2lzLxPJ-}0r)P*PHjUGk)=@#?CLZO6QMAf zXo|c`-eK{o|GGx&F{dy_&&D&SdkTy~AU~=f^|qcV)nPpBl6>U$XvLwAMX`5oW&=07 zq;KOV^m9sg=MwG|;|4J)ss5G$yXk;|%7Xq_k@>_qkA93vgmy&t!NRi@rG7UnR+(Bb zCMrrfT0)x@(({Ba$7nPNT*n$CINS!f3O#=sBGjKQ2J~hyGhnzF1m8f%c)B8z*LImR z>H^vg6{7msbF|3tgCZ_`aFZfO!yrw-KD^Zm6NL5E1<{E?xxQXWVeb9YoW{X@f!8+Z zgOc2rd}DV*(2s)W;@9OdZ=Jv|YjHx}+>|pSi}ehO<5s4%-f`#Ej)2EgPOs_p75(NY ziIDYLiSq%fE->#$ihlHfrp&4hfgLfOy!hj>I@;oI9wRzmGPXeFf(IXWceb9LrIvja zUG-Di?816JK+_dfd~6iPISEqH{8!dAR`(LDuO2!<`D$as=Fw3zE(-GG;XHjQ4VKvg zosWTHbbucC6k!FhnNqm*%ZIq=CsP0=@~(pk)qjzr1j zwOWZ)n8(pxy{Rn1<5rL%E}=*9^QgK4Xn1O0>ww2*h~j{h<00I1+VLTAe`zi z%+jV}BH%VxY>whX!#d_dBz!v0-5%&(5zMGY2A}K$lRc%XticlN2>4{v!D7n~{5;?G zJ?DZz3!PQe0fnEFqy$m~8Q@7wF3=RW#*3Ilw*uLwg*OdxJ#e%SBa*6`qxB4VK!h+y zBwvFvB-`kj?Y6TO7Dd8^N*~il!`35V2#YE&CA!73u1k)rGc^_u-wqwcr!V}|Tfgol zFurOPU)-UUCZBQ6Z05s@3&@k7>X5YB;$$-(Dpl&kn9xCs_X4839&BRgy0Db+-#+ zVV~ky1SP|+3w5O{T|hZvgO-N9-3iD=AyC??cOIYm7m1U?6fp0K5>2hYR!kgeI|DLD z2r$QD%cF)Wg{G1D#=SDQd8SBHjoHT(>6iwIdcHQ?8e|CVA#7=x^@2KxPiAj7Nf}iY zp;aZ3j}9bGl8VMq@Uy*BAe%I&d(k)OCt=$E>?mm<4_@tsCjvf)30J*x4!s@wIo~*Y zk9v>+o7|jj*q+!{YHR)|{Jhwf4>?CusOK2S@PW|rJ_s^FDmFX~2?e4n*)cCeoOH*n zHOx*yE~H$|hSk250;BFa$nHy^EM<%?SrOQkS>?UL&JU_AfBC3wedkVObZq*@#zsKS zejbk#RL70&ocNq~ODD=rDd7L_n(Lx}(KmM-WA9|OL(@sYYjaJ8v=30e=73@`a}5Gk!uux?Ct`#me!S16W#B16DBDpQEW4uY37`N6JLZD%&PnAo%tv}fZ zps<)Bovz3X&pdL~0Ube6e=u1wCk~;9ek_lsPQKu_8Y;ET@Zg>YlEj^!0ir`&nnG5# zU5QsDk9D6Mxg|HbeA8<#ivA1&$@8g|#s*!xl3Sa`ew2I<`e*N(^>f9xZTrk_-hLp} zzXx%f<$JsK zqnGYYtfp#af!j(9VCZ!*-VBx9nLuIa#~;+r!K1GRb0qewklCy#Lx^kl%gtDRZGd#?#i-B?x@y7c8;^pL(Oo$A zsx#Gw_M7XwX4FOh6$ZvPy7{|=lb%F$MRQx$$tp^Q*be0CdRrQ3I|DU{W63FchHr8r z0eGYXDfQ$S&z1fEf_Eik3yhzpydme&y(kB(?oj035XMpu9z`aTzWgQLA$U&A1rVVk zP4++*z1y9sM%yOiL1r)weDT8>s7Ej1c#ksdJ*mt>e*AefG_Kri^{=_i&-JGhz;Uvd z(38JYHkq9{CXaIZiZ+Q*8v|unOTnZA#Nm%QjeXY)T4J8FI5ocJk}cm^Q<;hN+X5E; z^35C0ek%eaD9O#3MrAJBWt~Sy-b^)U_DMq9K6zwvBGX+@Ea)mNP^@5};fT8ciKv>B zl?Y-?Huw;bv%fmW_4xMs2q*bZX$lZD$^&hdi(&-s$IjA_9TROz7v**fa({(%i~i}( zmi0k&Aw+NNz?E(6-@d3&AIzW&B7^2!@v#wjQp=a7GmR2WIp^)j0YZM3e;l*8Q$xz{FZRT@TZ)KSf z{}*VwdsIghKUsCvxu=I*THn6ynty+whn0dFNIBYxS>R>wWwXz0@738{o1+7;!SE%@ zXDG+rDE=}6K_aA|-1g*UkwK4`K1G^(S#c4!v5J59wO8(CtklF*R8(EHnQ?%GGAS~& zDJuUDdv6_8<-T=~Dl)GQHBpt%E46 z-hm$*hql0DCT(_eRHyAWelQ1-(dFDsrni1`2%EVKpDtTar1bl?ptN{n1}3+Anj(s2 ztck;1+y7cOlBj8k9jEA3_mN-4F+pX1AZ2@|XL-q-{O3|fj$)*Jhv-EMSNF#wUE!K1 zz3KAjKXw{;PFCklt6}R0$RTwJyqJiip^6&JU8lF8;JTW)nbWT5>a=` z^mO7fl|BgoO1Z!ZU!P?Th9LC;Sh#PolE9XT>`Gf`-)GZjkO=Q)v)zkls&t2wJAkcz z?ZJzV60&Gz2}4U3zA9nj^l6lP%;3DK5nv+!2I`9bmK$gF!bqwzFOn8S@VOz4It;g$ zMjl(I$sisXx_5;a%B+Z7OhI&76rkk8ee?57*>#3R#>VYY%Yw?OCF zumPl>N#I^`xMEE6LB70KE+6y20Ykpx-w33CWd0%y5`(lSL*@SQP4von*zq}694XWQ zS^47|{_j`!==oRZJju_8dj4$^{_`jHpS^gHCmVnMrwjYL8}U~A zWBfN-i9gETTmp(6{S<-g|Mu;{rnp!G?@ecC!qWKvzL9_VTleS_)lA$(bAP_wzkTI# z^frkasIdW$sE8BGmn?{);WK<(m(I~AFnPlem*uK zH5b79{Zqb2CzbH%tT8-mEgG7vjG15bZ4pM{IGy*2rhhtWf83(KeoaTgouo=~G=!5bkEjaAtTPehRMI5vPz#V7v(hhusWy(aaWb|VtriKF$)cl6Tq zi2wHT8(zTWGmo-N`~B7ucX{x~3#1XaHUZou#bl4f2rSl`80WqEcNY#PypupHt$s$? z`qqE)lo7+DiM-2<{hypl9{4w%`BVQ+LjUL6c4vaCbk^3p_#eDC3LtJ*B^b7b|Lytx z=|k4U#CF~N(m?UgU;M|(_}@bS{|5XUq4o%t|0HT4u`eF1z4`F)KX`8*GY~r8$FLa+ z{4WRYfBIR@mne27&r!YlGXVent4@eCL_8*Kum6pU|L3>t+yDXw@nbABuJ}K_kN@dw z3AZ7CIHIDUt^S|>`hWb|iV%c#CLi3tML#eW|lfN}ntfdJw8|CE8!0zxAH=>_obhwuMpBg~8c%|=j; z|NpO?YnW@k^M6-ANxB{^DH2UfS&=Z}KPO$)tm}0FtG(2ql@tw5TJn)z1+Xa)ZIuBC zJb`cb^Yi~GzZ%9dfWMQ#2f&VK(d$@U>V2InCp-u*QtSj{q~iVp8U-9-`d#b4&F8!} z7FPM`ORcDA^ZD)Ch0W*x=yoXF`Bg5LSRPeu%=f5l-NdYtDF?4fN_ob3=iRkD^AWB_ z07TQHVn3n*iw~GnZP9e#aPSVm<=UMAq)WM8Ta>a$C?f-U7zuvkqA3#5NkEtQ;F)mU zBlWCNoD&Sa(Qs0lbfTv-058(q#W6-O-(t3&5~Goda~}rHmNZZCrd}k61^bd4Ag*~v zoi}Kt6JDcn-oe&xWUQ_O7iIKCVIgQo(%!bG{W4PQ^84H=xIY>BsYYk(B^@eLa)r(y z_B`=Fu?}PPap7TP7`6){`8yy@G%&6SMw>IUF}<=z<2l+GAj|Yc4@Q8Wb{UmSap@DvH#v!I>~#r7h;VC5;i z8`5H9JK^Q+)Vma95tbXgHfmNKcL? zpHwRy2F;DQ?|O6Nn9G-2vGWDU?{YY{Jkc9ZL|KbaYBP9LYuj1Qf}uR%fR;OX{Dz~?DLN(u%OAR{VX_+|L42@?UjyZoZcH+W*d|W zr}bRY!a$LbYd8m$_H6wJe77G`fs9BiaHSH7ejLc{cCs;sDkX}?MMWZ(i!$Y#f3t`B zklr?Vq@LTC`C1r|vGShzvxQ6YareYzH42axfl0!v>Kq@d_Tk$=!NKz=9(5FT+?*q- zP>TMr;zjOyH^i=|$zgq}5sYn_V3vcsb=LG6myIw;9`MjRGveMWV#+)k2V!_AIG=y* z?pMx#%z?aTK760k>WA>kAn(D7An*+plYq@r&Be#TYNU`XMxyDtVNI{e`1T&f` ztE6wfR?mLzlMXI6#IS@0Whiv-q>Us6SBx$yaN2%3Vq%MKvp@D0L>LcoM@78aG;EIw z*=#0mTvP7W6Z+ErPS?$igm~dA)?ZJ^2@Dc3{!lL#FQiR!63mUx2x>Mx2mhYt{!h9H z@cJ#{;=(%Z5p?;EMny@%vtAJ(oZKS4uLgvcmX;khZ~zM!>bu(uQ`bq*VBn=~o7@J3 zwhJgxXtX?tK~(`rZSTZCl?NwTZf^eNU-{`@LXBLpkN5cd5NWG-4`5SjFR zEV{tM5PQL)alLS|DRNA9M)XWe2#;5f`Eb{c@z~+%@cRoy;m5r%+NTq!e!Zkw>CdEM z#$(7zR-+Dz1qE)K84C0h2L94FGqa336JY31F<$%`3_qAUWBGT1tYbEoF-X>mAhT_3 zWHUiwGScm&Yv;!BIEjd~@P@D$O6Zn0k2m78qvtKgsLXJ)D{W@)jQQ%BH7^WdCkc79 z7_TOj8vJ^rbcEt`TKC?S1>Hb2-AZ?hvmV8Glhj-_7Sz^Wbt&~5(Jx)52kz~=wsUg2 zsGIA)92TR)6<6~Pfs82vJP3g~o9PKJ^79#q7;rB-s1srAXzmmdgsnOdb0@ybcwlaE zsJIz8rcvkDD>Zmjip>|BOI-aXn@``v1}Y?U_S8laum0J#|K21A@Sbi`z&l>+UzEt7 zY?wt|`?NTxy8I!se9Ncb|NO5|NYay&<)1|$hg`ELN+%`( ziP5jV!<}CQC+Lp!7rPy!(^WtcyamMfPnB3%*O>L*>Z*#c%4Mq!6l)(|YcBTIq0q!+ z-55%GN&rv9Tc+=bl!w@^h?JDZ%0HX<-(EdZr!b6hmgY;rsuBs>UKah7I(FjrqhBBg zinADyEN~(hMZG#LLse-MGQ)tOEUA#KM&o^%ArJgDU^S z`gHq{#w!J2AId?*p6Xw+7eqQAxfD-LE4hx{{!XpVUxS|QhSYi!6CC7e-`vrEB|!A+ zar;Ccz^2MRyP{X6gnX3!FYxZzY1RV71e3`-1+6+qjjc;7vJ}=+LH-sq%k7{pxVV}J zKEl5m>U?4(`EgLLJ6~5{A=yT`6fiAU&1I&9(C#U+Y1FQWybww%TRB4nh_+FYl;ID=&uhrT&uVi8ixc z)U?wg^S3E?f>E&)eg3~ZE{vy9jM2oaND+lh+Fd3Z(of{q|8kvh*}@kvG(u8EFKjpR z=!u<-9^s+(w#CYU0hb&YF5jz{C4&Tk4*d0Yq!)#0JYcn46GQRvjVJzO;%Tx;8PD@U z5jbJ+FF*A*hKZ}swSz9ztkK+e2Rny92rK7z620`dQQ~;h}M#!Z2l-aN` zFmrv*D#UAhIi!S#d$MCx-RkJTfkr7QjF4VI28W1&rgVK$61C$>?mY43^gz|RoJ^8jDWUq{#KNp> z9)~toDb@3RAM(nX8`RD3MxRvQsHH|!>G{15l36Yko<{uT%yfCWd!D?5ouudybilEj ztzNFzmGtys8JF#xFwE0^mvx##nV7&r+Az1ZViiVQ%^-CToEsw!%XzoB!C<+wqOE(Y zY;(RZW%=sn>Jp$$ZyTk4jZr(4xw`9IoTSBL-BR0|*XixIk0b@K=a=2SwS#T&rJgm` z&&OQBcQln%#yZ)41b`U)X6yx*ryIR0B66uW>>q3f_81Qi4*n>~sZJZa+!j>&kvGU} zUXi3a5!fPJTkSC{#e|F+GIQ+Zk0VB{QZC)MUNAMjU*P61M$XeCbJbzH%hMMjJs&B^ zm94?7nC#;$Sd_gl-WJVyy(^h}uhw*T&NgX;suCgbQ9*lg>V4vw?dD=~zkt)4ZuGbP zuHWMz86wThP}{dEt=z9d==eHnFFsAXZ@=Y3zi*zG8MW@4sm!I=7R6=EE!H;d@FRWR zB2>Zt!T11|!k9@BhcNZeVJXSjqdP_NiT*$-D4N891NAskFAp9Ji~ zI!R#gxRgf)9pHA4k-Ox8(x$0+-j`MCnXCDuGWMKBH#fS4P3*lti^hMXEB^O5M)#Xc z8b8n#&q&5a@scnRU=6q_6VK>ws~oP~svZx;dQ-RICKBSz(wUthU2HgSK+=`?arpR~ zl=0x!`Fhtu%Lm$anY(8nrj!!!1)VA{D&1n^h~cyq*gDvC`qEy$HnL-nkjcV&d}1Me z-kboBrZo7w*LS_G>BNz;`$eZ;YPw|}3L#(Y>nk633)CYA<0cBT=3Rp+N0tMhZRP}? z(Qs6KA9DWi<+7=Omg$<)t4FV795p3`1eNDqRVbLotj%7|M_cU^w2K~nd8*lFUAr** z_=Uys`F)@mY1XF^tUkUY`O1OqcvW)t;Na@ne2-u@`?CXnwc9EUr}O?&TNo>hLpW#u z!ZLNW{gm<2*%|0>G0EJrt(QC%eleDP*sXcCVs!@iz&C+c zvl(V?<|2Gg2#|?nV;tvb(vNeM)y3@?JO=S%6kk0gHN_2rh)24t?Lyuk z46=fY2O{pBpFbk|Kr>29r;vFUc_DATiwn;c{IhK9tlq$Ts+29h*_WeUu7GZsoXw5j z_GE#Mzdo#R5!e+Wz~V2rwKWr+ZO;YTQtgXaW6SQW8B<%*pu)>+eJhC2z`@w78rk>m zxnR3eKlVoc8Yz=<-90UkSC2IU+XFeRFViT;KT9w?z=>MXJ9thqn&Ewk7pJGR((h`A zYC5X?i_%_a_E=r8sQy=$?c4OeSBOzjY^ruNZpznbWD%ZG4_tec9QMo%Cin)N^KRR0YYpxntdtXzDa|~hm7H=;XL~FDT$I4{ zn3T*)#j$N^iFNpgf(`1bNhjYoG)+z{?CwJ}Bk7&@xkLL52hV4CN@$;gqG~d{{fd<@ z=OAej=x#C1JD|y*u$UwBo=IRSgC^3sPR5CgAOtI~AQsC8Luh#xtjj)t4&iEiav-%R zR>Tb?5H-5)OVntv7`EY_6%1b%J+lXAWfJW3J_3u3+b`q0aVl&_%?^b15l?~X_GNDl z*9de^q0p3hwb1J?rslsjmJ%_P?~VmRnR5Ay!M=SEx?b?P8{HOmIc+9WY!0otC8^Gb zT_K{?FHcilpX$$MA((a20pe(pOCCT$_;Eu8#vjoFQD&g*bt?BJD6>W-=RZ8%1iMz~ zpqs^8c;6=1`$_jn%`GM4!H(??U@^JiwS;^6?~1!DZ!8Y=y{IaEv){sz5Ua`69C5_@ ztVbARb41|rYSN+}Sm5%b;SyS@>Kl;G7B|bPl&xvc&4|On_JuxvpT9(u-_CC%aoD}3>zsBo{DEhh zLa0(IxQyd*Bl90-mv847?^m8r){f^OH(Lgx(DxV~7ZC-fa9yYO2o_{eA9*PQ{YEhL zL~}bMQw25EltsvNy_jT}@|>;14&QR~Ir7#3R{{f(;4)v+`g3w~^jbMKNQo_T`y=l< z9evt{&oq2Zku0vk$sFbF!k4dbtZ;2N`}=eR$(~^7XrGlg6x`ovMLy1FnR>6gJx3d7BQR5%)??-W`kE<^WD>k339w*a3s{P?w&aU@ye_HDPNFW zgxk9ek%2{bgOZ0nS!*y*3QHU~OjQjJo8F?OzIB1`NXMDoux5Om!J6vzy^j%CPd4op z4R`YB(Cp4tr{w(1S(%Kd3|vETjOAPaMrx%>g^Kqo|6q+uiKQXE(W^BHs=n*&ucD6H zW&y`K19G^2)t}sABpH@z>{B z&8S+3Z1bXP)5Us8*IJxDCRx7g($^Zm0QG?wjV@c74bXq_&>P=v{j*|14_li%wT5wcGgw!KmAldw3?ipin!0Cm(2Av1B&(mZvYG^BgKnM~4QCQ`?ciuGvwmW)sd zx}m{pl+1@F%YH}9?sImuAEYnarl6C%MBk($Pc>83O_DRe_S<^cGxQ3l%13V)N<<6S z-I?%0m3&cMF{x>y&ePf2SULHiXQo98wYJ-Fl+dg&7(C{t$_U+Jp$YSxjdD$qx)T?O z9&MCsp##EQ;6lz3r?6#L41O9J&b1#38DI0`w4VM@9^=p(cFE*NUUb)SH>V7gw^K`g zLwjyGxX!83Gd}7bYyQxk5Z515aD}wx_0m%wOd)2J)^EA|KxBx$ICK~&(k|2;yTxG} zAVZY#rf|9~RFib9gEv!yt}U8}it6|ruJR4K4rJz_l)IAAkEEXEF0DvSIP7xjq9Q&+^kdr8ZpR* zW^q*&)tc)K#Y3H)p$B^D z!uleC1;=c-q%-V;5s$@rh_w;B#mFh|^I@uw46A$E1eM8s5yKPCV7DX?(!?4$(_+uHkAnJDEBn0pyp!Ts#@^_< z3ae@Avg|s3JgJI}lf`^LsZ_WAgT?oZtE96IkJnk~K|cNXj^eA*J=qKehVo|ixdO;{ z2P*jn;zPPJ`_?sE3C`I!cP3fx)co2Ejmz_&lC5ev9#v9U8C#5OL|#{|B%3SM^te&W zvyEp%uTYdQJmTc8HaeHgA3Sf;*)>@+*q5V3s6d>0-_f$lXKwqER^Qepv%g1Su=SA! zV~t(hvHWHFi2Gh5g`~pA?NcK2+-2_>uckH2&Y9}*c>07U=zm%6TN?IY`ms)U=O&Mr z+pP;oW`QP6h59R^^*#ER=h;nk?TwU1viaCOdzI-z+9PhQR{=@AKg-PHFnu!{*VMC8 zA!~WK$fbMmZGI;L<;1Y?IQ1uPAH{o&vW@6A<^r8s94g$nW|LVTM$GDjos0O-X`>5; z4IR6t5jmuCRqvzww_bW8onFii7o&tQxnYnZt2DV*NUWGIJ zEf1_ema3mpA#Lg0g2~wXw!60AWEfWd+LZjh<>&ss0S{=4si96{3rT8; zY1y{Dw+zE}hd&e%>^lWU#9sZdRGVY>Qq%P*^ZB3Q4Rp&*hH1l|Y-nzJ$6sAtsI0h5 zY}9p*O!>i~_c*;QnWwN^Xy#eXwVTO785*j4KH;|*xQB0FxNwCAPo@9(O@c!Ut?kut z`^g3m7c15_m%U>)(douyO;=pbwhGx)C7RVWp|*6P(IeXXs&?BIY~sfTPUJ;2NV9Iu@NnL0AMb$As#=7Ip+ z3D58e2=er(xNQ3ZYWzw&NjtvHduKd1l*=598*)tgvi+tcm8QUgFysKSgzdgt_C`&PKTb+VVlR)AJiFk7_(o)a;w~t;X!g@#^ED z+;bnW_6~Lu*SD?GR!J_GWDDm^wU-II$nINHb#3nUN~|<9J+1qdjR<b8J(g!F8G(h-Jcj18N2n)(bnTjMlcpR>g?owv@xc|_8e8y%w= zin*Dwv#PN^uX5$5ln&T9NW*3Fj(kki$vU{^z(-$~p1~-)ufwD58G=QBc0rP>90lNs z#nQLECoEHwg97K77k{+JjumWg8zfnFjqwPzJY==5H0Ogpb`5IXQbu)>`;S9oY-r1D zlG{w}U}X`f?OBwGa5ju^s$JGS9WFCjyJ)E%UlhryIXEK?QE!L`%MY)j?DT|9Q32Ww zsspxWg!Wv8+Fz;CGwDWanI2Cn=xk8wD<(8Q$9j*2+$eoQTUHT^ zMHc;@(|Nk*HbdV$vmeSmcGRDdCVhGPYY^He0_!%~Yj1B1J0*c-wKax^J4xAa*1JG0 zbJzVJRue7q)n>(GW?o8IQ+4I#(Z%IX{NXyxnA%n_ui|BLvB2cS%2BifI(1f3Pe=Wmm2cM!5k(b zzk-t}y0JCQh`(Ni_1Y%5Hb4HO5ed~fP|H()BBjqx? z^DjA{{?Yl6T=<}qD$jbIYv5pB@@)PchAmrEdJ;3r3{|%!g?DSDGoz|txl^&oOo`eM z-ypWjJejj0LCs=H)e>av-~6wKycF_wnwgaheXu)HBmIuk z+f^Cy{W`Y|#W!tG{^l+w${t%BaIT4|Ip7-{yq8nEGK^m_BDHg1USu1^BWkG4Ow5x*db?<5EsEQIses26u==7+@IYWOc#_Zl?0!1* zG^l5i`=rUL1x6oIkWUxU>*)goM-0r*&4%T!gBx5k8ve{WzjT4@!TqO4)hBgq1Vifz zB0WSyLL&YuB2CEE4Xm75`q)Nq)=jBu4U9z)D8$|19 zL2Br;-~HSMs{-~1HLo_n&9*MPpAjru)pIaxS(Y4>etRcaCeO$F&s_K0D|cW1cR2D% zbwqA1oC9~X>*yJtm)kdN+_PvNeo8)g?NVhr44BGd=taNeoggwn*)Jyg?wxMQ^5?xB zTe166cTAvG^y%WQtZPFA-In(#cL-YpIWyJ+&pa(XpTe|J=~t-Rts*Jv^(>W620bb> z2{pSac>Dz{T0|2ym)SyPJAR_P^G6U;U|&A0pCUZy`mAo%^z|LVBp}E^~Y_sK)yv4}bMel9w`xGYf{ULGW0;YhyRFcOyN>J6CHwZaUQxPMOk2Jv@iXx+*iR zUvHKsb~w_lT%Re*frO@!QdA79tvgdW|Fc1YCff^L#R@Ey1wXbv0Lm?xEk-M}g0cLg z3{=nAF`J<|7qEp_1})P}+gfggon;Ns&3 z=g=q6s+qjb%dBQDM+mXGr&aO2W7tDF0<=bi6o>6E~t8T z-e+;ziQ(?8pY=IFGkB>*b1WBaP-m6C?I=V_SPJVqeaV^Xjlzs!8pQmp=guw|A(~z2 z6?;3$4^}Ak+uqX(0dP@5A7L1nx5I$ zM1=Bt53PEz&zow#QxBBM5j4b}2N9@NLx3XQ(rn;ciDp7i8wo1z)zwu1gAYyTNTWn0 zI;o|B>*X-?Inghp`my!OJb-UH9H*kmA9Ck_aGoEPiV3!r}ZAQgjRsvNX&-}i^?bLw=q9%nGf9 znxsAA9V59h!`|twkY2jU>C&-V2Q2}D`*y13xfWEGmN|#aM5yfFMmHm7RZ%I0IYUQ~ zhdy3ESlh3hva2lksV57F!5n_6RmK|HHkZgEk9c&4nuoKltJ28*Y3NQ*EVy@2g)lO_ zU?}T})~q$IyMb5U9}MG=L3vRSP@BzvR8dZN^e#6%fEByQZc$~3Qg_pS0c|s({pIyI z+kE~!pmmmG^PXgI7RfnX4@wp(_gojDV4d-Cn2ks4gQ2C>b)sv;iMlBmm2cC7Yjk*VZdY ztR@Z|yvU3*%A`8+yHdqf>%CFAeRZ*+OvS!7zpUFgfmjwbP4$CWBtu*gm zO)w*Zn2y>6)#FXne>#Wtk*-G5T|^XE$mwwpg~dqLJa8pu@(2;0?%@yNWKGh(Rjz-E z$~SRwY8z2l#YmEx-woU7Wl_njrBzPF>*VBMpF=UQEe8NY{dgbJC4MZQUK2UI<^1XL zfk;;SU8btrX}hJ``ztaf%$vONvO9HGepZH}^N&Zt9jQD4B4fK|b>`*f=fHyvxM_ zeuWlRTd?+3vcAUF^KO+l`dQ=LJY>`P`Zj=(bkq?{D+T8c21$TTxG~cy7-jH$ef~k` z6|~QfU&_-Z>rRi6moHJ*9;}=VG-rV!V3gMiMqlKajS=V!vmp))GHu-QQ3l zHOwOi)oHZX!$741Lkz>1g680jR*TqpT^jt6EDbNGy zfj?*>Htc4__yuh;gcf=?k__HQnHfu&2shH~6oSTFPxFZt*4tpX@zqS_V12HB+yP{3}(m>eg~ z@U|TPDFswQGp_jVvB_58i31I6e3G3z=9J|CQSbvRpq*=Dhw&SDwv-PRK_e9zW1 z1sGV7UU&m!u*awj+ZDK0j6aYq+*8L4dfAdKMMFNCsOM3m_E$N~3+#NGTr*uf9ULT6 zrluduk-eV;f-ybCzqoe=3}S@m>wS37Hs9z;bz3g)nDlYA<|p@ zt?uf#+OAK!^@Noxun&jJF9%4wdzGC7XTY9@q(TFabT%-jQQcGelpT-}@KdyUz(L1H zUmuojqI(GcHoh|#U6w1O zsA0ft#Wf8jq=13A8yHyxUf=7oHr7gmDipRzJW7#mhAjxb1M}ColRU7BFD8>$GZkxv zZw{joO7j}_bxN`)n{pC&ytl`D6%3JcRm53$CKYEp6TM6zrslwH513g)7#Gga zzm=GTtH&oNx1jf)@3}2=2pIUaa;1@|mzrGj5scFVDUv^yhptIZeWJ{A^F&Nddp^<8 zEJsvY__n4#V&`ZTxWjbN(0w_0mrB#LoQ85rqoJb*MJNU3kG&VHt(`?kb5Fz zz{@f2&!xt_SRTIgdQ(JQzLR%Y+&FcHymR1z-cRU#z)t<6h0#J zX4Q7Il~!@FNgreV_efS_{4ND3TmoFy{g9F)Arx%ez6Dt% zwRYqB*?)n50d2NaX{dut0De>xTpJ)h=JsFp@ z>495|&iNUmD-CI1Yir-N*-RR)l0Lf^yMC~{UKf}@RR;8t2z!@-C2)D1zrS2{?An4k zp~ln`{|UIb-?l1RS<*RiCsfRe)r`m8!R_-5yRTyL_5nDQ=rsgTQXYQHOFTINXNHu8 zK*isGvi)vO6_vRs&0(qbrcWJjb&k;;>woRP-+l(tPu^}{?1Pc4wjH6TNd8r;;G1p} z2{Bk)ZcCXhd(H(ZNR$LOdsZ;;05f|R{s@^6cldG6UEC1S){6D&L-4Wr=rWWYXoNG5 z8k!c7#Y%5yzJG%d%YY&|->@7m^4@?%fGZ@X*@+rLlSxj0qABEzp{SOwrd+W@;Xow+ri;r1kpU#;(+ zb80m!eO!O)xKHamVZ{ENQ#QDuP0{Mw6~d?L)e~+%>NwBPiMaAn1-y4D(LMNc=!p5q z*v07GJk?7qA2MoGT(N6Ky@&2KS3{I_>wiI*9%3G;9Y>}xX$4VPhtQKeqMo!^@A5oe zaSkNsJ<0(h*m7x=om%0GqK&F)m04>OUFEgbuaB;a8vb0%2uGcGnDf=4R%KZ}Lt#K8 z5bJW(7jo1oziaQZ!Xqj%88WxW`&?mM=nJxjIwx3ps1Mm%qBVOHjKA1lYE&H`m3QWV zcUD4`n@7SBddZ{~$HFF9PZQ#G?#Qz`hx9YUGU)*HR{PNaCv0P}Itkzl`~Vv$o9o&$ z9r4+VpGJ2+pSmCn>_1Z`+1OTaY&ILJkOPytv7*Qkv1esJ^q}f7-8VtF@(u&%;IUHY zr;ma);B0^Z4A=^gd|d}Eb)0?`on00&KJRbesoYY6AqFe78!ZqVy!T|D{sYT+v<-47k{eqKayF~j*=K6=s zQi32jazYM$_qxzjpL0B9?S|)qH{UCS9vj~FC;td}et_&MOtlw$HzxPjs~runQRXAx@HC5 z`EM5XOB3Uni_zqpvoFdvy?fbz_jB_LK4;K;`-tNmiA1T6OJ7Mg~k>oPLy)-}zWyZ>_w zA25Nrwb&n#>cl&aZzs~jPsSa~>C&Yu`62O4rOWeg>{=n2TW%!A_ASFq^#k(F9wS5g zpI990xoMQm;$3cYA139O@usn-ZMxnhP2)d$DPWeP`$VkFDQ=l%78NT{|y zzl)4rLE_GS$o)|pUUeiHgin;-z;NNP@S6MPxKUMK=Ct8Yu0kFKH^5%dSW={hKtdm? ze+ltR^U(s_Wtdtr??+(f_Z)UH$v?-DKE3A*tIiTU$jSr5Osw`fl1BQ?Z6#P1Zt9nE za*(H(bPV`{Iq$a~df*MGutG+-B^k5OUq74+U8?S_90-%VN<3PhPjo70Wg^gKZK={! zCbpJt(2jQHXjYB8Ci#LZGpaiZrRRhaknPPbSX=v}43**q-k9cy(~V#h+?I&KCJTjU zrrP^$7glx7orl(>KgS5@_cmy9&0ZbipO>(ATIe{*iC^5FHn6>?>-Ft{zr%)BSJj;h zQ8z74PBR%`xM1XParcK(9TDIg?b%jeV9qt+2JA&OPW5YF&HmOEmtka&-%ushxBG(+ z4GZ4Oee-wJwEF(_Q-h1-HEz<`pvU{~u%{~#Lo6|MXKf;w*ThM}F6QpL$j{^v?zuT; zhViKHjdlv~x@6>F8l*J`=6bK`VX0U~uM_GHt1 zYNB5rtd(snjXgN3y!1L^oZ}6_1HSH`6Fs^awfu^6jq63nl$bN!&~~xW;7#rnlbx-T zpiS~5V9z?D^prlny0$o-pY=4O=$^m*Ri*X*@55z0`?q|ZQ6Vim9Zd?Urrd6$Mv;Bl z8`tJ-wdNvg@{TMw<0_AK)KPhd)OG`W%XnAk3VF0=KJ!$W7W3t$s}j+W9_2W@=-QjE zjuzE$)NQ-ehxjTaBDbrGdW*c>7Pd#TzjF8^mmAjJ^^nGP4RVdyq*QWjyc4c@>E}|c zhvezXe-+F{TSMEI8Ce)|SfqbQ+sC%)xT2ilq_!TneroK;rXj=1V8u@sq!i(pgd1I& znV}$XIvX~_^h5rhaPNy@S{&-`!H*6MIIJ(&+Q~&^fMZ6d=y<$ch@lG3+-G@e z*DDo;C^zYx6_SKad#k8U*8=5k(ZS_9dMg0zp7{d$*{jc^XrIkyK;f+bI8t*%gXI^i zh_NhExq83riJnaooRfs*P$5NW#q`w@iABQd1A?hi*i)1VGPtAo^sS`3ov^Y=OQW}& zRcR=k_97J8RLw0d1<-j$2pB?hyWWl<#_1S=wNMXT9A%-&%|*VjhhWP(7nFxyK=~5) zM)VJ&Jh_r5@ikCi332hvC_R`egGN}4Qv5K}vk3Hb_qULi(le_a+oUNBmrq6Ve#9|- zj6?A3;OXt?AI|0#MXxqm(>}+4vHOI%M7Y&e2zACBH_t*j?JJ>Y4xIcAod5I!SmhQo z3Gi19li@SOQ5^-%YMY^06$jelQkFuD;VyPmY!$~1lDd5*k4*BA{w;#H+ri-%{t zB>0aXrXA)?%UJ(byvUam}ZJm^^+I`LO!_xV4>% zS928K*XAwEdoghoZLbugzmFv|4H^r1hZb;qRTwa&b5J&6yGh1q5o$?M^zaPW#B^Bd>7{Yt4aUZ4>)mylk({oV+uK>o}@N%jEgh zj<#gOD3fB|!}n<_A*!;%Cf`I~4WECrDWBt%iFbu(1n0@_sm+P)k-)@u{r=OZxENb; zy45=}Echi?nh$m|Pv^MX|K9B1RN&WM8sa`+I+11eyZ}$Jtl%@>g)Yq%4p5$|n@8_I zqPTU^jG7IKkK2y~JLqoZUBi><5Tc~XX_Cbm$W$$6RMo!4@PqGo*Pmc!RV66>n;NX7 z(eP5=ClZiqV3KKQ-27U_MYM&M1QYDNWo@$;n|Rw{_JfcD_Q;2$9p;hR569$5Qh>hy z&_%<7_xQkCcBL_+5-4{l@YT<$d3cDEIpSoo!-wjMgFRpMu+-u*EANJH%%^k}p>%`G zjuJ`R=?4fLRR~yqtSy{&R%}RyY1k2E zIy)j=o8Xq%%J!~CgVY51={o%0jpI|bYZXLd=!GWCtPCw_nogDUEqG_n$#vIPnC3iK zvrsMnvaflyTx``|5k)VyO zu@x*`8qMkMws$iewU3PhY@gD-tWkNzRp*P_3OS zT-b`&jiQy~bN+N!wL8jkiZ9c4IwM~|cR%miXkJ>*1^98BCDY^-W#UJz2a=2RIm83V zOf&Xp9M9&0kYgo#PLcPPWKemai=_}SBq1`|DzPdG^9j#EP;6kU7Ua;6U zxFl=syT6>s&NQ!FJ1FOCI{M?@mMTgO+&S}_!fn+g%|@r3xpUoe4ofzy`@Rp%(uZvl zV~;F5bRA9LziwV`SFu}q_38Hm|3g7**}`cdkwe2KnRBV+yVyjIjj@Lt8F~Y;68H#o zO`=LAF?I0KPQJ3eqQOt(ou25B?J7b(M-mssN*$n@TBZ2&GK1Ot+=UCwmYsiQlbfN=87FCOK z_hmjCKwEYxrNiyjh3i~B;P^d3o`Pd=47l+P&s5~z933}Z#*L4>DH`GuIBe+={ZOMW zv9;*+fH{Cke@FRX;Y;Im=MA9sbM>YV-;xz#JT0-Yp2#pbtOA=v#H-JnX{T7Knn!$j zj598mDn*%WOqh%IAC01TuP9G5_DCi2i!shIP3DyylJ5M@;}F`+Z@n8%2&e6(wk>Cz z$XW8zwD+B$pt69mG|tesP7Z%un0YVAS$ADqO~0GE-|0B!w9J#zBtx%yopys2L;|;c z(&nt4B5t3CB4e*<-;VC?L`Lkt;~C;`I@Wn$Gs>kb zKS1`v?3s~$$9`@1ZNt-q793``!#^gU(8$?8qns$)X2Zjy%xjYEok;Lomh!lNPHJ`D zjc7b=hiLl3u|2QD#&qxw GDUVwGB&tFQIs|KHL%j!!%k6<{2!#&NHG#)l|*$;VA zqLA|@W+1vKX!(z+se{o$bCoGZAqkc=anej~O0p;p7wlT`A4Yp2x& zrnelK%F#=odOPN$I$X{2OI#24I+jc;6^+cnPFF&{c*vrCZ#^M1Ao1pGLNC!dtSSU+LFT>wuyXGzd zquzA_+$@lMao;xc6Xg>OvG2` zB-MPYUStJ0{M6?B*6;{poHTnCM!cB1R+c=UNS;P z!ac;Yfp7?%%)i{sbMG(CnlhqVu%}w${>|H}d&a85r%!{A^GL4Q7c2a|z$jXF@HekZ zL$Lr0IP7jAVgf+3=(|CEX9tU<v2k6DE7I%JZiK56nVky4au<(gh?q-IttC!y-Ca$`9k#z*(2sMbZheIz?s$Gs zAkS@|ee(?ao0g4hgh^eO<36!+!ZNJ^SXS^%&=a>&dPcNQ`mT7pkg67KDv^r%9UBI) zEH41exULC+r2;v`I~wicC%NQrpUYB9evZTb ztXbBqK6Tk6p6Rp{QAba^yt#m8nIG>}oE93Xv=eFt$ty`1h`me$jtxZVI{MgD-npBK zV~k_#PzdhwT$EyO7H_;k+PJzNjjpJ;RqVk7&h&KZccvl*9wr1dtPA0)zndCRv|&^& z4@{bJm+nO}nSM`Sj-u#~$;6Qhf5K5fx_P|a8z)3Zr&;Ud^zQ$)_myE$tzFoPpfD(c z5*8t-2uK)ot5^uAFcL!vBHi5%iUA77L6q(oVnAT%R76p_hX!d7knV47&(Y&i&(Zh0 zzF*(v`{TXlfScL-+0V1$UiZ3}>F%bM+xR@~-EPYQ#+2n~d6x4S>PE4Cp@i0XQqhc+ z=*#I2cZKlFuLI;8vI|1y;$4NUy;lC1+2hud(-Kd5Iq#|=7bew9@2V?0!TDaWjTyUW zjH+x?p^DJ+lUcj}gdU!=OO^6+y6KH?e_;SW=`vqWW~Y=r3d-{~xci2!hsmg?{hmEr zn3M8VmRws-OG|143lp4l2(5YsqgK00e}P;cQv$G7WsBOyR#r}nXqGb>Mh!t0ejc`F z4KG$h_Uq%7#N`_jl|0X4L~%#jV3fjnEVFB{>uk%DhYx9vWqau3HaA3`-WuDZRxRDJ zFXMVhCW$^u7SUan*H#D>G?k6x-bQz_mL7+i=GYOJB)h$VR;bP{0QK5P_9DLqrcl{t z1wi+*zS=hvqUWz%@XV!sP;Xa&+Gb>Y+VsXw6-HiBK_qc_o>r;yYTL4x%-zF()y=v< zuCwRHr*i8*{%`1@)P#4JvWVMq{L?>LcaES~&aKQ60~} z&eT5+(qBJ&;7fwIE8W1*0AH@xYqFs>wPyj%SXtI0=lc6A;Zxx{y254Jynp=c+nX#Q zL(v}8w$DG-;nuq1z2Z1;F@K$OE^ndUmC*IVJ~#oUb~f#T%4!$aMg{y5FSPDju#bQJ zpe&taP?=t0(_a5yw~Qi*_9=huuSd_J_RhWi-o4EU&}g(K&ijwQco`1E)esYH_uJ8t;$I}KX|A%X2kZT5S=(haFTl?nG z9u$C9bnRS=^}zpdO$1zXX}UPouj6w|8PwlTtn+>ap=?FrJroHzaFht8Jx$Wg!6|z-#_c$ zPyNqNmz3ZdFA1S1|6rbdb@M-Xpdl_e3cruf@8k3P`20RT*MEB-V154fKBT|B56JWW z4&MGRgEvn_oA$qA9c(&XGiXF4sic-rF-rsuYy{|jN^2_Cud{`DX>Or&pwye>auKdE z-n{hOALZU}Ew}tMd}A>rd(OCAt2JK$ozTeC+tyUw+uWLYLWbr%g$x29a=RPG5F?Ue z3u=XK`E-X=s*UR7u0Zn?!aGsTG;2=;BKTomej4jnE|wcV(F)(^79o?yUT#;g@z7ex ze|p7UBa~M*?gD=ulcT*49k(W{R&tfhPa|dQRqBHi`j@>4h(g*cM1?T$h@KZr1Aj}! zBsLgy30nLyxpt=Mb#))+5yTz%bm`C#@ycd=k#d=a?UV|Xe#Oezb>yqO_YYx#CD9Tl zeWNEQ2dXEny1wG{O~TJMLpXRQstA~LSD!t5b~o?jxpymTuPO<{w!U(AGoGLMe)(83 zNqDy|O9qOs%IODyNU&<}tNYfX`v<K@>_qK`Cu8bCRKc+&S&)n{CFegd|t!IcNlES}SwSnYDjfA>=qO!K~d# zL3~C@U0FTP!O}y^l1}dk+;+N@w&v1cq%UErN>Z}M|9rp#5bMllomQSHe~}Tj9IbR82gKLaC4>67hpsRYwzAP@80HVgWSDn$ z%zkJeVeWNKwH}aXub+Ok+k8GJX#DQeqk|+I)2HbAH*RGbReGivoehP_5>PUIHYR$( zGXox84KVXW7+>8Y5xO1H4(wH$3o0tzT{eb5CY#+lWEVnrfZ*76N&64#&?TfY$k%b3yv?$VQCb`(=~-^sq2adBX9p_E8}HBL z$1BA@8jqe5r?K9s!BW~u3$v-AWknk)>eh=w+uXhFFWIK){Jj1vt^Y@Y$iYHQzl_qb zhT4dn-y?$#lI`sB>7Y5cX^R0c@~W4L1c3#V0np+mJ7N6N^ic1(?8~6lH@+zh`XP=n z!A`^RG~-ZZ)U2eBq1j|f{j0eWmX?ORb-2c~9dtv}F@mn{6k^a+bA=v`)D_nPAEdEA zHq;G)#8WA@A5eigpQAY=$!WmuUA(1&Y;rf!f;g?h0#7r)oeqI6w>I!Q{A$kiV3_1E zS>cf*M=q^MY$vROEPy9^skW5%gI7JLak{P#7vVPvK=yGJ}YR2oTG+ zO`84hfBvb5)>%S-lv*XQHG2v|V4Kd#9B8>I<3)QnE252bl2!hl^uO)C&v*GHcl{_0 zX)9=~aI5|Cc4vtK+*`MD_*d=u-(Bzx3UCRHTp!v7P3%^}C+3IXa4&OC{~*`>7waO0 z1Nfx8?{O;(m*mkWmxSGYOUsk#m+znY3>uQBY!@q0yV2Kuo4aG#bt)$ks=pUk`VFlyJX#bg-Nlpv&!xVQa7c`!;BPW}>ia?|;jK{fPo zVJ%PvFa>Ll&^MMq1w9FRkt?l5paPr(l=YgJ*Nu}<8!GQ`nUaHs>v48&?IFS+{>)Ev|;xG}m1xofI4m}i0K%rCjkD$H?cQ*C} zW0nf?&{;kgV~M~{HzdfIe_ojgkWafvjRJJY%V)J(B;js+bs^&KI`2ml)=@Tk6zqednO zkT!;&*fav&lN_W^>SCl?fYUx&xVD0~7O#kuQqrD~tr`JGfw<<48ZppnCIAFiV4*H~ zEKc>@FY!hMx9&5FHqxpn=7Q!&i3B@n*Aif+ZS78Hpn0c6`*A3~f=Q^xpfu?ZN}3|0 zLX7|V?!W!T)zd6y#rUlf^Fpc2-n}-(6ICu_nS*;*0Xsz)~mM(Rg&Ugw{uu$2Qv+Z!K zxf_1`qdUkajRNui-r%sPR(K9D=vor+1xCu6j?qXrUQCL{A-N`GFlRo<3(i8@bRe#X zOn`AN<00E=A|i8S7S1u#?!LAXQ*{&PzCUN^Xl#mqL7PMs7U}oRoEfSsgI0Y;OI7FD z(NsjBACbs~fC$x4$ZGVfYgG$1zmi++FpOdr zG*X@tDxD{aH@)yFs|_#LA=-_@rnSZKBLZem>eS1if2K48lqYaees_e~l1}dxCX1y_ zL2a%><2Bn`3R1w&hr}kZJ|$6S4{?at{%UH^Q`@dU^8!npj-dpE1DkhlqhCacxr3N? zW3Ih&c5DOQ-en*j4=~Zydd)gE+Wi4<#dp^tN_`N{R{wG$>8&yn z->F?cvtysl8dinWig9@nlub=O13pX5_qf&=F~gcOY2g)g zyqAM0%?FdW!r=BXAX97#<3T#y*IbQZ$h^5qwLMzlQ)~xOhV)8-ARs zDP!Qf`lRLS9+HlO?weDAJY{8cd@j&pqobC_6M?cv(dT&5M{*xWS5Gg)fXoMyB#W*) zk~no&6YnK_-No~7HiJ4>D%nE|3`1IMh!f|a5wv7jlbjNFo=t~2CBk%ncx=qdyEs3B z=-;CKtc+o@_Pw|C?%?fGpoJ$#gViXsvO(l{VV?YEMutVrf&Du2nKNKMnj8;+O#MgZ zf)6<(CZN}OB^h_pu11ET1#$IdOwNh!E?tzK2b8+GZAMPr=fDsW8{!qq;sg2!E7!Wj zaGUMMGMWN-r=!PsVH7lj(7wTpemN!Mwye~&j7UNTGQm9Q>YGO){p%37a&h+?k7*gjuVvnXy2!P=%mp4CLYM2nR1;uzzuD%R<_YWUqf) zl&``jDJnA5z(ih3ozlY*7+ydClh90YdSTW>Iu5J&*d}2-T8=e&wE6tEa~W z&Ezl>rIE0VTugOQ^?N|v%9rd`LHbIB$5~HGXGu4*dD_)WLM7bP;pJMs5{q%-E7Nt- z^hB!KCZ&r5e<;cy#-GzbgjkP4uVsWhKY=Sbt3*j=43t!@2n*8{k>hG3{7vfHo9X77 z{MD`Qx>thj?yMA_Q(s#uVgSM6nZkTfHyMSS%Z&69Der7bR6Sbfk9!+m9)QskLZj*~ zKZ04^)1hUQur|9vnutn>u5eoPT;cB1_jYuX@^dN0X(JY&1Oyc--@SVmNM=d*EAH8f z6p2ZW*GTNE>ufFQF&~cX@5TOfrajBi-QL`i)e348T5FGCq3vu$vg#F27Rh zCXxYtw<4Gwiyu_0bm7R;oX{#rh5XT;aAi7w>x#tH*VI)P{9iT3U3@Wpo-G5$FF(VL z0S_X^OBaPQYAppCQHK`;uNfq88A$jD9gM7UbWOSgLDoJEiK=zh@<|xK!mHFfz@$iz zAcFZDay>K^0tL7S#m!;3nL8<{&-R&2;c%|R92L5QRbo@;^}V}SSC&KzBil$)7Shyy zX`d9Wk$Nbq316tu@{)vk^cSlRftSn&+LGOHe5{iXdQcWKR@1{4W@Mb%X65b9B~yXp z-j%jJ3x;H77yaCLZ-OFCo798hgZABp@8Jq<*q(DNvdX7yzBv}#` zXF~F3aa6I~hkz1oOyoJLh6Eh?ujT0q4Zr}nkdPKX8h@6;`tz5DwZN)xD$FBX+g$jE za6{24pFJQKUzK1;d0fqf6r`Mu;LuP8Btpn9Jsz14ovQ@J?6<~2IBOXrgh=huL6o;D zy1xFQd{vV!h?iRC7m!>b)*gFuIr4Gu1=^h{j}I*K}tbeS&^@lsB-vptnpH=W$!D;5K$2I2IYvf0ZXcr z3>V@Ipg&l8L&i)m1$z*6J;U2Tu-;BoitCPJBw+e?oAo^pEwhFskTU9btbAxA(@kGOvgL7fLn+cHdE9$+4_(>H+E0SP)S3b#HbX5k_qP|e|!!H!JSPYTXD<9HO zwdBSD<&WMYv|yH5=leLfI}gCnaye;yH9f~mIuU`!Ih3v5wQEjPb3|fYLZ@{E zt@s0;xn~i+xAoYl?LoxEl3nlk&$kq4gSb$*89Eoj6sdQbPDA_s_dhdj&uPdAt!yT{ z_U>u7NEV#8lY)kNBaM0SmS6B-FBMp{ zJhar@ptV-)h8Cm+cRCqkhRy@hu{GD4Z1XkfL~m61G)79QgW~4KVrc8`Q!1`+d_Y?K z@q@6%{+~V*O9RZSkAF1LKZy4U_8)1Q^$s_MDG%Wqd4G;U*I&P49#Q}j+PW|- z=&*cg?ro2A?bsSV