From 07be67ea1ce06de889357c1120a49fdd7cbd13e3 Mon Sep 17 00:00:00 2001 From: jhauerst <114038876+jhauerst@users.noreply.github.com> Date: Mon, 4 Mar 2024 17:24:53 -0500 Subject: [PATCH 01/41] modified radio code to handle binary data --- .../Teensy-Based Avionics/include/Radio.h | 8 +- .../Teensy-Based Avionics/src/RFM69HCW.cpp | 286 +++++++++++------- .../Code/Teensy-Based Avionics/src/RFM69HCW.h | 22 +- .../test/ReceiverTest.cpp | 4 +- .../test/TransmitterTest.cpp | 2 +- 5 files changed, 202 insertions(+), 120 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h index 6f6a930c..9e8ab573 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h @@ -33,11 +33,11 @@ class Radio public: virtual ~Radio(){}; // Virtual descructor. Very important virtual bool begin() = 0; - virtual bool tx(const char *message) = 0; + virtual bool tx(const char *message, int len = -1) = 0; virtual const char *rx() = 0; - virtual bool encode(char *message, EncodingType type) = 0; - virtual bool decode(char *message, EncodingType type) = 0; - virtual bool send(const char *message, EncodingType type) = 0; + virtual bool encode(char *message, EncodingType type, int len = -1) = 0; + virtual bool decode(char *message, EncodingType type, int len = -1) = 0; + virtual bool send(const char *message, EncodingType type, int len = -1) = 0; virtual const char *receive(EncodingType type) = 0; virtual int RSSI() = 0; }; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp index 0e70ece1..8853c819 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp @@ -7,39 +7,37 @@ Constructor - highBitrate true for 300kbps, false for 4.8kbps - config with APRS settings */ -RFM69HCW::RFM69HCW(const RadioSettings s, const APRSConfig config) : radio(s.cs, s.irq, *s.spi) +RFM69HCW::RFM69HCW(const RadioSettings *s, const APRSConfig *config) : radio(s->cs, s->irq, *s->spi) { - if (s.transmitter) + + this->settings = *s; + this->cfg = *config; + this->avail = false; + this->msgLen = -1; + + if (this->settings.transmitter) { // addresses for transmitters this->addr = 0x02; this->toAddr = 0x01; - this->id = 0x00; // to fit the max number of bytes in a packet, this will change - // based on message length, but it will be reset to this value - // after each complete transmission } else { // addresses for receivers this->addr = 0x01; this->toAddr = 0x02; - this->id = 0x00; } - - this->avail = false; - - this->settings = s; - this->cfg = config; + this->id = 0x00; // to fit the max number of bytes in a packet, this will change + // based on message length, but it will be reset to this value + // after each complete transmission/reception } /* Initializer to call in setup - - s is the spi interface that should be used - - cs is the chip select pin - - irq is the interrupt pin */ bool RFM69HCW::begin() { + // reset the radio pinMode(this->settings.rst, OUTPUT); digitalWrite(this->settings.rst, LOW); delay(10); @@ -53,6 +51,8 @@ bool RFM69HCW::begin() // then use this to actually set the frequency if (!this->radio.setFrequency(this->settings.frequency)) return false; + + // set transmit power this->radio.setTxPower(this->txPower, true); // always set FSK mode @@ -64,47 +64,58 @@ bool RFM69HCW::begin() this->radio.setThisAddress(this->addr); this->radio.setHeaderId(this->id); - if (this->settings.highBitrate) + if (this->settings.highBitrate) // Note: not working { // the default bitrate of 4.8kbps should be fine unless we want high bitrate for video - set300KBPS(); + // set300KBPS(); + this->radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); // remove as much overhead as possible - this->radio.setPreambleLength(0); - this->radio.setSyncWords(); + // this->radio.setPreambleLength(0); + // this->radio.setSyncWords(); } return true; } /* -Transmit function Most basic transmission method, simply transmits the string without modification - - message is the message to be transmitted, must be null terminated + \param message is the message to be transmitted, set to nullptr if this->msg already contains the message + \param len [optional] is the length of the message, if not used it is assumed this->msgLen is already set to the length */ -bool RFM69HCW::tx(const char *message) +bool RFM69HCW::tx(const char *message, int len) { - // get length because message may be too long to transmit at one time - int len = strlen(message); + // figure out how long the message should be + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + else if (this->msgLen == -1) + return false; + + // reset variables for tx + this->id = 0x00; // get number of packets for this message, and set this radio's id to that value so the receiver knows how many packets to expect - this->id = len / this->bufSize + (len % this->bufSize > 0); + this->totalPackets = len / this->bufSize + (len % this->bufSize > 0); this->radio.setHeaderId(this->id); - // fill the buffer repeatedly until the entire message has been sent - for (unsigned int j = 0; j < this->id; j++) - { - memset(this->buf, 0, this->bufSize); - memcpy(this->buf, message + j * this->bufSize, min(this->bufSize, len - j * this->bufSize)); - this->radio.send(this->buf, min(this->bufSize, len - j * this->bufSize)); - if (j != this->id - 1u) - this->radio.waitPacketSent(); - // delay(100); // leaving this here for now, should try to remove later - } + if (message != nullptr) + memcpy(this->msg, message, len); + + return true; +} +bool RFM69HCW::sendBuffer() +{ + memcpy(this->buf, this->msg + this->id * this->bufSize, min(this->bufSize, this->msgLen - this->id * this->bufSize)); + this->radio.send(this->buf, min(this->bufSize, this->msgLen - this->id * this->bufSize)); + this->id++; + return this->id == this->totalPackets; +} + +void RFM69HCW::endtx() +{ + this->msgLen = -1; this->id = 0x00; this->radio.setHeaderId(this->id); - - return true; } /* @@ -122,75 +133,76 @@ const char *RFM69HCW::rx() if (this->radio.recv(this->buf, &(receivedLen))) { // check if this is the first part of the message - if (this->incomingMsgLen == 0) + if (this->totalPackets == 0) { - this->incomingMsgLen = this->radio.headerId(); - if (this->incomingMsgLen == 0) - return "Error parsing message"; - memcpy(this->msg, this->buf, receivedLen); - this->msg[receivedLen] = '\0'; + this->totalPackets = this->radio.headerId(); + if (this->totalPackets <= 0) + return 0; + this->msgLen = 0; + this->rssi = 0; } - else // otherwise append to the end of the message, removing the \0 from last time - { - int len = strlen(this->msg); - memcpy(this->msg + len, this->buf, min(MSG_LEN - (len + receivedLen), receivedLen)); - this->msg[min(MSG_LEN, len + receivedLen)] = '\0'; // make sure we don't go over MSG_LEN - } - this->id++; - // Debug - // Serial.print("Received ["); - // Serial.print(this->bufSize); - // Serial.print("]: "); - // this->buf[this->bufSize] = 0; - // Serial.println((char *)this->buf); - // Serial.print("RSSI: "); - // Serial.println(this->radio.lastRssi(), DEC); - // Serial.println(""); + // copy data from this->buf to this->msg, making sure not to overflow + memcpy(this->msg + this->msgLen, this->buf, min(MSG_LEN - (this->msgLen + receivedLen), receivedLen)); + + this->msgLen += receivedLen; + this->id++; this->rssi += radio.lastRssi(); // check if the full message has been received - // int msgLen = strlen(this->msg); - if (this->incomingMsgLen == this->id) // this works for now, maybe find a better way later? + if (this->totalPackets == this->id) { - this->id = 0; - this->rssi /= this->incomingMsgLen; - this->incomingMsgLen = 0; + this->id = 0x00; + this->rssi /= this->totalPackets; + this->totalPackets = 0; this->avail = true; } return this->msg; } - return "Failed to receive message"; + return 0; } - return "No message available"; + return 0; +} + +/* +\return ```true``` if the radio is currently busy +*/ +bool RFM69HCW::busy() +{ + RHGenericDriver::RHMode mode = this->radio.mode(); + if (mode == RHGenericDriver::RHModeTx) + return true; + return false; } /* Multi-purpose encoder function Encodes the message into a format selected by type -char *message must be a dynamically allocated null terminated string +char *message is the message to be encoded +sets this->msgLen to the encoded length of message - Telemetry: message - input: latitude,longitude,altitude,speed,heading,precision,stage,t0 -> output: APRS message -- Video: TODO - message - input: char* filled with raw bytes -> output: Raw byte array +- Video: + message - input: char* filled with raw bytes -> output: char* filled with raw bytes + error checking - Ground Station: TODO message - input: Source:Value,Destination:Value,Path:Value,Type:Value,Body:Value -> output: APRS message */ -bool RFM69HCW::encode(char *message, EncodingType type) +bool RFM69HCW::encode(char *message, EncodingType type, int len) { - if (type == ENCT_NONE) - return true; if (type == ENCT_TELEMETRY) { - int msgLen = strlen(message); + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + else if (this->msgLen == -1) + return false; // holds the data to be assembled into the aprs body APRSData data; // find each value separated in order by a comma and put in the APRSData array { - char currentVal[MSG_LEN]; + char *currentVal = new char[this->msgLen]; int currentValIndex = 0; int currentValCount = 0; for (int i = 0; i < msgLen; i++) @@ -225,6 +237,8 @@ bool RFM69HCW::encode(char *message, EncodingType type) currentValCount++; } } + + delete[] currentVal; } // get lat and long string for low or high precision @@ -263,13 +277,13 @@ bool RFM69HCW::encode(char *message, EncodingType type) padding(spd_int, 3, data.spd); padding(hdg_int, 3, data.hdg); + // generate the aprs message APRSMsg aprs; aprs.setSource(this->cfg.CALLSIGN); aprs.setPath(this->cfg.PATH); aprs.setDestination(this->cfg.TOCALL); - // generate the aprs message char body[80]; sprintf(body, "%c%s%c%s%c%s%c%s%s%s%s%c%s%c%s", '!', data.lat, this->cfg.OVERLAY, data.lng, this->cfg.SYMBOL, data.hdg, '/', data.spd, data.alt, "/S", data.stage, '/', @@ -278,26 +292,45 @@ bool RFM69HCW::encode(char *message, EncodingType type) aprs.encode(message); return true; } + if (type == ENCT_VIDEO) + { + // lower bound for received message length, for basic error checking + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + // if len wasn't set, make sure this->msgLen is + if (this->msgLen == -1) + return false; + message[this->msgLen] = this->msgLen / 255; + } + if (type == ENCT_NONE) + return true; return false; } /* -Multi-purpose encoder function +Multi-purpose decoder function Decodes the message into a format selected by type -char *message must be a dynamically allocated null terminated string -- Telemetry: +char *message is the message to be decoded +sets this->msgLen to the length of the decoded message +- Telemetry: TODO: fix message - output: latitude,longitude,altitude,speed,heading,precision,stage,t0 <- input: APRS message - Video: TODO message - output: char* filled with raw bytes <- input: Raw byte array - Ground Station: message - output: Source:Value,Destination:Value,Path:Value,Type:Value,Body:Value <- input: APRS message */ -bool RFM69HCW::decode(char *message, EncodingType type) +bool RFM69HCW::decode(char *message, EncodingType type, int len) { - if (type == ENCT_NONE) - return true; if (type == ENCT_TELEMETRY) { + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + else if (this->msgLen == -1) + return false; + + // make sure message is null terminated + message[this->msgLen] = 0; + APRSMsg aprs; aprs.decode(message); @@ -322,7 +355,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.lat, bodyptr, i - (bodyptr - body)); - data.lat[i - (bodyptr - body)] = '\0'; + data.lat[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -332,7 +365,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.lng, bodyptr, i - (bodyptr - body)); - data.lng[i - (bodyptr - body)] = '\0'; + data.lng[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -342,7 +375,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.hdg, bodyptr, i - (bodyptr - body)); - data.hdg[i - (bodyptr - body)] = '\0'; + data.hdg[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -352,7 +385,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.spd, bodyptr, i - (bodyptr - body)); - data.spd[i - (bodyptr - body)] = '\0'; + data.spd[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -366,7 +399,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.alt, bodyptr, i - (bodyptr - body)); - data.alt[i - (bodyptr - body)] = '\0'; + data.alt[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -380,7 +413,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.stage, bodyptr, i - (bodyptr - body)); - data.stage[i - (bodyptr - body)] = '\0'; + data.stage[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -390,7 +423,7 @@ bool RFM69HCW::decode(char *message, EncodingType type) if (i == len) return false; strncpy(data.t0, bodyptr, i - (bodyptr - body)); - data.t0[i - (bodyptr - body)] = '\0'; + data.t0[i - (bodyptr - body)] = 0; i++; bodyptr = body + i; @@ -478,37 +511,80 @@ bool RFM69HCW::decode(char *message, EncodingType type) sprintf(message, "%f,%f,%s,%s,%s,%c,%s,%s", lat, lng, data.alt, data.spd, data.hdg, strlen(data.dao) > 0 ? 'H' : 'L', data.stage, data.t0); + this->msgLen = strlen(message); return true; } if (type == ENCT_GROUNDSTATION) { + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + else if (this->msgLen == -1) + return false; + + // make sure message is null terminated + message[this->msgLen] = 0; + // put the message into a APRSMessage object to decode it APRSMsg aprs; aprs.decode(message); - aprs.toString(message); + // add RSSI to the end of message sprintf(message + strlen(message), "%s%d", ",RSSI:", this->rssi); + + this->msgLen = strlen(message); return true; } + if (type == ENCT_VIDEO) + { + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + + // if len wasn't set, make sure this->msgLen is + if (this->msgLen == -1) + return false; + + // otherwise, check if the length of the message is within the expected bounds + return this->msgLen >= message[this->msgLen] * 255 && this->msgLen < (message[this->msgLen] + 1) * 255; + } + if (type == ENCT_NONE) + return true; return false; } /* -Comprehensive send function -Encodes the message into the selected type, then sends it -char *message must be a null terminated string -Transmitted and encoded message length must not exceed MSG_LEN - - message is the message to be sent - - type is the encoding type +Encodes the message into the selected type, then sends it. Transmitted and encoded message length must not exceed ```MSG_LEN``` + \param message is the message to be sent + \param type is the encoding type + \param len optional length of message, required if message is not a null terminated string +\return ```true``` if the message was sent successfully */ -bool RFM69HCW::send(const char *message, EncodingType type) +bool RFM69HCW::send(const char *message, EncodingType type, int len) { - strcpy(this->msg, message); - this->msg[MSG_LEN] = '\0'; // make sure msg is null terminated just in case - encode(this->msg, type); - tx(this->msg); - return true; + if (type == ENCT_TELEMETRY || type == ENCT_GROUNDSTATION) + { + // assume message is a valid string, but maybe it's not null terminated + strncpy(this->msg, message, MSG_LEN); + this->msg[MSG_LEN] = 0; // so null terminate it just in case + // figure out what the length of the message should be + if (len > 0 && len <= MSG_LEN) + this->msgLen = len; + else + this->msgLen = strlen(this->msg); + return encode(this->msg, type, this->msgLen) && tx(nullptr, strlen(this->msg)); // length needs to be updated since encode() modifies the message + } + if (type == ENCT_VIDEO && len != -1) + { + // can't assume message is a valid string + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + memcpy(this->msg, message, this->msgLen); + return encode(this->msg, type) && tx(nullptr); // length does not change with ENCT_VIDEO + } + if (type == ENCT_NONE && len != -1) + { + return tx(message, len); + } + return false; } /* @@ -516,17 +592,18 @@ Comprehensive receive function Should be called after verifying there is an available message by calling available() Decodes the last received message according to the type Received and decoded message length must not exceed MSG_LEN - - type is the decoding type + \param type is the decoding type */ const char *RFM69HCW::receive(EncodingType type) { if (this->avail) { this->avail = false; - decode(this->msg, type); + if (!decode(this->msg, type, this->msgLen)) // Note: this->msgLen is never set to -1 + return 0; return this->msg; } - return ""; + return 0; } /* @@ -546,6 +623,7 @@ int RFM69HCW::RSSI() return this->rssi; } +// probably broken void RFM69HCW::set300KBPS() { this->radio.spiWrite(0x03, 0x00); // REG_BITRATEMSB: 300kbps (0x006B, see DS p20) @@ -567,7 +645,6 @@ int max(int a, int b) return a; return b; } - #endif #ifndef min @@ -577,5 +654,4 @@ int min(int a, int b) return a; return b; } - #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h index d301a6e8..9abf9506 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h @@ -38,18 +38,26 @@ struct RadioSettings class RFM69HCW : public Radio { public: - RFM69HCW(const RadioSettings s, const APRSConfig config); + RFM69HCW(const RadioSettings *s, const APRSConfig *config); bool begin() override; - bool tx(const char *message) override; + bool tx(const char *message, int len = -1) override; + bool sendBuffer(); + void endtx(); const char *rx() override; - bool encode(char *message, EncodingType type) override; - bool decode(char *message, EncodingType type) override; - bool send(const char *message, EncodingType type) override; + bool busy(); + bool encode(char *message, EncodingType type, int len = -1) override; + bool decode(char *message, EncodingType type, int len = -1) override; + bool send(const char *message, EncodingType type, int len = -1) override; const char *receive(EncodingType type) override; int RSSI() override; bool available(); void set300KBPS(); + // stores full messages, max length determined by platform + char msg[MSG_LEN + 1]; + // length of msg for recieving binary messages + int msgLen = 0; + private: RH_RF69 radio; // all radios should have the same networkID @@ -68,9 +76,7 @@ class RFM69HCW : public Radio APRSConfig cfg; bool avail; int rssi; - int incomingMsgLen; - // stores full messages, max length determined by platform - char msg[MSG_LEN + 1]; + int totalPackets; }; #endif // RFM69HCW_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp index aafb5b27..5730c4d6 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp @@ -6,8 +6,8 @@ #define PATH "WIDE1-1" APRSConfig config = {CALLSIGN, TOCALL, PATH, '[', '/'}; -RadioSettings settings = {433.775, false, false, &hardware_spi, 10, 31, 32}; -RFM69HCW receive = {settings, config}; +RadioSettings settings = {433.775, false, false, &hardware_spi, 10, 2, 9}; +RFM69HCW receive = {&settings, &config}; void setup() { diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/test/TransmitterTest.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/test/TransmitterTest.cpp index f30a9090..a59a1bf4 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/test/TransmitterTest.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/test/TransmitterTest.cpp @@ -7,7 +7,7 @@ APRSConfig config = {CALLSIGN, TOCALL, PATH, '[', '/'}; RadioSettings settings = {433.775, true, false, &hardware_spi, 10, 2, 9}; -RFM69HCW transmit = {settings, config}; +RFM69HCW transmit = {&settings, &config}; void setup() { From 6f45546894a19e2c36c7b85a7d084b1cc2ff5aca Mon Sep 17 00:00:00 2001 From: jhauerst <114038876+jhauerst@users.noreply.github.com> Date: Mon, 4 Mar 2024 17:40:40 -0500 Subject: [PATCH 02/41] consolidated APRS code --- .../src/APRSEncodeFunctions.cpp | 167 ------------------ .../src/APRSEncodeFunctions.h | 47 ----- .../Teensy-Based Avionics/src/APRSMsg.cpp | 158 +++++++++++++++++ .../Code/Teensy-Based Avionics/src/APRSMsg.h | 17 +- .../Teensy-Based Avionics/src/RFM69HCW.cpp | 18 +- 5 files changed, 178 insertions(+), 229 deletions(-) delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.cpp delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.h diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.cpp deleted file mode 100644 index b785f731..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.cpp +++ /dev/null @@ -1,167 +0,0 @@ -/* -MIT License - -Copyright (c) 2020 Peter Buchegger - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -*/ - -#include "APRSEncodeFunctions.h" - -// takes in decimal minutes and converts to MM.dddd -char *s_min_nn(uint32_t min_nnnnn, int high_precision) -{ - /* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth - * degree (-> *= 6 -> nn.mmmmmm minutes) high_precision: 0: round at decimal - * position 2. 1: round at decimal position 4. 2: return decimal position 3-4 - * as base91 encoded char - */ - - static char buf[6]; - - // make sure there are nine digits - int missingDigits = 9 - numDigits(min_nnnnn); - if (missingDigits < 0) - for (int i = 0; i < missingDigits * -1; i++) - min_nnnnn /= 10; - if (missingDigits > 0) - for (int i = 0; i < missingDigits; i++) - min_nnnnn *= 10; - - min_nnnnn = min_nnnnn * 0.006; - - if (high_precision) - { - if ((min_nnnnn % 10) >= 5 && min_nnnnn < 6000000 - 5) - { - // round up. Avoid overflow (59.999999 should never become 60.0 or more) - min_nnnnn = min_nnnnn + 5; - } - } - else - { - if ((min_nnnnn % 1000) >= 500 && min_nnnnn < (6000000 - 500)) - { - // round up. Avoid overflow (59.9999 should never become 60.0 or more) - min_nnnnn = min_nnnnn + 500; - } - } - - if (high_precision < 2) - sprintf(buf, "%02u.%02u", (unsigned int)((min_nnnnn / 100000) % 100), (unsigned int)((min_nnnnn / 1000) % 100)); - else - sprintf(buf, "%c", (char)((min_nnnnn % 1000) / 11) + 33); - // Like to verify? type in python for i.e. RawDegrees billions 566688333: i = - // 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33) - return buf; -} - -// creates the latitude string for the APRS message based on whether the GPS coordinates are high precision -void create_lat_aprs(char *lat, bool hp) -{ - bool negative = lat[0] == '-'; - - int len = strlen(lat); - int decimalPos = 0; - // use for loop in case there is no decimal - for (int i = 0; i < len; i++) - { - if (lat[i] == '.') - { - decimalPos = i; - break; - } - } - // we like sprintf's float up-rounding. - // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation - // ;) - sprintf(lat, "%02d%s%c", atoi(lat) * (negative ? -1 : 1), s_min_nn(atoi(lat + decimalPos + 1), hp), negative ? 'S' : 'N'); -} - -// creates the longitude string for the APRS message based on whether the GPS coordinates are high precision -void create_long_aprs(char *lng, bool hp) -{ - bool negative = lng[0] == '-'; - - int len = strlen(lng); - int decimalPos = 0; - // use for loop in case there is no decimal - for (int i = 0; i < len; i++) - { - if (lng[i] == '.') - { - decimalPos = i; - break; - } - } - // we like sprintf's float up-rounding. - // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation - // ;) - sprintf(lng, "%02d%s%c", atoi(lng) * (negative ? -1 : 1), s_min_nn(atoi(lng + decimalPos + 1), hp), negative ? 'W' : 'E'); -} - -// creates the dao at the end of aprs message based on latitude and longitude -void create_dao_aprs(char *lat, char *lng, char *dao) -{ - // !DAO! extension, use Base91 format for best precision - // /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest - // integer https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm - // http://www.aprs.org/aprs12/datum.txt - - int len = strlen(lat); - int decimalPos = 0; - // use for loop in case there is no decimal - for (int i = 0; i < len; i++) - { - if (lat[i] == '.') - decimalPos = i; - } - sprintf(dao, "!w%s", s_min_nn((int)(lat + decimalPos + 1), 2)); - - len = strlen(lng); - decimalPos = 0; - for (int i = 0; i < len; i++) - { - if (lng[i] == '.') - decimalPos = i; - } - sprintf(dao + 3, "%s!", s_min_nn((int)(lng + decimalPos + 1), 2)); -} - -// adds a specified number of zeros to the begining of a number -void padding(unsigned int number, unsigned int width, char *output, int offset) -{ - unsigned int numLen = numDigits(number); - if (numLen > width) - { - width = numLen; - } - for (unsigned int i = 0; i < width - numLen; i++) - { - output[offset + i] = '0'; - } - sprintf(output + offset + width - numLen, "%u", number); -} - -int numDigits(unsigned int num) -{ - if (num < 10) - return 1; - return 1 + numDigits(num / 10); -} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.h deleted file mode 100644 index 2e367ab0..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSEncodeFunctions.h +++ /dev/null @@ -1,47 +0,0 @@ -/* -MIT License - -Copyright (c) 2020 Peter Buchegger - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -*/ - -#ifndef APRS_ENCODE_FUNCTIONS_H -#define APRS_ENCODE_FUNCTIONS_H - -#if defined(ARDUINO) -#include -#elif defined(_WIN32) || defined(_WIN64) // Windows -#include -#include -#include -#elif defined(__unix__) // Linux -// TODO -#elif defined(__APPLE__) // OSX -// TODO -#endif - -char *s_min_nn(uint32_t min_nnnnn, int high_precision); -void create_lat_aprs(char *lat, bool hp); -void create_long_aprs(char *lng, bool hp); -void create_dao_aprs(char *lat, char *lng, char *dao); -void padding(unsigned int number, unsigned int width, char *output, int offset = 0); -int numDigits(unsigned int num); - -#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index 69359f1a..3240f409 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -208,4 +208,162 @@ const char *APRSBody::encode() void APRSBody::toString(char *str) { sprintf(str, "Data:%s", _data); +} + +// creates the latitude string for the APRS message based on whether the GPS coordinates are high precision +void APRSMsg::formatLat(char *lat, bool hp) +{ + bool negative = lat[0] == '-'; + + int len = strlen(lat); + int decimalPos = 0; + // use for loop in case there is no decimal + for (int i = 0; i < len; i++) + { + if (lat[i] == '.') + { + decimalPos = i; + break; + } + } + int decLen = strlen(lat + decimalPos + 1); + int dec = atoi(lat + decimalPos + 1); + + // make sure there are nine digits + int missingDigits = 9 - decLen; + if (missingDigits < 0) + for (int i = 0; i < missingDigits * -1; i++) + dec /= 10; + if (missingDigits > 0) + for (int i = 0; i < missingDigits; i++) + dec *= 10; + + // we like sprintf's float up-rounding. + // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation + // ;) + sprintf(lat, "%02d%s%c", atoi(lat) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'S' : 'N'); +} + +// creates the longitude string for the APRS message based on whether the GPS coordinates are high precision +void APRSMsg::formatLong(char *lng, bool hp) +{ + bool negative = lng[0] == '-'; + + int len = strlen(lng); + int decimalPos = 0; + // use for loop in case there is no decimal + for (int i = 0; i < len; i++) + { + if (lng[i] == '.') + { + decimalPos = i; + break; + } + } + + int decLen = strlen(lng + decimalPos + 1); + int dec = atoi(lng + decimalPos + 1); + + // make sure there are nine digits + int missingDigits = 9 - decLen; + if (missingDigits < 0) + for (int i = 0; i < missingDigits * -1; i++) + dec /= 10; + if (missingDigits > 0) + for (int i = 0; i < missingDigits; i++) + dec *= 10; + + // we like sprintf's float up-rounding. + // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation + // ;) + sprintf(lng, "%02d%s%c", atoi(lng) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'W' : 'E'); +} + +// creates the dao at the end of aprs message based on latitude and longitude +void APRSMsg::formatDao(char *lat, char *lng, char *dao) +{ + // !DAO! extension, use Base91 format for best precision + // /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest + // integer https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm + // http://www.aprs.org/aprs12/datum.txt + + int len = strlen(lat); + int decimalPos = 0; + // use for loop in case there is no decimal + for (int i = 0; i < len; i++) + { + if (lat[i] == '.') + decimalPos = i; + } + sprintf(dao, "!w%s", s_min_nn((int)(lat + decimalPos + 1), 2)); + + len = strlen(lng); + decimalPos = 0; + for (int i = 0; i < len; i++) + { + if (lng[i] == '.') + decimalPos = i; + } + sprintf(dao + 3, "%s!", s_min_nn((int)(lng + decimalPos + 1), 2)); +} + +// adds a specified number of zeros to the begining of a number +void APRSMsg::padding(unsigned int number, unsigned int width, char *output, int offset) +{ + unsigned int numLen = numDigits(number); + if (numLen > width) + { + width = numLen; + } + for (unsigned int i = 0; i < width - numLen; i++) + { + output[offset + i] = '0'; + } + sprintf(output + offset + width - numLen, "%u", number); +} + +// takes in decimal minutes and converts to MM.dddd +char *s_min_nn(uint32_t min_nnnnn, int high_precision) +{ + /* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth + * degree (-> *= 6 -> nn.mmmmmm minutes) high_precision: 0: round at decimal + * position 2. 1: round at decimal position 4. 2: return decimal position 3-4 + * as base91 encoded char + */ + + static char buf[6]; + + min_nnnnn = min_nnnnn * 0.006; + + if (high_precision) + { + if ((min_nnnnn % 10) >= 5 && min_nnnnn < 6000000 - 5) + { + // round up. Avoid overflow (59.999999 should never become 60.0 or more) + min_nnnnn = min_nnnnn + 5; + } + } + else + { + if ((min_nnnnn % 1000) >= 500 && min_nnnnn < (6000000 - 500)) + { + // round up. Avoid overflow (59.9999 should never become 60.0 or more) + min_nnnnn = min_nnnnn + 500; + } + } + + if (high_precision < 2) + sprintf(buf, "%02u.%02u", (unsigned int)((min_nnnnn / 100000) % 100), (unsigned int)((min_nnnnn / 1000) % 100)); + else + sprintf(buf, "%c", (char)((min_nnnnn % 1000) / 11) + 33); + // Like to verify? type in python for i.e. RawDegrees billions 566688333: i = + // 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33) + return buf; +} + +int numDigits(unsigned int num) +{ + if (num < 10) + return 1; + return 1 + numDigits(num / 10); } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h index ac6ae169..bca89ae5 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h @@ -122,7 +122,7 @@ class APRSMessageType } private: - Value value; + Value value = Error; }; class APRSBody @@ -139,7 +139,7 @@ class APRSBody virtual void toString(char *str); private: - char _data[80]; + char _data[80]{0}; }; class APRSMsg @@ -168,12 +168,17 @@ class APRSMsg virtual void encode(char *message); virtual void toString(char *str); + static void formatLat(char *lat, bool hp); + static void formatLong(char *lng, bool hp); + static void formatDao(char *lat, char *lng, char *dao); + static void padding(unsigned int number, unsigned int width, char *output, int offset = 0); + private: - char _source[8]; - char _destination[8]; - char _path[10]; + char _source[8]{0}; + char _destination[8]{0}; + char _path[10]{0}; APRSMessageType _type; - char _rawBody[80]; + char _rawBody[80]{0}; APRSBody _body; }; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp index 8853c819..4635b0c6 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp @@ -245,14 +245,14 @@ bool RFM69HCW::encode(char *message, EncodingType type, int len) if (data.precision == 'L') { strcpy(data.dao, ""); - create_lat_aprs(data.lat, 0); - create_long_aprs(data.lng, 0); + APRSMsg::formatLat(data.lat, 0); + APRSMsg::formatLong(data.lng, 0); } else if (data.precision == 'H') { - create_dao_aprs(data.lat, data.lng, data.dao); - create_lat_aprs(data.lat, 1); - create_long_aprs(data.lng, 1); + APRSMsg::formatDao(data.lat, data.lng, data.dao); + APRSMsg::formatLat(data.lat, 1); + APRSMsg::formatLong(data.lng, 1); } // get alt string @@ -260,12 +260,12 @@ bool RFM69HCW::encode(char *message, EncodingType type, int len) if (alt_int < 0) { strcpy(data.alt, "/A=-"); - padding(alt_int * -1, 5, data.alt, 4); + APRSMsg::padding(alt_int * -1, 5, data.alt, 4); } else { strcpy(data.alt, "/A="); - padding(alt_int, 6, data.alt, 3); + APRSMsg::padding(alt_int, 6, data.alt, 3); } // get course/speed strings @@ -274,8 +274,8 @@ bool RFM69HCW::encode(char *message, EncodingType type, int len) int hdg_int = max(0, min(360, atoi(data.hdg))); if (hdg_int == 0) hdg_int = 360; - padding(spd_int, 3, data.spd); - padding(hdg_int, 3, data.hdg); + APRSMsg::padding(spd_int, 3, data.spd); + APRSMsg::padding(hdg_int, 3, data.hdg); // generate the aprs message APRSMsg aprs; From fa056e7ec94a795f74a1c854168ab477f547a57c Mon Sep 17 00:00:00 2001 From: jhauerst <114038876+jhauerst@users.noreply.github.com> Date: Fri, 5 Apr 2024 01:05:34 -0400 Subject: [PATCH 03/41] radio code bug fixes, preparing for long packets --- .../Teensy-Based Avionics/src/APRSMsg.cpp | 3 + .../Teensy-Based Avionics/src/RFM69HCW.cpp | 78 ++++++++++++++++++- .../Code/Teensy-Based Avionics/src/RFM69HCW.h | 6 +- 3 files changed, 84 insertions(+), 3 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index 3a139132..44a26d2e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -24,6 +24,9 @@ SOFTWARE. #include "APRSMsg.h" +char *s_min_nn(uint32_t min_nnnnn, int high_precision); +int numDigits(unsigned int num); + APRSMsg::APRSMsg() : _body() { } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp index 3a2d8b77..235bbb84 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp @@ -1,5 +1,13 @@ #include "RFM69HCW.h" +#ifndef max +int max(int a, int b); +#endif + +#ifndef min +int min(int a, int b); +#endif + /* Constructor - frequency in hertz @@ -64,6 +72,10 @@ bool RFM69HCW::begin() this->radio.setThisAddress(this->addr); this->radio.setHeaderId(this->id); + // configure unlimited packet length mode, don't do this for now + // this->radio.spiWrite(0x37, 0b00000000); // Packet format (0x37) set to 00000000 (see manual for meaning of each bit) + // this->radio.spiWrite(RH_RF69_REG_38_PAYLOADLENGTH, 0); // Payload length (0x38) set to 0 + if (this->settings.highBitrate) // Note: not working { // the default bitrate of 4.8kbps should be fine unless we want high bitrate for video @@ -91,11 +103,11 @@ bool RFM69HCW::tx(const char *message, int len) return false; // reset variables for tx - this->id = 0x00; + this->totalPackets = 0x00; // get number of packets for this message, and set this radio's id to that value so the receiver knows how many packets to expect this->totalPackets = len / this->bufSize + (len % this->bufSize > 0); - this->radio.setHeaderId(this->id); + this->radio.setHeaderId(this->totalPackets); sendBuffer(); if (message != nullptr) @@ -119,6 +131,68 @@ void RFM69HCW::endtx() this->radio.setHeaderId(this->id); } +// partially adapted from RadioHead library +bool RFM69HCW::txs(const char *message, int len) +{ + // figure out how long the message should be + if (len > 0) + this->msgLen = len > MSG_LEN ? MSG_LEN : len; + else if (this->msgLen == -1) + return false; + + if (message != nullptr) + memcpy(this->msg, message, len); + + this->radio.waitPacketSent(); // Make sure we dont interrupt an outgoing message + this->radio.setModeIdle(); // Prevent RX while filling the fifo + + if (!this->radio.waitCAD()) + return false; // Check channel activity + + ATOMIC_BLOCK_START; + this->settings.spi->beginTransaction(); + digitalWrite(this->settings.cs, LOW); + this->settings.spi->transfer(RH_RF69_REG_00_FIFO | RH_RF69_SPI_WRITE_MASK); // Send the start address with the write mask on + this->settings.spi->transfer(this->msgLen + 1); // Include length of headers + // First the header + this->settings.spi->transfer(this->toAddr); // type of transmitter that should receive this message + // Now the payload + while (this->msgIndex++ != this->msgLen && !this->radio.spiRead(RH_RF69_IRQFLAGS2_FIFOFULL)) // these conditions need to be verified + this->settings.spi->transfer(this->msg[this->msgIndex]); + digitalWrite(this->settings.cs, HIGH); + this->settings.spi->endTransaction(); + ATOMIC_BLOCK_END; + + this->radio.setModeTx(); // Start the transmitter + return true; +} + +bool RFM69HCW::txT() +{ + if (!this->radio.spiRead(RH_RF69_IRQFLAGS2_FIFONOTEMPTY) || !this->radio.spiRead(RH_RF69_FIFOTHRESH_FIFOTHRESHOLD)) + { + // this is basically tx without preprocessing and no toAddr byte + ATOMIC_BLOCK_START; + this->settings.spi->beginTransaction(); + digitalWrite(this->settings.cs, LOW); + this->settings.spi->transfer(RH_RF69_REG_00_FIFO | RH_RF69_SPI_WRITE_MASK); // Send the start address with the write mask on + while (this->msgIndex++ != this->msgLen && !this->radio.spiRead(RH_RF69_IRQFLAGS2_FIFOFULL)) // these conditions need to be verified + this->settings.spi->transfer(this->msg[this->msgIndex]); + digitalWrite(this->settings.cs, HIGH); + this->settings.spi->endTransaction(); + ATOMIC_BLOCK_END; + return this->radio.spiRead(RH_RF69_IRQFLAGS2_PACKETSENT); + } + return false; +} + +void RFM69HCW::txe() // try to get rid of this one +{ + this->msgLen = -1; + this->id = 0x00; + this->radio.setHeaderId(this->id); +} + /* Receive function Most basic receiving method, simply checks for a message and returns a pointer to it diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h index 9fc4cda6..11a54040 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h @@ -12,7 +12,6 @@ #include "Radio.h" #include "APRSMsg.h" #include "RH_RF69.h" -#include "APRSEncodeFunctions.h" /* Settings: @@ -43,7 +42,11 @@ class RFM69HCW : public Radio bool tx(const char *message, int len = -1) override; bool sendBuffer(); void endtx(); + bool txs(const char *message, int len = -1); + bool txT(); + void txe(); const char *rx() override; + void rxL(); bool busy(); bool encode(char *message, EncodingType type, int len = -1) override; bool decode(char *message, EncodingType type, int len = -1) override; @@ -83,6 +86,7 @@ class RFM69HCW : public Radio bool avail; int rssi; int totalPackets; + int msgIndex = 0; }; #endif // RFM69HCW_H \ No newline at end of file From a2411e67ab3909177a25b4e50923068763bbb88d Mon Sep 17 00:00:00 2001 From: Varun Unnithan Date: Fri, 5 Apr 2024 01:18:19 -0400 Subject: [PATCH 04/41] Small bug fixes from merge --- Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp | 4 ++-- Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h | 5 ----- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp index 235bbb84..194e0a04 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp @@ -333,12 +333,12 @@ bool RFM69HCW::encode(char *message, EncodingType type, int len) if (altInt < 0) { strcpy(data.alt, "/A=-"); - APRSMsg::padding(alt_int * -1, 5, data.alt, 4); + APRSMsg::padding(altInt * -1, 5, data.alt, 4); } else { strcpy(data.alt, "/A="); - APRSMsg::padding(alt_int, 6, data.alt, 3); + APRSMsg::padding(altInt, 6, data.alt, 3); } // get course/speed strings diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h index 11a54040..19abb2ff 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h @@ -62,11 +62,6 @@ class RFM69HCW : public Radio // length of msg for recieving binary messages int msgLen = 0; - // stores full messages, max length determined by platform - char msg[MSG_LEN + 1]; - // length of msg for recieving binary messages - int msgLen = 0; - private: RH_RF69 radio; // all radios should have the same networkID From 71306cca37fbff1d387c89a2f7954b30d9d6c28c Mon Sep 17 00:00:00 2001 From: Varun Unnithan Date: Fri, 5 Apr 2024 01:20:43 -0400 Subject: [PATCH 05/41] added artificial newlines --- Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp | 2 +- .../Code/Teensy-Based Avionics/test/ReceiverTest.cpp | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 458bc4f4..938a8281 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -12,7 +12,7 @@ BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 DS3231 rtc(); // I2C Address 0x68 APRSConfig config = {"KC3UTM", "APRS", "WIDE1-1", '[', '/'}; -RadioSettings settings = {433.775, true, false, &hardware_spi, 10, 31, 32}; +RadioSettings settings = {915.0, true, false, &hardware_spi, 10, 31, 32}; RFM69HCW radio = {settings, config}; State computer;// = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp index 5730c4d6..a44acb50 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp @@ -6,12 +6,12 @@ #define PATH "WIDE1-1" APRSConfig config = {CALLSIGN, TOCALL, PATH, '[', '/'}; -RadioSettings settings = {433.775, false, false, &hardware_spi, 10, 2, 9}; +RadioSettings settings = {915.0, false, false, &hardware_spi, 10, 31, 32}; RFM69HCW receive = {&settings, &config}; void setup() { - Serial.begin(9600); + Serial.begin(115200); while (!Serial) ; @@ -25,6 +25,8 @@ void loop() { if (receive.available()) { - Serial.println(receive.receive(ENCT_GROUNDSTATION)); + Serial.print("s\n"); + Serial.print(receive.receive(ENCT_GROUNDSTATION)); + Serial.print("\ne\n"); } } \ No newline at end of file From cde1a15670a47c41935f27dd43906d45ff993f0f Mon Sep 17 00:00:00 2001 From: Varun Unnithan Date: Fri, 5 Apr 2024 01:31:57 -0400 Subject: [PATCH 06/41] small fixes --- Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp | 3 +++ Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp index 194e0a04..97145a81 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp @@ -131,6 +131,9 @@ void RFM69HCW::endtx() this->radio.setHeaderId(this->id); } +RHGenericDriver::RHMode RFM69HCW::mode() { return radio.mode(); } + + // partially adapted from RadioHead library bool RFM69HCW::txs(const char *message, int len) { diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 938a8281..61291c55 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -13,7 +13,7 @@ MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 DS3231 rtc(); // I2C Address 0x68 APRSConfig config = {"KC3UTM", "APRS", "WIDE1-1", '[', '/'}; RadioSettings settings = {915.0, true, false, &hardware_spi, 10, 31, 32}; -RFM69HCW radio = {settings, config}; +RFM69HCW radio = {&settings, &config}; State computer;// = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); From 1a5a87dd517901042ee4210f34fb7344608e467f Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Sat, 20 Apr 2024 22:32:30 -0400 Subject: [PATCH 07/41] Added switch BNO to 16G mode --- .../23-24/Code/Teensy-Based Avionics/src/BNO055.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp index faf8ecf9..6a2e078f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp @@ -14,6 +14,17 @@ bool BNO055::initialize() } bno.setExtCrystalUse(true); + // set to +-16g range + adafruit_bno055_opmode_t mode = bno.getMode(); + bno.setMode(OPERATION_MODE_CONFIG); + delay(25); + Wire.beginTransmission(0x29);//BNO055 address + Wire.write(0x08);//ACC_CONFIG register address on BNO055 + Wire.write(0b11);//set to +-16g range + Wire.endTransmission(true); // send stop + bno.setMode(mode); + delay(25); + initialMagField = bno.getVector(Adafruit_BNO055::VECTOR_MAGNETOMETER); imu::Vector<3> read = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL); for (int i = 0; i < 20; i++) From 9a2a39dc1bc4499822e63986c14294c7896870b0 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Sat, 20 Apr 2024 22:35:41 -0400 Subject: [PATCH 08/41] Added if RAM dead, continue to print to SD card --- .../lib/RecordData/RecordData.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp index b90935bc..4fd1761e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp @@ -4,9 +4,9 @@ static const char *logTypeStrings[] = {"LOG", "ERROR", "WARNING", "INFO"}; static Mode mode = GROUND; void recordFlightData(char *data) { - if(!isSDReady()) + if (!isSDReady()) return; - if (mode == GROUND) + if (mode == GROUND || !ram->isReady()) { flightDataFile = sd.open(flightDataFileName, FILE_WRITE); // during preflight, print to SD card constantly. ignore PSRAM for this stage. if (flightDataFile) @@ -15,7 +15,7 @@ void recordFlightData(char *data) flightDataFile.close(); } } - else if(ram->isReady()) + else ram->println(data); // while in flight, print to PSRAM for later dumping to SD card. } @@ -40,7 +40,7 @@ void recordLogData(double timeStamp, LogType type, const char *data, Dest dest) } if ((dest == BOTH || dest == TO_FILE) && isSDReady()) { - if (mode == GROUND) + if (mode == GROUND || !ram->isReady()) { logFile = sd.open(logFileName, FILE_WRITE); // during preflight, print to SD card constantly. ignore PSRAM for this stage. With both files printing, may be bad... if (logFile) @@ -50,7 +50,7 @@ void recordLogData(double timeStamp, LogType type, const char *data, Dest dest) logFile.close(); } } - else if (ram->isReady()) // while in flight, print to PSRAM for later dumping to SD card. + else // while in flight, print to PSRAM for later dumping to SD card. { ram->print(logPrefix, false); ram->println(data, false); @@ -60,10 +60,11 @@ void recordLogData(double timeStamp, LogType type, const char *data, Dest dest) void setRecordMode(Mode m) { - if(mode == FLIGHT && m == GROUND){ + if (mode == FLIGHT && m == GROUND && ram->isReady()) + { ram->dumpFlightData(); ram->dumpLogData(); - bb.aonoff(LED_BUILTIN, 2000);//turn on LED for 2 seconds to indicate that the PSRAM is being dumped to the SD card. + bb.aonoff(LED_BUILTIN, 2000); // turn on LED for 2 seconds to indicate that the PSRAM is being dumped to the SD card. } mode = m; } From ea63e5f41e8ef1d2453c0eebe188c911c7a0b817 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 2 May 2024 14:48:02 -0400 Subject: [PATCH 09/41] Refactor LinearKalmanFilter constructor to remove unused include statement --- .../src/Filters/LinearKalmanFilter/LinearKalmanFilter.cpp | 1 - Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini | 3 --- 2 files changed, 4 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/Kalman-Filter-main/src/Filters/LinearKalmanFilter/LinearKalmanFilter.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/Kalman-Filter-main/src/Filters/LinearKalmanFilter/LinearKalmanFilter.cpp index 37abd7a0..5a930f4c 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/Kalman-Filter-main/src/Filters/LinearKalmanFilter/LinearKalmanFilter.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/Kalman-Filter-main/src/Filters/LinearKalmanFilter/LinearKalmanFilter.cpp @@ -1,5 +1,4 @@ #include "LinearKalmanFilter.h" -#include "Matrix.h" LinearKalmanFilter::LinearKalmanFilter(Matrix X, Matrix U, Matrix P, Matrix F, Matrix G, Matrix R, Matrix Q) { state.X = X; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index 292bd841..43e5628c 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -22,7 +22,6 @@ lib_deps = adafruit/Adafruit BMP3XX Library@^2.1.2 adafruit/RTClib @ ^2.1.1 adafruit/Adafruit BNO055@^1.6.3 - adafruit/Adafruit Unified Sensor@^1.1.14 sparkfun/SparkFun u-blox GNSS v3@^3.0.16 https://github.com/DrewBrandt/BlinkBuzz.git check_src_filters = -<*> + + + - @@ -41,7 +40,6 @@ lib_deps = adafruit/Adafruit BMP3XX Library@^2.1.2 adafruit/RTClib @ ^2.1.1 adafruit/Adafruit BNO055@^1.6.3 - adafruit/Adafruit Unified Sensor@^1.1.14 sparkfun/SparkFun u-blox GNSS v3@^3.0.16 check_src_filters = -<*> + + + - check_flags = @@ -59,7 +57,6 @@ lib_deps = adafruit/Adafruit BMP3XX Library@^2.1.2 adafruit/RTClib @ ^2.1.1 adafruit/Adafruit BNO055@^1.6.3 - adafruit/Adafruit Unified Sensor@^1.1.14 sparkfun/SparkFun u-blox GNSS v3@^3.0.16 https://github.com/DrewBrandt/BlinkBuzz.git check_src_filters = -<*> + + + - From 610ada1a16b9619111b001efb1bf7792632a559b Mon Sep 17 00:00:00 2001 From: Varun Unnithan Date: Sat, 11 May 2024 17:47:18 -0400 Subject: [PATCH 10/41] change? --- Spaceport/23-24/Code/Rpi-Middleman/data7.log | Bin 0 -> 13107022 bytes .../Code/Teensy-Based Avionics/src/main.cpp | 135 +++--------------- .../test/ReceiverTest.cpp | 6 +- 3 files changed, 20 insertions(+), 121 deletions(-) create mode 100644 Spaceport/23-24/Code/Rpi-Middleman/data7.log diff --git a/Spaceport/23-24/Code/Rpi-Middleman/data7.log b/Spaceport/23-24/Code/Rpi-Middleman/data7.log new file mode 100644 index 0000000000000000000000000000000000000000..015f5acedd66d4c21fc0d3f48456e2dbe2216df6 GIT binary patch literal 13107022 zcmeF)ZI3L+c^=^UyukhkesmBY`RvT>TY?0UWy>;bIgTtR`5?fiWl~X0kpfBi4Mu)? zlCCWk>*<;9DvIZArsslS?~>g++;jJHUtLpYcjo{7-@i;>rZ3XZ(3_dWpQm4> zkJ8uEKYucP{#E*ybVzs8zxloN>-1UrcslawbpDs=SLr_-o%bK7fBw7a*vHe+zdt#e zA0?mh>2&nt>8n3U|Mc=W|L}5V`I_In{P({||1RC8oAm0;|ChhV|33XWzI^#pe>Hvf z(e&r~V*0b^&wf7rDL;QnB>z*+^5f~e&!*4*e){Ksoc^RAPapqw`ZNAx`u*v%{HOiL z>1cbjzn%W=7gOqAPv?FyeSQA#{UH6<^cU%e=}*(2q`yu-N#9RDoj%Y1E?vrayoAZhkm@H$O=~e))cWIz48cqC7!|>1*!N)AavePuKXP^q;5y zo1at8$dC7<>Ct|Y{wV#Amydt^@_2tbJ?{UU{_RhvM|qtd(r)_thv~D|)4%^w`q!5n z@26wC^k?Z0r(-#vAHV$D$LYWMnC_>4%K!d{FO&S$^!?}m(jTQip8oA$Pl@IXe~^AN zrSj#=_x<(s&%c-c_jGpd#Xr1!&wrf$`6ZVxU#{q9Cufu_zCS(ApH2VuKbao;uU;NE z|NDHEmm2VD%0G9e&VS7Pqx4^yR7u`Sjn<|MrJ3-%SczG z=RSW|Ur+yy&!(^VgX!z?_xtJe?|$)eZ9kd5>etgheKCFfY)bvpm;B22@zFFPrNOyF z$N#neGyR*EN^b2Brn7(b(x2SY{NK&9^7YGin$P}fI{xYO&-n`daQgf=(|3~l|2*Z8 zA8Y>AS%;5a9--#&%jw^I_43t!HJzPB`Fwi(Vsy@6o=-XZd()r%doN$JoZz3lWc=&j zPXE76DdegAtEs_%I(@9u_WI=!{_tfcb4vBUnm>LtJ;Eo`_xZ{69nIa#f6kgo$)bF( zS)iQw&!&v>l;=nM*=$C$C_kGX?aS%U`Lik0GI`&d{^{4#|FTv2vGa`NCf4uf+dgi- z`gwN$>1Db;nI12H|K-a6U`pbX>A%w+HQxvSb^3Q7P3L{P@4NT-rx||tN6p{qKfffA zQ;t(z6Zy^b9e*|*`}k$fem(uEznF5)_krv}n~m>J_pa|xS3IlzhtvNr!Zz#jbVr9? zO^=Xg`}E)ER{ip~-&4LP{bYKqznF~9{fXbr-%Q`x{JZ%m{il=vN_(`w4u6vRr+XX8 zm32kA^W>SxkNxrVXUlinJlpvm`{QXEvsnK&{onI%?=c@u+P<3pWUr=Uc^2#Ae1E!c z=V{HWqjHDO#^-;|`F%Of^heW?();{x^8F)co2APuth%1cYpZgnFZPrxmhaJJ8gufw z^SMF4c)1SwpFW)){N&}|WzqA0 z?emxKD$hwiGheNo&DY=jx$?iweb0ZEzj-WFHGfa#yU&l7 zvni?MB>H++sq@Mz+m~ng%PISL!tuZN-(KeN>zDca!ONfMv-Iz$t6Hw+k6*sy-y9wN z>2HtzXgd1Y^d~PXfqaef*XE=7Dt$Kn?~BQhvWEM+7vZj@Mw)^dDlnKfI zzi8@MOQd`z7c*fdS_1l@4{aJ4sSo;~4=n+G(1$h+?hpE)5Bks&&42YqPM;QpWw`k)Uj0e#SiHVy6%`k)W`&=SxGeQ49*{-6)~ zpbsqpeb9$C4ek&6pbz@c63_>IXw%^Spbz?>4=n+G(1$h+?hpE)5Bks&&42YqPM;QpWw`k)Ujfy?W|zVlk7jO@sS` zKInr!v;_1)AKEmyKj?!#=tE0DAM~M3!#Up{4xQH`bu3=P)@ixO<+#&k!c3S6M&@-7 z3s}Gc7O)^XkUuvQX2MLg1oS~4+BB5U%!HXR6D=z~7AX>fng2Yt|omViF!Lz@Qo z2Yt{7eP{{jgFduraDUJTeb9%NfIjF$n+Ep>eb5JeXbI?pKD23Yf6xbg(1(_QKIlW6 z2KNVj&y0`VuT$%-T;y`xTQgxM%mgFz+J*%zU;ztQ5FN;$ zn+Y>vCRzgepbu>t%4cT6Oqhw5fIjF$n+8VegFfg(OF$p=p-qGPgFfhkKC}e%K_A*Q zxIgHFKIlVBKp*s>O@sS`KInr!v;_1)AKEmyKj?!#=tE0DAM~M3gZqO%=z~7A1oS~4 z+BCR7=z~7!LrXv(^r20|b=@DHI=?IH*nBFg6LOJDO~6b%C4H#VP(GRoGclit_Iua5 zGEYWVbY(sfx^gq!Q8_W63Qm}b`9yGn6YH<@#m{+L_{q=tMDUZJ{EVGoBqQTI87 znK+-BcvyX{_^0GpyiTpRa*<0(z)WPz^+6x>fdwpx4&=|xgqbiCEdhPdhc*r6Gc#c( z%tT8-AM~M310(f8AM~Lmpbz@crosI|AM`;VS_1l@4{aLUAM`;V^r0o75Bkui!TmuW z^g$n50{Wm2Z5rGk^g$o=p(UUX`p~Aq{Xrk}K_6NI`k)VO8r&cBK_B#?C7=)b(5Aut zK_B!%A6f$Xpbu>t+#mEoAM~Lmpbz@crosI|AM`;VS_1l@4{aLUAM`;V-d`V{(_wl= zz~%p*V{&N;6qn3IOQd`zmrI(7=ZIXw$$*eb5JeXbI?pKD23Yf6xbg(1(_QKIlW6 z2KNVj&=z~7AX>fng2Yt|omViF! zLz@Qo2Yt{7eP{{jgFduraDUJTeb9%NfIjF$n+Ep>eb5JeXbI?pKD23Yf6xbg(1(_Q zKIlW6hV#8Y+)u9#wDx^EHczH@S}t;_37CoJqz`o(%11L{Cgu~-UV~3p=E>-auFNMw zS8k@)GUmj5DmY;#<`cmQPT0GMonRy*<2>Zg&4ih_gqe7nR=jK9r(^SEYNzEQmzsc? zc%I%tlp%E<@<%gaCgMDpiQAN)Gjn1-6`U{=^NDcp;DohQ>;xkj8RsE?ZYIoxnP>^< zgFdurD4&@LGhrrL0{Wm2Z5kM<5Bi`FEdhPdhc*qr%l+Y@^Yasq#Y|hrt+#mEoAM~Lmpbz@crosI|AM`;V zS_1l@4{aK*>Hcsxy`IEA-L1TWouhFUq#+GWDfdcU&;?!4h0+3D&;?!41*-xQl8}TX zBq0e&_yJHpnBk1~QO=gd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|VIB67IXNY3yj6c4@qw zG#;n-0*oEXpSMSLR2uW?FdH!sX-FeK6X7H$V-utyjhpEmmdTLkz+E!7K^oE^Lzw|x z&;?!41$$5=Bq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wx8cOl_j_h%p-jZ-HLX{>e7 zY?uwRQC6zDpbNU73uOj$K^JsE7pw|MNJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqZUtlkhI> z(qZ*Aa2(A|s!2*i8u9Kb4Qbq_{BB=l&;?!4g*F4$3@r;QsF;N`q+!iaXMmG6iTqI- z((r7e%z!TFf-dNS-Dwh%kc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2ejT}yc1eN72RV+W-njWv8Aqh!HLK2dYgd`*(2}yWe65glB z&QE1K8sC3G8q$dONNGr;ylW2`bU_z%q0T^iE=h*1%kb1)KRX(`APs3$BlAaTNF(pL z-6t~Wf-dMnnE_qU1zpeus{#^|kc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2>jgwNeq9(FW(B@Jn;>1{U5hS?~0c3sc~UC@QoRW2E}E5mMj z4gS}w&n6trZKzjY8q$b&NNGspHs$v|BZDsJf-bZfux4mkSV6@sq#+G!hB^bBtV!gL z(vXH{6J-W;K^JsE7wk@xkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTPbIwTzBZbp(G6)xV@*-B zVK&T0xx?y$F6e?TSZ$J!gd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NWyn3;eC4S z{H%+k@!c7uA&uyfG^A19(}xVYpbNTCXP~Xy$v}oW73HJZh8Aqh!HLK2>Xgiqa{uX8kBBWXxu z?cQxR%!b)0>pES~1zpgE)8{y3AOji5Kn4<$kc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNl3y= zmT*74ruO<3bTs$7USDZQBi{3+A&uLV->ZTQx}XcX&}P7zp=DtO6|<0rG^`ow3~;h0 zkv~d98lFv*8PEk?&;?zvJ553ol8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`;4c}n;^{cimHf6*&P zr4gq?8qz5DGBW6bF6cs;0bS4qUC;%q0uqvtgd`*(2}wvo5|WUFBqSjTNk~Exl8}U3 zlW?CNj(&k~N9^Q5w>)W+*f8wz}}x-S>7h<}3|qtO;y3%!b)0cV}JD1zpgE)0HY2 z$Up`%kb#6GBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l za7z+CbzjrCcl0scb-vco_!{iekVaHP8qz55+(8Ci&;?znGtgGoWFSMGit^EH#5|-S zjl3hrNlwNlNJARdlXV8%C2JD-qco&p%}{1Q7j!`vbiv=^k&uKWBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H!mUcU z>%RJ#qp|zakj9#XX2WcljdGXN1zpeuT_`i43%Z~Sx?oj6LK2dYgd`*(2}wvo5|WUF zBqSjTNk~ExlJLVw_?+%LKMC_Lk3Mw&yN_G?wp@W+T2YfHb5Ldm;^Kly{RM zgD&WTF4P&Yo~%jakJ6Av-h*jtX-LDGq0WH2WKAM}l!i2{8OjXkf-dNSF8F&o z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2ejQY3urzT&Z?Q8Q^sW6gH6VK&T0x$o1X-9Krb#kO3jo2Y+NaHr;cS#_F zF6e?Tv>C8wXjxc6#Vn*D4Qqxv1Dvc$8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2dYgd}_u37@;KsOe}lRvOY+yW^M*vtc&MYD5=wK^Ju4bY)Hk zGLV4`WFR34Nk~Exl8}TXBq0e&NJ0{33Gb)(`in{A&)aM`DvkMcn2nf+G^9b%G6TAx z3%Z~S){`V8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8 zAqh$N?j(%a?z=z#@2ITS=Fn`I4YN^JYr3Edx}XbX26RCebU_!a3P?yo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF?^eR6>AgT=#`*I$ zb&g77J{@Kw<{=GfWS=?7$=C#GNaH4vp-h3hWNd>pq(KHUc-~Dy5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|Z$3NqFD=Js?M8&eD*^+WpsT zm<_X0)@Hh(3%Z~Sr_WQ!Kn609fea)hAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}$_7NO(WJ=il?{@BccQv#hE}LmJUn zX-MNX<#+ocgD&WTF0>hFYlgdN{m}k>`OMLnh%}^;@1dF!pKC}%8qo!5NTWR0AcHRG zf-ck8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUF?_a{Z?kf*F8fQ`((pYP#*)SVsqpV|fK^JsE7s?Fif-dO77P|15 z_MK;oj>cD(mWDK<`_hm`c|QU&=z=cjLY;y3{D=%>s8dlsnvIx;G^CMt5;)1p*aT@v z!+NsLfV*T(B7c;IG^`oQ4CsO`=z=czTRakykc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wx8w=3bH`>Jb>MsuVg zjWvPIhS@M1keeJ$9wx7mhw+oKOE=WTfORIwHq}ebVW+ShybYZ@NA_E!7K!!2{ zx}XcXpbJ(7BqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl5k5BK6PKy*wHxc(vZel_sxdcFdJostP8rJ3%XEdKo@jD7j(g@fP^F@Aqg)}!iTi$ z>=QZ~-^E56(unstX-MPd<(*W?pbNU73v~wC^FcC@p-x5lXf|RV(vU{pIpHKHV-uty z4eQA|1MZSFiTqI-(y(SIGoTB)pbNU-Z}CV-LK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2ejyGgk3zKVjQajv8xjkT7U4YOf3%34$xbU_z% zq0E3T=z=cjf>i+tNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBwUv8d3pzicqD(`vT{@!^XV`fF%M}-Bd@PG$;sFRX-K2Ii_I2gc8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqg)+lgJ;X zAq{JWG6TAx3%Z~S{-%b6BqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}$_=CA{mt zF0rF=CZ!>bwT7Avvtc&MI#w5SK^JtP%z!TFf-W3);c8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTN%)~9e45?`@UZ&oI*#U!)@vjUX~g@sG^BBx z@;e-nK^JsE7upP1GqfzMpkfx%kcKrwodHhPB=SdTNW-&8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTN!XY0zWe$}jz&eLA&s?rirFw5W}~b(bU_z%K^IQf-ee#H8OT5e5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh$NrV<{ecd?2o=Fi()IVz3$beN5phcu*- z1?D6tV-utyjq+|^WY7g&(1kh!R*W@?{81XxuzoHxpbNU73%X!GmV_iEAqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`;4sf5qn zSAK9bx*-i|tSM?X%!b)0cUWD}1zpeut4$J;kc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{l@NG)?oO1cd63Ta3q`YR1-l=m8Aqh!HLK2dYgd`*(2}wvo5|WUFB)nV+ zA3E<{_?#S#?Usf#)~qudX2Wch`=Bo9f-dMnnE_qU1zpeus{#^|kc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXB;ol<_?-4>xB9cwj^>%IdP_qZ@jfOEY22p# zUKM1}1zpgEHUriSEek8Cn1wW?Va-ryfRi8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh#i4GH(%*Z6fbS|<%@tjTXS%!b)0s{&on z1zpgE(-krq$Up`%kb#6GBq0e&NJ0{l@O&kFOzZDX_?#S#@6I3%X++DUA&v5$K4j1Z zUC@O(18vPu1~SyCC?Cy6%tIQ|$j^>B$;sFRX-LC*vd)0JWKAM}y!134J3p2EINb^3 zpY{09>u9|C(vU`Mi!`KBo=uQJ7j!`v$_(g&F6e?TSQU_vgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|Z#5Bz)?=rm>?@!uOxXZhA%S*Xgiw zjU0^)m4-AlrFf+ax}XcXP+Fi1x}XcXU{ydu5|Z$GB)sqLoH!c0APs4($zV3jhS@0V zXI;<*UC@Ox1G=CKx}XbI1tcUP2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFB>Y_^eCWPfvZGNIX-H$uShHa^zRPUv)7m=>=6ji=ucj1k(@m1b z@txgln2jioG^D}FIs@(+HHrLD8q%8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wx8EaAiSe=&*td7F*PJbKst6FC~MuQa3) z`!5Y?l=}i1bU_z%q0E3T=z=cjf>i+tNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&_$CtWy04b(Xf#$D(pbCWm<_XGHp*&57j!`vbm4Sm zP6jfNfed6IAqh!HLK2ej!%O&_dV9!@#&<=OhBV@xTN={1NqHqh23^nvU8pnA)^%hc zL!FB9(QL##q#+F}C^FcEAR!4!NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqZU7m9Y2fXV25C z%EarFKaUgZs5IhyNJAP$GcxFcF6cs;0bS4qUC;%q0uqvtgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0f}Pr|$DT>uZOKXK$}?nISA8q$bHN<$jADZlp_8FWDxbfL|FHABn7 z3MytH4QW_2)EVGpO(K7khBV5viTm!JjH9tB(vZfQ8)n07m<{)oG6TAx3%Z~SRs|#^ zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}$_f zBz)+;TC$^YuB0K2wU(KUEziaw^{%g@@%8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(39nhg$Ik1i9+IPRHl!hqwKap;FdJs0tS5Cr7j!`vPM=$mfed6I0~tt2 zLK2dYgd`*(2}wvo5|WUFBqSjT-;RWj)2nJnQS#^QksX!Bd^*fV%tIQ|$g2@faxykS z8qz55VnYU9&;?znGhoG7lgJ;XAr0&2G6TAx3%Z~S_G3v%LK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&`0XTYT70|n{akBKOjd1fq!F`_hBW+SW1Rs`)+F*rX-LC! zlQILkpbNU73!bNwkc1>8Aqh!HLK2dYgd`+kk??NXH=O@3&W5AXh|?hrX>g;=fG+5Q zF6e?a5(!C2LK2dYgd`*(2}wvo5|WUF>k{s!pI6=;{oOZG>{LaiA&q!Hk%lyG zQ~o_5GU$RX=t7$TYlfDE6;#YZ8t0eBzWWTw(Wsd;q!Ak|4QZ5TKxEJbUC@Ox1G=CK zx}XbI1tcUP2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&`0gZZKba@xcbBq9b|-Tub0=dg z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNqC(S9=fkg>S&Zf8q!#E(rlOwvr+D$x}XcXaE)EqrN_>C($V+lgJ;XAq{JW zG6TAx3%Z~S{uYmfBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXB;htBeCoc&k)zQ%X-H#DezRdV%tl!i=z=cjf-an{kjX#> zGLV4`BqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2ejLrQo*y{dM+0{Qbcla5Mb zJ{@Kw<{=GfWW71b$=C#GNTa-q4H8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wx8^Ox|h`&ylj#w#cdX{_DZ&4$@98)em} z3%Z~Sx^Vgohzw*P0~yFbLK2dYgd`*(2}wvo5|WUF+mY}o_2${p_+Ay#kVb62G^A19 z;fM^npbNTCXP~W+$v}oW73HJZh8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0fRo!8lZntn?mwj_TZ-EdSIaXzFWjdD*RgD&WTE|eM21zpeuU9c)3Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh$NHYD6nzsYb|{p|)v zbI)qd(vU{H_ew(=w<*6@1sQZf7j&V`fHgzQ!U`&8Aq{C*Gt?R2WKAM}l!i1sn8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqn4)g!kQ7A9XZd1!+iQ z?e1(g%!b)0D>q%x1zpgE(`PYcAOji5Kn4<$kc1>8Aqh!HLK2dYgj<$yKfO;?bS{71 z{=AM#V?G^bBjzCuY2-B$Cpj6LAPs4h_wyoyF6e?T)ETg1tV!gL(vXJrbD05M&;?!4 z1^cliBq0e&NJ0{l@XaOc{nqL}IT~9g4QZ^IV>Zl&*(moTUC;$x(1kJsx}XcXpbJ(7 zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TSR>IzU z2k(=kv7yqC#+p}V!)%z1axc>bUC@Ph+lBk|IK4aL{C{og9F6Z>DGh08N_mH0UC;$x z(1kh!)(ka?{81Xx$m@1@NnMCdkcKp@8R`t2!(H;}Xzyd*P)Fl6l7=*Dck@SSNTaNB z$)F3mpbKRNbU_z%K^LqFNJv5wl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NW$mtD;_%8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(3E#Jb59xL1 zm4_XDHRW@gZc_GH8q$dUl!i3OP-lRXHHrLD8q%<4C^Mi7x}XccTNj>EZ#Tfvc!!mS zG@`K5kVbi4Mh0Eb1zo5!(4L8qfedvj%15&i^N@x#@^f}haxykS8q%8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc8JL;dA$WOdO4` z&LItHL?xvmjq;jKWY7g&(1kh!?b!qw$WW)Ed^8&|4{1mvKkw!wCu0+&Ar0%vIs@*K zHHrLD8q%<4C^Mi7x}XcX@Orv0&i_Y-n1?i^!O1cMx}XcXpbORvBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqn4wgm*{3?L2=~5J%(GNkbZI9W)ze!)%n5sxIh)F6cs;0bS4qUC;%q0uqvt zgd`*(2}wvo5|WUFBqSjTNl3zTlJJo7|KfL)Kd;xwQE8Zs+mzo~Nf&fM7j&V`z%}0` z@4IUTN8@ZrLmEwu`Rdwim<_X0R@b_q3%Z~SWd?LX7j!`vtO`g-LK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(3C~%=hwkeVI~w~d4QZ@tW;V=* z*(i59UC;$x(1kJsx}XcXpbJ(7BqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|Z%!NNCbb+WVO_Im_AF#@famhlC^~Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNl3ysm+-Osif4|-mPtbzYvz~@vtc&M{YV#dK^JtP%z!TFf-dNSRRIY}NJ0{l zkc5{c;d8p{>=HZrDz$l*hBRWgr6G-*lvjOZ&;?!4g*pS)3^j@TQ5w>4mn<`&3%Z~S zx?tDk938Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~ExlJI&Y+;?B`*wNSpX-H#D z2D4!{%tl#1>w+%mf-aO9&;?!41zoTzAR!4!NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>WX9*A8*Clo|_E#FxSkugGm<_X0?sU4K3%Z~SWd?L% zsSEe%F#Rtc$)DG(9F>OIxJ@@{mvliFbU_!|47f|SEUXz~7SfQ0HA9^NPSzyyM`=jI zvxzbTx}XcXpbK^&Nk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H!gG-DzWZ83j>c;w4QZ_1yUm8#FdJoE zrwh8E3%YRn9ES{KAOji5Ktd9dkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTFG0flbV!%*edcN6 zDp$G6)eq&>L-$q79F0CpLmF#$E3;uX%tl$s=z=cjf-an{>d8O`GLV4`BqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|Z%SO8A`iou6-aH2(gPG^7#l zuhNjlP0H&HGU$RX=t7-=w)!Fi8R}G&k7gt0Aq{C*L6N~O1PMt8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zw7jkWur*)SVsqpXp1K^JsE7fzoqkbw+jAOjglNJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~ExlJM8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1?>GzlNlVfwAT*xmej)yz?8n2pBX;?GV8Q^41B7c;IG(4LqGoTB)pbNTS2a<#&Bq0e&NJ0{lkc1>8Aqh!% z4HDjUe*(wRD4{f@v36fD8)n07lr@7c=z=cj!s+^%3}he!8OT6F5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNq9XH?z*pd>}c$QG^DX6gV`_} zW}~d1bwL+&K^Mvl=z=cjf-YDUkdTBVBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXJYNZ))9cQwaXR{H%I7xSqIs=@nN#u{xkcKrwnE_qU z1zpeu&ooI$LK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H z!tF_T*ZmC?N2C1GkjC15&}^6uvr*Pax}XcXpbMwZ7sx;cGLV4`BqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}VgBjK+5ipP$|E=WTfYciM( zvtc&M`dJrrK^JtP%z!TFf-dNSRRIY}NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5?-c+kLe-3UVSwZ zNAq0Qc1uGV(K%^I<2K!-T_S@n=z=b^8L(z(Sy(~EETka~Ylb=loUBRYkJ6BaXA@-x zbU_z%K^N>!laPcYBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Ex zlJHc*yYBBiIvU-OhBVd`H5+EbY?M2!F6e?T=z`TI2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exo`ZzD?kf*F8n2Nwq_KAIHXCNc zY?O7KF6e?T=)&o995RrB3}he!2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}U#Ea6jnot{>IC*9H9?|OZuA&q#? zmxeTM(@okM-|^ES9^#5|-S4NjIB&;?!41zqsGn}j4JAqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~ExlJL7p_}qPcBuC?1NkbZIEi)Tt!)%nbs4nP&F6cs;0bS4qUC;%q0uqvtgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wx8^Of)}z3#j&v7@i1 zd~VZC%2!Yt(ukHxLmFhLGr-B3ME)oZX;?Fq8PEk?&;?!aOp}BpBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNl3zTm+&z?bbgZD(fBig(vU{HuS-K3 zpbNU73v~wCs*en0s8dlsnvIx;G^CMtia5#1*aT@v!+NsLfV*T(B7c;IG^`oQ4CsO` z=z=czTRaky@XaNB?EY=Iqp@Yukj9!hX2WcljdDNI1zpeuT_`i43%Z~Sx?oj6LK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}yXl5VNk~Exl8}TXBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXd@~83(|x*Ief3~R^L*8oNkbaZ8)-=6Hr=FM zBEuHCu8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh#i@4n)(qtQueNMr4;VK&T$ z*(fUtUC;$x(1p|0H5tf21~QO=gd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2ejyGaQ$0r%tIQ|aCa>;pbNU73%X#XNkS5mkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~ExlJH$ic<8=rsiU!j(vZfQNM^%qn2mC`(gj`61zjjJ zpbNU73%X!cKtd9dkc1>8Aqlr9;ePr(;9YuH*->{i$}bIRXiB*c>Vhulf-an{3CTc) zH<977yB2jcnj;NqtO;y3%!b)0s}Wt$1zpgE)0H_H$Up`%kb#6GBq0e&NJ0{lkc1>8 zAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l@cm2p)P3b)N8?ONLmF!hH5+Eb zY?O7ZF6e?T=t7wRUC;$x&;_dk5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Ex{;m=}cV8{p(Wr_vq_JkK*)SVsquhUWK^JsE7f#orWFP|> z$Up`Xl8}TXe47$Jr9)>o&(T+@nIjEpM1Q3rjhmG3M`X|iUC@O(1J(>RiTqI-(r}k7 zGoTB)pbNTS*M)>6Bq0e&NJ0{lkc1>8Aqh!HLK2ej{Y!Y?{Ye-{<4j6J8fy(T8)n07 zly$5w=z=cjLYV8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqZUQ zgb&?UKXWurjx?m9M`cB!3%Z~Sx^TL>CIcDBKn609kc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2ejT}$}beKlQ2V+W-njWv8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~ExuD{x9 zeziA8qm$B*#@b!OY?uwRQC1YXpbNU73#Y4VGLV4`WFP|xNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXB;l4Md`j_8lRuBw*HLN2`H+S*$|{Hq zx}XcXP-Z|EbU_z%!K#3SBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H!t<5zIX!fK zF38dNQ&Q59Mzl;C(zr?4b~5OKF6cs?fwtx+0~zX6l#ga3<{=GfSV57&E(8flNJ0{l zkc1>8Aqh!H!YxVIdqt7w8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh$NVI}On3-fbw zG&WQk(pdA#Y?uwRQSN2BpbNU73uOj$K^JsE7pw|MNJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8AqlrC;d6@DHh&(c-O+EC#xC8b-D;AK#<`M) zG}g>98)n07+@_nfpYA8_DQz_(4Kk2{3~dJL%A5>jXj4%>GaE4xX-LC*k_>jJNJv5w zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!H!f!9(zWa(Xj>aUVA&s>=tl2OdW}~dWbU_z%K^IP+iI9N|WFP|> zNJv5wl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0gkzl4YG zD-SywXHpu{SZk=+FdJs0tYdXS7j!`v$_(g&F6e?TSQU_vgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2ej5+vNG*Xd#Pw<;XX*RX0P4QWKz-(MP! z-G(|E8!8QH#Fk1!8vB&*-DJ=OUC@Ox1G=CKx}XbI1tcUP2}wvo5|WUFBqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFB)k*}pSrJ0>}b?X8q!#^-E5c*vr+E* zx}XcXpbMvKU^0+_3}he!2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFB)nz`pS!OB>}Z?~X-H#j&0sdnhS@0VNnOwdUC@Qo=T>AO0~yFb1`?8x zgd`*(2}wvo5|WUFBwUv8A>DQUp3c!%sZEYFq!C*r4Qbq@yuKoXF6e?T)ETg5s7d6H z(vXI`WSIe7&;?!41-mXJBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0gUS;AfSm1!M~{gs9^)-*F4X2WchJDo1*f-dMnnE_qU1zpeus{#^|kc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H!poI#-+k3$M`OFCA&oWb z%!b)88|6Nz3%Z~Sx=?077j!`vbit~Cgd`*(2}wvo5|WUFBqSjTNk~Exl8}TW2@h$P z)|=vJo}k(zX-FfAA`NNWrklx6GU$RX=t7$TYlfDE6;#YZ8q%<4s58LHnneC64QY5b zQD$J1e$A(vZg5eZg#)4YN_!47#8Tx}XcE>t`~Mfed6I0|`k;LK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`;4Wl4D7ebr(|<2*}4 z8f)z~8)n07lr^v}=z=cjLYV8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NWycL@S*#<#E!=PN<$iJnwbr=VK&O0P8W1R7j&V_ zz?Qr4lI}p+!>+r&a#U7zYVt>ENTaMM z$e;_lpbKRNbU_z%K^LqFNJv5wl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NW#8^`|c|MI~o<0hBVghDQ3fLn2oaD&;?!41zk8@dy|0-WFP|> zNJv5wl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0gUO~OO> zb%`B~6DtjAto7Gym<_X0R=K*M3%Z~SWd?LX7j!`vtO`g-LK2dYgd{vC3GdS`J+1Bo zJDRUmomgo|BX(CB(zs1GX`jfT3%Z~SZ3e6vS{7DNF$-x(!8Aqh!HLK2dY zgd`*(2}wvo5|WUFQNri$@BTX~tF^m^*)SVsqpT=&K^JsE7fx5#WFP|>$Up`Xl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0|6sf7FVy7TJ6 zj=q}mxlK1I=PV6rL~*1c4Kmaj;ABlAf0TwatQpD-=z=cjf-ZQbNkS5mkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh#?Bz#J{&hPO# z8h;~08q$b&P-#e`{2m_}bU_z%q0WHyRZSv)l!i3&^KN%ZU5HJPhBT}h>I}F`)+F*r zX-LDGq0E3T=z=cjg1@ODAqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX+;@Ms z#nI@bG^DY1*DxDq!)%llg)ZoVF6hGP>Y5B>AOji5Ktd9dkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh$NE+jm3Ut8GGICavH###r>hS@M1Wu>YM zx}XcXP-Z|EbU_z%!K#3SBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8AqlTf!iTg^538?a;%M$fl|dTP zh(=078n@}@MNo=za^41ajhKftq>+u}Bqw7Nq#+F}s5%4gk~N9^Q5w>)W+*eD3%Z~S zx?r!Kgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXB;os)@Ui8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo z5|WUFMZ%}8Aqh!HLK2dY zgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX+?Iro>28Aqh!HLK2dYgd`;4bxOGF{#K)-Q3h#9W6epk zVK&T0xrge4F6e?Tlo`+kUC;$xuqq%S2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFB>XlK?z^uK>}c$fG^DYnirFw5W~1D3bU_z%K^Mvl=z=cj zf-YDUkdTBVBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!H!Z(%hkRCg~3-9Qw)LJGDX+&|PA&r}q1tx8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUF zBqSjTNk~Exl8}TXJU0oSyRS>^Xq;GSNMo(PX2Wcljk3zs1zpeuT_`i43%Z~Sx?oj6 zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*( z2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}$@NCA?3s zJFh(K=&LE8+jNuiHIl~lrtvh*!QE<89L8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`;4 zHAuMYzS^6kQ9@}*W9`0RHq3_EC~F2?&;?!4h12yj8OT5eGLV6UBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~ExlJL7pxbMDtu%mIVq#=#9mYEH+ zVK&NIR2OtX7j&V_fG+5QF6e?)0SQS+LK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&_+2DCq{q%rbvpVgwYidpG-Ai3A&r}qS6^h%1zpgEIs?`WHHrLD8q#o=EHj`B zx}XcXVAq9&BqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`;4n@jlA{dsRk zW6Pu=jWu)3hS@M1<$k0Kx}XcXP-Z|EbU_z%!K#3SBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!H zLK2dYgd`*(2}wvo5|WUFBqSjTNk~ExlJLVy_}qQvVMk*_r6G+qugr$oFdOAwrVF~D z3%XEdKo@jD7j(g@fP^F@Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}U#DdBT^op!6Q%j9UD z>)LK8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!H!fi{q@4lLWqw(rXLmF$V0<&Q@%tl!;>Vhulf-amsdm;lF$Up`%kdTBV zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0{l zkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e&NJ0|6e+duWR~~jW z&ZIP?vDQ$tVK&T0S;y*vF6e?Tlo`+kUC;$xuqq%S2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|Z%RB|N0Z&TpR zZc@I7l0g@AK^N)_STocl@<(Y%!(Fn>fG+5QF6e??7ZQ??gd`*(2}wvo5|WUFBqSjT zNk~Exl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TX zBq0e&xNQlay02m7XuSH;kjC1oz-*Wevr$%zx}XcXpbMwZp2$E3GLV4`BqSjTNk~Ex zl8}TXBq0e&NJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}TXBq0e& zNJ0{lkc1>8Aqh!HLK2dYgd`*(2}wvo5|WUFBqSjTNk~Exl8}UJ58AqhXcgwLsW6_$?PrQ39qa(|bO?z%_!-J^%@(fjVvhwjnG?$M|2(dX{b zyVS1XQXY4ypVwXLCw4a_-OKwf^;5e`{oL+SKe@Zq&+abu)4Q9dr1$;r2Kns<`RxYz z?FRYn2Kns<`RxYz?FRYn2Kns<`Rxb!?Faeo2l?#>`Rxb!?Faeo2l?#>`Rxb!Wv6=c zcNpY%802>ttPucjTAZRIiA zV;lXARnEg>v?T?Lr%F`KbI?A5Xb~4R>`V2ooHOQEZcBNTU8mmFcgFncUsoPwH?TJ!&X~`~HRX}#BL9Th`g}N} zO-J6R+g2W<{jvHAoW1$*7;QrGd~7L?(f(L{1=iktc#QdcY$=b?4qAN$-rjt8jQMe3)%O_ltG}f@M*Cy+ zb?tle;W6g(aXER6_Q&eG7WA&Z$CzLJE#)!VAFJmo4Qn z+Lx;D1=gDnk1?N*E#)!V{i^Q;*P9QIF`tji$fN%g1dg_A`fBjg7MGY+e{Je$y!w}z z#%OKX|LGw|+x0)sB>QVrN89y#_1o80Ut7VPXIA|+rlaxteyBA1>pVx}H9F5U`hWZD zXuN`#m`49^Zyk--_Y%|S|NX3^@%mn38vVatbu?bzOH8A_OWfMp-0}Y2(>f+FNnF zw-;02RdBsOA3DGO?n!;uyY=ti*Y~ggx#!d0U8(PTw|@P7egFEuX+HhEllty<>(|HE z_pi@~&ZoccQs2LB{rdX){`EcgeEPdK_5JDAufMPFU;lH@r@yOH-+ylX`uqC+^*{G~ z`nx{$9q87tzpw9K|8vi$zbjPVVQ&5U`}+R%|FHSg_lR4&evZfev%7`Yv%d7>aers& z&*ymS?}x}I?$0d!_Z{zFpL5SA?!PQuU&s5`_tNu;`#Ve5-|_zSKlgm%{?5|%b-aIl zFFl{Qzq54x9q(WNOV20n?<`$^$NSg+(({S?J4@H!@&5Hc_k801&C>OCynlT!JD>Wl zYGwcI^!hvA-yeJPeER!S^LGMUx<0e9U{>(l(-oHNQoloAk>V5x?Z#|#>{@46ntxlgmJAUc;_4mK# z@AI{E{e6Ak&vVbGzrQnoAFrkB@9X>5|3l}~-`|?QQ`ge<_4WPhd+z!4_rK=v_qBBW zeSQD>pL;(2{h#?eel1;pU*Es}-#(xG?pg8mcJk-(9krH^x99iE$J_JErQ`8EMwXAa z_3QHSwtiVY-tKS9$D5DK$6J4vkGFi6kGK7;<>USQ?!*4Y($_zP=f}&(`}sYDzkgo- z`hI>7;qR}OzrLT}L)af*{`!7?4`Kgp`Rn`h_c+M!F}%mg(&Il4@_P(_zq|bP{rP(g ze}A<6_5JyK4ExW^U*Dg<$HDwP4f1;$} zeD`w3{OWHhkMYXH8S|@uE_sYsjLw)}x$DYf{CvR~^ZB^0Jo?WT$ImC7(WWPVc1d~U z@3sE@!t(BlGvd|FuUCFuiH-Kw;w!kXO_0ZEGnDh%QXZonwD=17YxChT=JRnmd5reQ z;_KtDU44%+zxwYdkI~LmeC7PLE9WuhSMGB180}oe*VSLU`W|C`^|zGAXm2aN?*7_* zc#QdcY$=b?4qAL&{Hj&{Fx!=Ipb#_@b?DbvyZ*lzgq^UgS)kITt)wEMLi{%(Xbj<5cfG9B%H?S{V@ z1g+BH~5{myocg3+Vy{5dBoS(U*79;M!PC`uWws< zjP|AC>-(?GhsS6WlILSfd5m_y;`=A8&4TfBJ(e77# zcZIe2@EG&?*is&&-LLrW3~Te@G3N7eIeCnBzv6o{tX+MNF~9m-%44+q72msIZ9Y84 zd_LYr9;02S_?`=E*TrMZugjM5812)=_k38J505dQkL~0U-w|T@>N}%d`@EyLtvp7% zU-2Cw*5<=wvVR%;#fEdBokX z<*Vqf{q5v2f7kA%tM80G9B$pJq-8yoN+uKmy_ve_v>M}qv(v|tG}g8N4sAS!yQFu9M8w)WIEdY zdKm5~I^+22ZzUR$MbPHnU0?QJ`Q&joN;{h-%qBa=cSLs=lae# zzH*n7X?vc2n67jDbL7wSGf!uvP8O1YJ(1qusBk;f|s+j<5cfG9B%HJq>phopC%Lmy_ve_v>l6qv(v|tG}g8N4sB7 z!yQFu9M8x5$#k?Y^)%e;bH?$NyPQl%`%+KCy*_6gU;WF>^m$>&=xMfJ=!|R2BkmV2 zUwvn^_U9d=Ys%w!wxhT-AI@mgk#`iYEswbSwLBlrXcLm>V@r9&-LK`V?~M7?-%=iN zZ)^GLJ7a$J&n1tzFSUH-oH4(0*Of=yms*|=XUym0y7Gv-U(561jQM%LJp*1lqdn7FJEN_&*Uo6Gt+g}S9eM4HX7bt@t#iv~+=W?R zJ7bjT-7wR;@Kaf9|CLdu`MnwHPY$m=#wgSL)7GQM7-gFGNBfVFr)+e_DAV0A)7>!B zUHECJ<-~TwOn2euF4i7nl<6+~{q5Rgj56I1Gu?+>>*fE-ewgWgnCX6)>3*2$ewgWg zIH&tzrtzKRm-C44oxOI(Xig8qOb^3M55r6k!%PpuO!NC?_gk5NA7OOHXinq12Q6nB z-(hC$jL|(RzU#)?V~jkF?*Op$7=6P=bJ5GOe}CEa&YWw=~7`M_H^ZD3P9{sy*Zi6%CSO1#w zh_9=@d`EUhn~uB(_rCJzuMYF~;f!`=t}l<#Iyt`1{93a;#(aXdl*i~MfUuS-8K0L;JJ}xJZ(cV^ko%yw^?=j|Ae@l6c z_6y_d%&*Od$C%H@<>WEi{fe(5zjpOK#{BBPpFBo8SMfFC*RGt$m|wZ=yI=8rCe|j%W3(B{6LdLwjCQ}``%J7|eUCA}`di9lwEGp`XJTzW zJjQ%J-bNmyeW~~k5Np@PW6ZD1mhu?wOT~A9Sep-zF`thu@kNG=s zF6|gOqfJNNQM|T1M*D?#!yQFu98b{YWIEa(o4*V1vL7C!UH|OImhu?wkImnMd3ioO z#(X}ul*ed)>~6TD=!`ZUW&LqEnU40y@_Q+^_v~HP!5QuP=ex)I$z!y0mES#Xbmg2e zzjBw8$7ts&zfSY$>N{h8^|zGAXn!of=F(_BoH3t|%gJN3KbC(}YjpLUF~9oT$s_M5 z_piP)+O^Ls`fJN$wELA;xuXekMw_8LL6?)qX!k4sX+~Gy8S|^Zr94KvU%TPYC_1A} zN4dYejZ8ZG%a$@7?Mv;3J6Fy)o{!7PbhNj%8}1i6jC^}<)^{*|D(eBrNxIgBM z;|Y2jnU40Q_QSnCXB=ObEoC~|m)Z~a`kZk*AD5HqX!mPB+);GK@zvi_rlZ}j{cuOo z8OQT+Ihl@jzxKl&MQ0pe{VioW+Wp!OcNCp*JRff})BJmKuTNeXJ^$To{ja>+GwSZw z`hUe4?fU2IvZXxg?$`R&cgFncpGO{tZ}$4uuADR4b<029v8_DnuG9L}cSgJZ`RZR+ z9(DI?eLkEqpO5RxqwapK&xbSS^RcBo>h9P2)py4H>R(qLb@yw1KAbV1kL${#?vJg{ zhco8$v86ml`%;JD&XqITbd=|&?I|IJS^uFr?Zn9s-MCc|v^8kyXv=TuX#aa|J332W+n&!a9c|AUmyWh)3`<9IJId>Rtfke@tG%x7+Sm6p zYp*l9_VxYT+AAWieSJT>_L^yHU*FHKy^7HC*SFV*Sv%gJxb~_VYhT}=y7t@sYhT}= zy!QLQYhT}=zV;h}%U|DqXKL+ufBxEUs;qr|fBxFfvafx8fBxD}yRLnGfBxdne=YTM zAD;0q9nb%+*WdV)3d>*LpT9#`H7tL9fBp{N{IvLTK8J69o_OteKfkzxxcvR~`x~Ei zFMWM{j=6lipI=;cEq{GKzxzRc_k;ZI!|wU=f4|?~`@#G@4Ce14Jd0oY?>~g+c}vGH zzaM>n#{D|?ukX+AA*{ofuCL>lo?rj|IQHMy_wU~yI-mafaD4yv_5JI6?)i+?Uyk>$ z@4L>YzkVC9k9~dr`hDnp`p;kD-v}?SuY7&~`kr?_e~tGie0{I~ zA3nd){*mMT>v!q-^!Inh`-i^1KOg6wPk;X>{yp~6`p)r7&#%9~Gv5FA_5J>j^6Brt zjQ@Vc*Z1>3_k8;MGvmKM^Y#7f|Dp5g@88^q-%(kQIRCkl{7mhm z^TYYimE>n?-#R~>?_5bfruNbK;r!=H@-wxM&JX81SCXHpecSwQBp*{d&c}YA56)+9 zB;Qi|==^X#b4&Tw;cYERwMTwihr1He}9^hPt1R+@27UG|LA;T{!{6%cC7!_ z`NVvu(pT+R-_iNR{HM}i?O6ZO`NaIE(qHXZ|E=?h`A(&;+OfXB%jcf*t#^IY9`mgk z`NaIE`hIFh$LBrei(BM}^PM}%$J9PLKb()<)BLi^zv_>V|E=@E`OiJgKdbatf2{xC z=7aN{dzxQX>8t)&->vh(`OiJgFRS!df2{x3`QZHLp5~ub`l~W}r`HlN4tv*;VBBJbZi8xNe1*|$}NJ79l2aDHSwRFVBL6AzpY znfj{8>hFsOPLIqVs>uG>7Z031nLkvK{qY$dI2AHoRFQSr7Z02onLkvK{V@{{oLQOr zs>tf^iwDlM%pa=A{@4=_(;p{_s&IGw`<1WF#e?OA_I;T@RN)RWUNiAv`PhLbimGsT zJkB38F=Ywbfo6`XSo`BAn6l*RK(jtotaX`*DNC*nH0x8v+8^UEW%<~FCW@+9t3MM{ zmX951qNs|sKW1Xe60`%&996OQ$2d$`K6apqqAJ$v&%^Xc6Gc^I_4meuDHRa#p@h|hbCnQ~kKSg&H{w&s2`2Bia zaS3<9U4>t>y9z(AcNKnQcNMN}SHYNGDAP-r`_=sw#`F@N8tX9@%5({Lj@=lH=@QPC z-58AN5@yPFV=$jCl<5*umhP`GpI#}`D`k2OcWm|NxKgIqaMtd|U_QN4pI#}`D`k46 zKD|+OkGQvDSHX_`xW8RD20QlS9$MWP z?AVX{@N{Fa^J&~mq#DECS@f0Tx(a-avN14ItH9SNtH4aH0w4QUftgwbzV2HEV;b+I zD`Iy4fxnAY;O{clJq&h`tuUhsze}Bs2R=L4w^c<}e_uTCwZZ(MitLY>c;M^4sjrHx z{#JOfdzcHo%Ta|ZYrpT0#Dm?RUcSD~b4B6$E?5<7^=Bf6pR~;Ds&M`H#{)lS8xK`v zf6T;#WhfV#vZ%t{@wj)Gi7ER@ zmG95+V9C`&vp!Y0Zg$-ti3dxr{$y5##&G>j{h4^ML~)^sqAJ`SkF&!}Oj$nmCo`%v zhC9U0ALH;~dExT)ZE)hO3fKN|c9@A6%g6p?uB66rhuGO+CLSyw`;(cn8YBB-93CwF zTIlRjRk-$#tH&pp{>j{Pmi1|jtlUUEST6M^Zysn2*WY$*n~4WY6#wMC6OEDmF%u7# zkNwG8M;ashV;mkV{rZzP$}~n+eu+c6J@LpZFI4_eg}cMf z4s-E{=~u13DqMe4e_uRe`c?Zw71!iF%OTt z?r5dHDqMR@6zAf>^0B%*2D`W41n)zqwTVLlxN{Kf#0LQhBB4S{IFx zb(x6=ORnzeedO978YBB-CLS#P%B#HB{?HiNALH;~`Pec;NKQ)K^7Te_uRs`epu5MfS(Oc;NKQ{Gp2MkC}Mj^vl#& zMOJ@bJaGDD{!m5s$G&*r^vnFAitLZi@W8p0>7t6P%bs`~zVt`4e~w>?k}9G<=HkKf z!UIhdRpIWiEO;&+EFU}2L{SxMf6T;`C1?klIjUmqk8zl?eC$9IMOCcTpNT2U$84un zcK4|YcZl6xjKhQFW46ZwQ(qNX{m<}V$(60z#gtP;R&FL9EV;6Eo0vaTk^M0a50;PF z8+1&4Rb=(&;bDm~R$mpay(LC-@nDIf-NQ0}sKOm${+NjeOTX;q+79HuP&I?_b(=PS-{Yq;AvDt=N`98)e;^N7inD&`^0u{!oQG z#QZT6kC=Yd>Z>BFzZD)am#URhMOJPm9xOpS(Tq(M?vBTGe$?k$;SRB7aDa}!=)z=tV z{dsttX`-kK*WR8iKE;FOQfHc6sba0%OiWpFb^h|I&mOGK>#A7$VDQSiimGt!AJ_evn6mWiOcO;_to<<)QQ-MyO#_dI4R3%+KGTt^4~MlwCVJVlY2{8>kx}^Yga>y8f8ok)C-lKc6pH|9zh? z*0p1Pr`I!N*B>9X{yToxA0N5?%U0JPAHDu-LEYce(XJgIzn)2T{jvZ2skQ5m{pWYB zU4QI9cI9K&J$BW*yi(u#^Icx4U)PTLU0%6B*B|q<-%hcEtO6f{F=MYkg;ii5Sp_~4 zXRE-v+P77O-;?i;2fnTt4^?D;?289GuY2CtpOZC4cF;IH@Li*w9aNFE-3kwUKWfUU zA}co&4|cE3o=40d8YBB-CLa7rOBGrDJ@H^^gWc)j^ja0}9{bl=JXnUp(kA=18p9nh z8xNMCv9!^6XpHQSnRu{7@j^34Rk%AISC4U+vV4sFmSATGjp6!#jt9%7Y|aLncVM4X z6bziwMO+vq`~ej@i|?suKzYk;(J52x_|~C&dz*)qdjIf)%a@n z<9kFtF}tZgzuK|Bzs)CRFO@!O$NG%UC#F7?{%XhikIpBiLY4k%$NG=XC#FV~{%Xhi zkIg5q5%aFU+GD;pBcGVBRo_qT==jfTD2>Q3=0nxzS3A~!bUraZs`OVo*8jVFaK2^l zWaGcD_Obcke8=9dz~4{pWAnlJQCwIv2l-Dq= z^jCkZ|JM27{OFk0$E@^Mf2{wu`Q$Z*-}O~H&fmu8gY&h##&qQm^+(75_xa&`=akko zsq|5Qtk2)(gY%obMth~N`eS{!&IjjbCz8LZeRO^}Kg)Y8RL8&ie;Cv|WU{dL?{#gI5^TGL0-k+w@U;VNE-{X__kb38@ zcASrm&j;sQdGDvnAL@^e&+YTW`B2{3tI}WnvHpLX56*}3PGyz8>W}r^Iv<=L<(+;^P9Yfb)}E`V|}*GC-3?7uCLm0{x&`zoS)@Azbb#IKRW)m&kyHAc~7rO zfAz=uZ=Da$kMf>fmHz6F_1`)loFC;~yDI(FAM3w$J~%(hdw*5>t3THNZ}Y+V(1px@ zQ~Pi8!}-mHydSFe(fQ&0=JJo)@%eRhJ~$t`koQB?z9oLwxAm2?KJV>I+Idp#alZ@u z_xyZfepczPc0d2m$S3AQ)%R07)_-(9F(0b*S3A~!bUra3s`OVo*8jVFVm?#xS3BlE zI-i*DRQjtO>pwc5m>*U8s~zhpwc5m>*U8s~zh977+f5r#rH`la3XvJUsG5@Xe!THTKtbv`&hx~BPWmHz6F_1`w18_D0)j`O$e^TGMpjpS=;|J(d@%?W6O<`OuBzZ)zW%AI^tvB!5%;==^X#bR+qj+DGSy^PwBb z-_$-jKb#NUNdD&SwiDm^?fu95E8pqbpU<~l`}6s!Yk%H9q zOb@SIs;^*750t4LG3;|NrU%OOK$#vW(*tFCq)d;L>5=;MNSPif(N~CVW3Xf2cWdg$U`&0-lx_^)Go!Cy z$G-1t(2v26eP0{BAA_AweSPJA40b;CHDJ3jd=<>Tg89@}8tlhl)P1$Oehfz4SG?-S zVAOq8o_-8Q-B*6m82^5q<$NWLo(DVjHAY-tV=kt?Qb^|yRb=(&;=!&j3%yfP#o8aA zVal%R3wn6hV&g+B4AVy*s6OxgYVLZA0lvG&JIOj+)*(6mPtYk!Qxls$VJZ%uR79YeX7X1 z%*BJ{Qoia)?+=aP4zU>mGx1>Qm#^y5`$J=7e~iO}rC+|LOs~Gi$m-9;gQZ`-=1lJo zjgkE^6AzYt`I%cs?}G8>u>7si$_eq zYJaFA`(q{^G5xC5S4CETUp!*^Rr^B~*&qAj5!0{QAF9ay_zVx02l?tY{ZoO)$jZ&c zgC$qK`c3Z-jgkE^4iA=(`Pw(V`WhpvKNAm@kL9&->g&G7$o`mzM_&1;QePFWy(Nls z@nHGbohE3iSo>oprYs-3r?;N#^M}T8huHaJCLSz7yQlY}Ykz2r?2n(|!IGHmU!Awk9`gKq5BiCmKjo}WlyS|xt zuzc*E-bb$ep)s;Q#^J%zuX}nQxmI6eWc6p^Ve2c$Rjc3CSA{EY|C)^lPQUEis=^(x zB_24JvQMgttlUgIaO!00t0JqvFCIAkGJmKd`(s}`aQbEbP(}8~OgwP_8JmRk%AI=Z~3~vIH&fOgSl&;(_J_vE{`d(VESJi=xYxR9jI7H{ zJXmsNb7k38T@~3M^YE~&7pt!d*WMC=xp=Vj%bswVKUCokF@Ma&gQZ{geVIR0k^M0y zkL7LcbkjbjU#i#}kC=Yd>Z>9j`}^V%)34ees>uHM43C&g)w-x6>#{E%F_)_Sp^EH} znRvwXt5#nXS^a(Si0N1D4^?D;?1{%IC5n|lRN?NhL~$-2G5xC5SB2|u>hFt3OuuS> zs3QAgUp!c%c%qr3D%?Mh>&s6tWy#eky^mZU*&4%@u`~ZnJXmsdO0x%Re`t*Ck8yag zeC(9oN3PY^7+L+9c(8ozl-@_K{h=|kKW5^=60}o#AG!92#>oB{hX>2YPHB!}t-i*{ z>d(XDOcO;_xc2tMHxdt)ew}GPri!)tTVcwQt8Movh?dr6Gc_5)t`we%g4?%b5zCJA2Ts!`Pi9ej;dJuV;rU|{W{Y` zQ59?TKf{zIS7(|As$#9&C`>Oj>r+M6c5ggbwsoO-p(@r68iy%Mzb-UURK;5TnV7Ql z>p~MnRjmCn6H}IcU1*}HinTw+Van343r!SNu~vT;rg0sl_g^B_8g>5}8rQFUHjZll z_B+w4)$dfQR=-YFt$voOTHVD}tEZw>t7l?Wt7j%vt3Q`lt#S4Gx*hY1t9jS`F|)WL zaNQqsi))6~{V}_^c46Hg^NVYBRsG{yO?5kVTwL#^?vGt}4A+~wKX%?RB-nL-?7m}2 z(yIRP&BVGL`|lK<#_ImqfAI~8x(~9U|Kh!V-5>k!5`KZK`(yuI!fzCH zf9$^{q^VW^g<`g`KR@0(TO?pUu1TwmwrB8Km~@+!C;4~^j-`YB@gdBOh5m=)Kzq-gzJRFSo< zdBo=(Rpk6;ejf2jtNymC$misJ@rcjawLesm{jo0|F=eU!p^EH}nRvtmtyW(ZS^a(S zh(}o}vDN-hp)j$m-9;gXLp!Rp9RI zpfR#PX5zu}u{?vbK7VM8?2mDHuzW183f!F?G)7kcGdx&wm1j=Z$F0W5%8kQ=C0B91 z-tM^77+L*!c;vSps$*XjuKjww-uif%ix|tt@_RA0gEWSF$X0wFhX>2Y;+ntR(V#K1 z`ZMuh=~sU1tv)+wjO>q@c(8mduKC-YKQu=6$5wc-Y%9O9S|9rwBWt@A9xRuNtMPWn zt;WdOj>CiHQu$r-`pDK8S^b%Ku=Fdg#@n48G)DHvOgvaVme-P~&mS5i`(qRyc^!~S zTUEHSmMHFx2TQ-=n!okcLltWW&BT=DV|k^Z`V6Bn+#z;``3W8@mx`F<+aJ zPt4D%@27Tj{M$~Q+is8fSEaAov3|eJ2j^FLhqOvR^~d^coe$23Y-K6@{nS1-ADj=_ zdtUhaseNodI3GIxqjs$C*7@N4=lC_d9)CZzkIe_?L&tyAj`ba#56*{<|EL}7KQ^Dd z6WROoo7!={_I*A$pUHcLRr;tuIzG4059c?hw2DThzxreSx6TLWKY4ewN`Ljo`fr^N z&d2ipXqEozkM-X=ADoZn{m&}>)gSBsxB1}wC+}ZY>8t)&->vh(`B>h;tkPfovHn}< zgY%)h4_c+a`eXeWADqwRoyaQw>W}$vn@`>s>s?>9<9us;J~$uC`(jo8P=9p%Z=WB| zfAU^pmHz6F_5a&^aK4lG0;}{@f2{A;`QUsf@AXybul`v7t@FY8PTmi!(qH|t{#)mR z^PjwDSf#)EWBva&ADr*xUBN1S)gSBoT|PK}$-8n@`lvtFXX|`${*!mzs`OWXtpB$8 zuyk+Mnn5uKnrnuKnqcuKk%Wb?uQ~_4y;esy*_n+9SWJ9rL>pez({8zy5x=*ZcEb zJLY#w{(JxYx7Ye--T0W_?e+ZL^~d~fuk~5#{&&LfPWaskzx!)%+V1aT|J@0{`zzn- z#>f7w4K@G)!^_$amt>_e--B&`A;%T|HiXcd^JRbWS21!HP8 zkE?pe)c1YrD;U!QWqP1Y50vSFGCfeH2g>w7nfglD9Wh@ExUXPLeZALy4CYf`GqN9p z`PA2?>c;SudHM==-1_P({TS@H^%WfYF&Ht85%-C-<9Zxo?40Z?JoNt17_PsmKMoIe z9`p4ddi6C%R(~cQ>~71~hv@yGF|t2C!-L%g`^pZzavCEmHx3W>gyZW<^y+Jjto}Sa zeAR?beO0*j|9<5sd*i{LJbhh--a#6}J!B3VhX+epd{v5GeT|XTpNR*{l*|=4KUIah z<8gf%hZxJYd`*k~?4U7Rf4er!#Dk?@zUD>m4~>!i@fjX0x$@O2dgU}mR&E>~ESK`N zEPC}dMpl0&9xVOxwKRHvXpHQSad@!w%U9Cq)z=tV{dsu!IuV`vs&MV?iEnQ_So-BF zP4o`Z815l+&^SC;`sM3%^y+Jjto}?qSo-Dbc=Z0z7}*~`!Gq;ezP?7Ui^j;h%*2D` zQojC1?+=ZU{V@{{mVWvAAH6>`M)t=zJXreWtAF(BYmBV^Ogvcn<*Q%x{?HiNALH;~ z>DPt6Q=|&l{*fuo!_-$6>5hF>WcByPgQZ`-_D1g@jo}`$H${Jf2g{`v`nItuTopU7 z&&7k~QVX3usEV~e#$n3Rue_ql`-&EJG-wRhe>NU0{aWbTwW@G;Jgy!yF=gr3Lf5-c z#o8a^FlFi2Lf0};#ajKDn6mV1p)1*_V(pKan6i9qp_!v9*8ccDQ??4Btx&~QB=jKh>AidUK_s$#AFOiWq&b)|`-D%SoOhbc<~uQV@I#ajKDn6mWi zN)yFBS6tuL47a=S$aM6In10pYMHPO2F!g8R5!0_)eN|-jx56XlQnhlb$jZ&cBc@KZ z`l`t4?}6REAifV#PqB7hbr75=8u_p#Pq9HUlm#XeesCtSM3i~WPj|7 zN6g1+f2bn+Vs7#$n2mtGwG`ecWmc*WaEB zX5zu}v0IuwSo=d`WPi-WgC%Hrx6|4m8YBB-6drk}+DcnhxUzODTteZg$I5vHRV*1 zm79mh;Y;2B{^!5G?(1zW`s%q-6|TKKXYY*%p6OydRN)TU9}ku~9nusKOm${@51}mXDpjju}s!YX@zw!dCNkRUiK{Z9Na_ zDm)SBD*V~BtMI3juEOt6y9&RD=_>pxR#%+EwV|tUuXh!$ZCAmV+Wh&agSs&o({q^Z z(v88Gp2IKi-58ANg)+T_^GE$xF5!skDj3rXWqJv-p{l>)zeHB8%oj*c{MoS=un+KY zh4shB6V^Sx*HF{Kyy86Xx<6(X=XuusF}FBZtnQE5#W^c=f6Oobid*%Mzn<0Y>@0-& z9sl5HL5@Dsvk&HXq-P$?FW$3OeBwPz-H!RO>*9&aSp_@F_;D6z2X>znpQ-F~V7F|if*tpEUS!uHRmA()v54`jqAFZn({^7x z@Kwops3QAgUp&|~+n(sreSQ!Gql?vHNY)MPp=LX5zu_laKUHS{3dNTYq~b z9yq13@1hDKU!r>p&;3U`S4VK5K&`FD$lA`tgC$qzG{3O+hsMbM7==e(y`$1r z6|Sr$ihJY1^0B9c zR)yhFoiohFK^aCg{y1$*Pc^07Nj&{VN@&^Sz4K6X!Y z6szltD%R@H#FXV@_cTYb_J_uBhuHOHCLSywyQevdwLdgQ_Qy}~V9C`z%^s|E(HL2m znRu||>Yio~*8b2K*&pNZVENcR%^s}P*BDv-nRu{#?4D*1*8b2K*&j3UU%pa=A{+NjePQOfjRb=(|#RI2b<_}e5f9#6~ zPQT0_s>uGBhsWVdU0)l!N)%P$+FPQy9Ud&nJJ7686>DwBVak%L1I_wWu~vU3rYs*j z&_q!cYk$ndlqF~fnmMXs?T>MovV6?;g=F`Is&M`7zHlZUEFZHyK$t&Nk^M0f50;=E zXy&L2cgN$oavY{CAG5We9%qNk*Hg&-Z3R0!TRtFM=k(N{30r`OfAAA>PHz0N`X z7>wzOGCfnKXUg4h@2Z-9@63uStt zOfQ5fK8LaM7yA78yoHZ1e7?fR71kdgPx$=g$!hIBPb<52thnbHU4Kl?@9?|+n4I77 zbp0_se$B*g`;+S>a@>&~FPPtv94r35V$H|jo9o&!e}A*4>yP>S%=)^&`4=moig?d! zD?V(87(N%3w?7{2+TwGo`?G__$PSu`2fiP(<3$x&{m<~g_avr^DzYy7;(?!q z%pa=A{+Njeequ27Rgu--7Z03vm_JmJ{jo0|I59APs3QAgCLTP`R7F;QPdx1CM|rB{ z*{X>C*c%U)DDq!CRN?-yJo#sMuw2S#PIpmto<<#Q?tgXLp<9)T*{9gnN}_L$mSy7(#W-{xfhq+Nw4XsR$``{LpGSf{=!{J1iI z?2CuzW1T-#k^QkR9-g3e{!m5s$0vBiw-st#RN<=FozmWTc-GhXLly22^T$j)JpJm_ zS4CETUpzeh>inUK?2nmvc>2|;uZpbxzId=qDZW|LIY?t<2hGHTC1^*Qv8lq{@pw8J zhbha)jx<42#ajK(FlEWrG0Yz9&g&Y(wX>(jad@y?Dz4|ysjo4z`t$HG#hgSX`y4^M}UB{+NjeOVCbX zPG08^jgkE^4iA=o#r4-Z^)*IT|1&&TE_I?=pDJ9p$8*CtOj#}!*F5ZwTaDrR+dcnG zJXrd5qWPFA+#Qdz!#GS?`W06*?amGw!}Yhb!#q6VO0~86s&MV?*xwrumVU*Rj5`Nu z4EK;ZXdE6a{fetpcj{}5to}?qSo#&$DDV8CF|t2?f(J{T;>z%yE*c~2G7}G$OT~Qw zI)7-4?2nmvu=FeL3eovPV`P7f!-J(?XPS?x!nJ=qHO|D8rC)Ksm+tJKG29{cOgIw{ zmXF2VemZ|>jO>q5c*K30YHd~F%G$MIZ#-D~75DM#9HcSaL*}5L;K6b!Te%F+K30XR z@;I_*BF1v5xOZN6+-eMWh#j{x@nHE_+&QuHhsMbM7>5T-zv8Z#o%$Lht3MMDmVRC6 z97R>QJ05ozGcjfP*o9_}s#yDD9HuP&y3l+~6>IfpV#?C53!RgvinTw!&vc>hBda1) z-y08>OD#0HQpMUqGck?%*r8ZEeMy<4D(2!5)2~`vRrt|wtK#pAM@+wJf2bn+VuGBhsQM~ zik14RaP93^z`gN^=~wL!Rk%aUAN%6L62&V`6jkB=d7NR!VaoEcD^1W;u~vU3rYs-3 zrWFqB>x;&4huHPyGdx(fbxphM*2-y&tlT&}SaNkuvj=PSHAYr{93Cv&x~92-wfY(( zt3MMDmXBT2?7`X}8YBB-CLSywyQbNLwLdgQ_QxnZZZuI;g)3{%`+MWT^06CD&{VN@ z&`eBO`gNm;qAJ$@_z9*gm%7ocPZeujW@5^6sT)nMRI&EQI80f#b)$KqD%R@H#FV99 zH<~D_V(pJ{n6mWiMiWIpVwyW@an6ARFb6tg>>ADK{dRO5d>na%217&&$2}%7| z4&f=ft6)rRN1W$g1Kk*msjZj9#$ZfsHXIv+F*T>+F^-h!kup7oXVaS4kup7oJJ@av z#`GAjV%->w>5(4$wt_fjdZJ8El-X;vvpU&&Zlud z;BE|d?8m)HyD`|YANMEh#$d;O+>@&tgB|;EZ=ZUMxOYoe!LCtpABk=Zc0P^k^H*cw zjt-tzX{kP7CT_4qs_5B{7I4`0)zSNHII>+aO z@0;UXliDBZkB-mn^TW>%akfdVzxreSx6TJY`^MQMwf^dl_1`)l{QMthi`4q7Kh}Ti zd~kjf=Zn<(t3TF%>wIuN6z7A~`l~ft0JqvFCI95 zGJmKd`(s}`a6V=JP(}8~XL#V;$aGOf)@5HjaIR$jP(}8~OgwO^W$LRUtG_QEI2AL0 zs3QAgPdrS2l$zTccB+W}n2QI?3)vf%)~+$KKW5^=@-g;)t+_*EWPgmqgXLofnkcHm zwYQZ7KE;D2SL~g3`=lDfwHu2E%cTx9$y0@E|2S@EV#@L{wpxW94I0B8G8+$;kJ(PU z?5R-|*&pNZVEGtZhsKTujgi%#i3iKaY`rXYcGzo$t@7c{c>K$b7w0j0MO(p08R)1eSJPqvpp^EH}eev*o ztn-H|vOi|x;b~x}zACc%`{Lp0SLY8^WPj|7hv#FRKU9(ZF%u7#e#JGoJAY`5?2qsB zi0hiy)K%fk?N{Qx@nFeST=%|nkj8KinS*BH!Sb=V>p|xajgkE^4iA=(#T_j=^)*IT zeoB{hX>2Y;!Z`K`WhpvKNAm@kHvkeI)7-4 z?2n(|!E&j%J6NZS#>l$N#DnEhac{WJ9~vY3V;&xH-@jUYRk-$+InKp{rC(>7kEvqq zkC~XV^egW9*_}T$hC9U0ALH;~>DM{DkKC!RF|ztI@nGp!+|9T1hsMbMn285Vzs}*k z=*}M+Bm3hgc(7b5?x5Z2qA{{AGx1=#)H%G5-1$ReWPi-WgXLrA@IG?q4~>!iF%A!w zex2#twW@IKADPlTOfU59T2*BA=i#PqB7hbpo^w!$MOSG97g$jZ&b#PqB7hbpo^X5takuUdUoWcByO zBc@-qKU9(Zu`eDhLA%n7O%?8+$J5DAFlEWrHO(HZk8F+M%Gh(mOgva}bxpGeYkz2r z?2mDHu=MMiW)IftYmBV^JUr}egXiwpx39Fszvts$ws*QJoXY-qumsIq!yKfF?4WUY zuzc*6<|x+Z4~>!4pNR*{$8KqkV(kx&k^M0a50;PJ(j3KFeT|XTfAX-o-RJUt?3p_C z70*w!t^(xJy52`9sd>M&MKHskCdsML)l+pOpny3 zN6Pd_ed@c)cK-1FJo^g9)b}{-$6!A7ozVI*7*pRbsUL&+)c0=b$6&|4?^n=`;Vby} z70jo;5_mrb^Qo@}+>gPIeP5Zh9>dOJm{{CZwj0BD4ecv1G5agnh5M_({xBY@hsUiiwD0OS4H;6JUrO5 zY20nEd(zSv?vBS=@;H|oiz!Zf?7OJK_1_;4ma_P6d;R%CV`K-7!-FMgES0q5MPp?3 zXX3%~Lf@aTKRalQ?2pgzVA&S?t-y|KjggfbhX+fpe1F3JxYZb0{h4^MY>WR2s0w$- znUmiurVz$NUvBAFIEuD*WiTJEcAG@ZI+8>`?hb748nZHq6B% z=7qKTs&M^H{eAI>=~wL!Rb+pBhDXe$YF$*3b=en>m`m0EP(}8~zIep+tM-Q~vOi|x z5!0_)eN|-j_r)WoU$s9}k^QkR9x*Sh{h^BNkC}L|e9U(r>@y{ek^M0b58rLCQ(qOX zy(NmD;=z(D-xsh~PGh)srrb%J=79gib>9AYdV^SuT8vxCNP{q5{9 z6AzY;`R;?gKQu=6$4op}KIS{+_5RQp*&pNZVELHu$JeW`F|ztI@nHGblHORZ?=3Y( z_Qy;-SU$F-_o8cmXpHQSpWwlAsfEs#Q-!PYcqW{OsqePeUDZ{Q)t`$8OTT%49@nGrKmF8orSgSu1QRzuv{bzc;92?T?v=vGnVj z-f6C$301N7$2d$``sI5I_IFAe!}Yg&htKd}xs>m=*DI$nvU20_V5yVuKG>_TF|ztI z@nGqf?@!qKLt|ur%)`TXAMDgug==q#z+6078tA(Z_WsZq?hy0GOgvbk==&4){?HiN zA2ab_`Izrd*!x3cWPgmqgQZ`-KVh%F#>nb_h6l@~ZZzvth3odXFC2#{%cX8Kxl+Yi z{h64u^y@}v52|AAkC~XVeC$SN52|AAk8zl?^y^0FD5_$u{ya?cuGH19#Hz^Z&&7kK zUw4|1sbcMqnV7Ql>rUq=s$%VrpJ2*Tr#qcJsEV~NGcjek)Sb>ARK?mK|2w8jvATL@ z`Zp_L`c;1pRk;3#uV=~wL!Rb+qci$_eqYJaFA`(q{^G5xC5 zS4CETKRk~A{O9XGe=q6XAF6O~*uOrCOqYG}h`Chl4^?D;%)}$6U$y$G z$m;KlM@+wJf2bn+V_!UQK4w=_Rb+q6!~^GJroJk&`upO6^D*;>DzZQJ#RKPK<_}e5 ze|&}qPOeNBRb*ZE#N+U#KhFA8;qI`kZ!R7zA3M+lO%-c@%*2%CV}~?*uu2tFvG&JI zOj&|59>&rMyS^9OP ziJ~gj>VJkQ%cYJq>r=&AxtW-EQt!t_KFMO9>N_r`;zUniQ6sbcM*pJi%$;>EvU|F)dQldG=6vx~06 zpKrSge~#)Z{7$;7@Vl+9!mqbog`aWjigP&Abrr5lSHYN`LxR?g!I+-I(|k7uV|otv z{M{Ig={a2Y>oG2r=_Q;Ux-l5j3uSr<$yN7PuuuJWwW>e!#WPc{`r=~@djWrD>;ZgC zVeRp;6ldvI-#E@%uiLTWah7J?A5)9-+Uow8T%3VZ_s8_&Z}e6F_?u+i&isb?#f-il zAM=Y@Vcj3|i)ljLAM=Y(6IK6s2UfRZe(cJ4BIlbEIoq7b`TG>oxcc+sWA_xE*Q@?m z9XvKx=DX(wc9#8aJJy|_m((9!$+piApBLlXGSzXT_R;y_do6xnq5k;z-#QA_1QWfobSZ9KkDOC{jvUA=Y#Vj{=2aHWBs?z2j@re9g+I@SAVSk*7@N4h|lX# zf2{x3`QZF0z6DYr|LTwR-#Q_cW^WyW0OYKb(K@ zd9CV?uFu=&hw~#oZ(04Z{#)mR^CLblUHx7E+uJ*Hnco)MV}4Y9KDA?gN9Pmsqe_3Z zWBo_x6Z4}=f3;)%N9Pmsqe_3ZWBo_x6Z54?f3;)%f0s{QVc=aKwa0vHMm{kgs=lAv z(eZgsYekI6FXn62=T|${e{?=EKdSUsJJx@6J~3ab^jAC9e{?=LU&`w`RsK+a?2oPU z!THiTt@~2xul`v7t@FY8QeKm-(qH|t{)`XKcg|_uq>8`#WByy`gY%udo?)fG`eXgK z%_px$`L3_pasDyADti0mll%GseN>Q zI6qoQKBxB4`QdzNA^DuzN9Tw0qlM&iY9E{5mE?13$NAj&d~m*WCHb7%x6TjeM^}=+ zsr_&B!}-^h-EQIzOB**_zGh_Xo9) z&Ijj9SCY@EeRO^}U%HZfPVHm!yODfO?Kq#yeC}`SKlApO?^ONO?)M)v@`?FR_5IY2 z^&g#2%#SMl)sFQaolne7M4tRr;$x)_?1KaK3a;^W!T0)gSA>bv`&>x~KVZmHz6F_1`)l zoFCoO{J2Vg^~d^umk-W&?rHv7rH}e!eYVaA=R5Z_f34DA{jvUA=Y#X5dz!yi>977+ z|84U*eC2aEfl|f4X;#|)c;E!ic&NfXG8+$^FWI+MMOJ@bJaGPG{!m5s$G&*re9HWx zitLZi@W8o|>7t6P%f5KvT*>^QitLY>c;M8^)K^7Te_uRss%8FAMfS(Oc;M8_{Gp2M zk9l~Qx+oJpeC0)|i0bc+2g?i1A+2=if1Cw zS3I9h`-GkB%JfWqdZtXz)Td|4)c3OQsQYf_eFZ!AeMjkj40b;CU1|F>nqs#)c0`e$6&|4??cm%!Oo|?S4BStJD>V`_x%{`eClgPcVpQ9 zf83w;70jo;@@qc^^Qo^M*^S|MN__>>_CU`;2YL=V&~wm%o`Y23cl`f;IdE@0*xAzV zuklf-inW8rA;!+y2YUaZinaRlF#VI~%4g=-T?sWt_Q$7quzRT^z1vd7TDftUvisyC zeTr7aTK$=rvZs?H%}`Xa_Qy<2*)#H=B)uBL9b$>WI6PRUbfn3IDqMR@73Si>QrbWH z4M$_RL(CuJ@L*~2k!FsnaP1#whnbkN^y^Q4oz)ob5IZ~k1P_)=9ck953RmTE+|I-F zPv$$YtWRTPf6T>$rC)zCA4X%iLu`)PI6PST^(S+kG)7i`CLS#PI?+T?748nZyO@gy zOTYePo}uG>7mt{a)&5XL_QyOt^4mU@`l@j4?TK%1JYxD)`$HA(5c9`OJYxD)tFMZz{=Rs` zM6vdVDzZQJ#UrL)wLesm{qY$dEV;_>R@cgDjI7*DJXms-->k3wp)s;Q#^J&8vAk+R zt-i*{>d(Z3Bl}|}9xNZrE2h-`&=}btqwvUU-BjAD!j-i|ac?|WK9<)) zsvV>;+(YJ|ad@zN?D92}-q$jz)mKGU|1&&Ta+TK~tCiCjS-F{bu;l8J=EBwf&=}bt zoDdi3iKa@~Wb>KQu=6$2dG#`gKWf*VgK5 zjI91lJXrdb*9)%wp)s;QKEWfe(p>4H3RlI_z`1y^Txy}ol`7W$n29M%uJQ`)_4z|% zxI^sxF%A!wel6*J!i@e@2)E|qsOs&&yAS(ll3uv}_MYarJC&=}bt zqwvT(kX72M!j-i6h(sgXfQ_V(p-rh_UqRO7k&Qto<<#QxH}&AA2Ts!=~v!&wmyGo40ni~KYoG-%cZU~xl)Cz@;Gj1V#;!< zE6w^;vG&I}Oj-JMrLzZBu~vU3rY!xs(nL`eYk$nc^!88OGo`wxQ$<#PE*>oXy3s^2 zR@mOrk(T}Y@OAz1zoLqOYkz!(DNC;IG}}_eTDftUvRvvO=E8O7b&cWr+j)H^9xNZb zhuMRjKQu=6$4op}f_4vc;W~e4jO>qbc(8oz9_A=^>T8Uw{!BbrK6Vdt6gz)tjO>qb zc(8oz9_A=^>T8Uw{!BbrK6Vdt6gz)tjO>r^@-WUmH?X3v3MX#=+8+;`OBoMUxJUNK z1E*icLlxN{Gx5Obm#MFctp2`u;PlJc2YSwJ}cJk_{oehY z%#U9&ncpzK#PDZv8eF?J=#96V-S7B=M1|)~Mi!H1K&=tx?|* zY2d4*TBE+dM+4u{sWqxFA`N^;uGXmUh&1pMm0F{|BhtW6#A=QDj!1)NLM$&(J9?7e zK3|sFs2%G&Iv<=h#rZOICaeC~A6w^xvl*W0t3THNyL@oA5@)Q`$EW&ZeYVaAXD|FW zGxf*%Z=DZLeb{UwwSSV|>21DO=Kp_bkEu}AU+sQ;&&VgHM%DLIJJx@6J~36Q^jAC9 ze{4Q^&e6O6YLEHjjC^9gRDD0SqvPM^+yCA6nEzDzsU7RHbv`lQsq|Gl)^~J1F+ZyG zS3A~!bUraZs`OVo)_-(9F<+|mS3A~!bUrwL%kLdl{!oAHkFE2;`O-1Hb5!ZC{#gI5 z^TGL2erLGSU;VNE+vbzs_ebgTvf7|DW^Py9EOTE%x{jvUA z=Y#X3yjDh~zxreSN9Tj{rBiyJzVe6qV}ER&56+kJIyja7>W}r`Iv<=bozjXtmHz6F z_1`)loFC;itSbH0AM3w$J~%(hE0k6Gt3TGC@xl4cDXmpj@mGJ$f7^WW>V5C}svYNJ zbH+ensN+0#d`fQyK&TsN+^OgSU zkM-X=ADkcMy#y-#)gSA>Z9aJ?hAHFul`v7@AARpwaloUdKe`fim!)F1m}>wIv2 zbWQJbv`&hx~BPYmHz6F_1`)loF84&{J2Vg^~d^e zoe$2Bu4#T;rN8=P{lCZOM)EPW<9uvQIA6Mxd`|77^TYYlo#b-EQIzOB*-AO*D_ObaL zzVbPoK&c|HDKr}ooG;n8RfRiXe>`yhWIR-n{V@{{oIaWQs>tepmWRz>dY{#5x;%5E zzT%lI^cBx%+rHxY^wU>7?~nV6=N(j6Vc+KQ4nbe>yhimE&!e)hcq-RdFs6rBn$?fN zm>ynF-2E7g>EU(P-i>jjOpmYYem@3ddVHN7`Y{;OBV~GgWmNrNVLm;+o^$&#m`_iX z>4`Euy{@L+=QvTOCwlCkDAN;VdZIo(QKl#A(=%o2JJff?d=L1(f*t$5k90oVq zwEY;&r@miiKL+!u?lieZDM}Q9IUmOMEVG`(qta;$F4K3`Fhmd~W|fqy%Y3J~6qezMtCt_@9wa z%xbv`&>%5P^>`l~e;C$(r-U6!h zSAVSk*7@LkDZe*Y>977+|E=@E`O-1H!B^?8{#gHQ^U3eDzU!-YoWK1(ADn;XH;ya) z)E^z6+vkV#o%}v|rN8=P{kP5s=SO+9fJ%S$$NF!b56+MBS`d}~>W}r`Iv<=L<&{1v z{na1qzjZ!1Kg#R4RQjtw)_?1KaDJ3m>8bQrf2{x3`QZF0ufbI5ul`v7t@FY8QC?xI z(qH|t{@>%1*DrhLuXdcDjn4n;*`1@_O6V@u~j!_}n@lobQ~;{5G|Z%`dNo|9*U{9p`i7^TGLA-U*@dhx()Q z|MvOe{OCg7FID^K{BVAhcQL7sfAz=5|JM27{3!2qQt7Y$SpTi_!TC|%$EMO>{jvUx z56*8cX)mIRzxreTTjzuGoxFQjrN8=P{kP5s=R=pYhv4$IzO&jRzY+Pw{HXf;YWL%N zK0bNh#P{!~_L#rT$S3A!)%R07I{ufmzrl$7Vt!P8ezjx$N9Pmsp-O+XWBq@dPt0#B zebkQi8J$neZz}!Oj`bg%Pt1=h{nd{3ADvIkk1GAuj`bg%56+hslFzAqbbdI0Thjcv z>inSo`24VKKG%P6{-pNV`QZHRO7bVQ|299I|6J4jwfFP0+DGSy^Pg*azqHa{{n7P# z`}}aebWQs+RQjtw)_?1KaK3a+@0V8kt3TF%>wIv&bWQW;D*e?T>%VnAIA6M^_e(4N z)gSA>bv`&>x{`cO?W6O<`O%f+b7~)(-;LyRYRCE9_xa#_=SK1|wU5pZ=SMe^zo~t6 zemFn7k^D{Vqw~Z0(2eA8Y9E~+&WCO!e^dMD{BS;WBl(-!N9Tw0p&QBH)IK^toFCmt z{-*Zd=7;m08_CDiJ~qEQ$;Z@=^Re;y;C$&$@;SAS&JX8HcaqPkeRO^}U%HcgPVJ-f z!}-#k8kN2+nisx0m zuXvv6`iiI5`--RfeFbBBcx6ca7>w!R^_<&}!I&N?)8p$-srxI(*VVMIU`&s%BdQ;R zF+EbI$5%4c{}txbihThW3Xf2_ZaQRV8_1i!`F@BJF)c@?0o9GVfAA$pZbnE z{TR%rzAH#S20QjI)Th4oeD_y;_3gfbFR_!DC6-r+!x230t7d$O2|2fKP4=($i8Yk!Qxl-+F|=ygsNYxO_F zl-;rY$uqLXaP928J`NA|gma*Gj;e6&A6NC6n6jsWKS{qdhC9U04m0s!>Biv?o*Feq z_QxnZ{v@?#zZGZ<*WRukbMaum1O3Ub8XChLV*Z$k2TS4pHmyI}=lue*MV|5sl#vv9rTWJXk*V zC-Z|eM)t=zJXrd5r1_XCT>Hn>F-gvO&D!*%9J4j==hs;4U@n8vBUTL8AhsMbM7>5VT$MPx?wfY((t3MMD zmXGB%L~4I%jO>qbc(8ozoaQLj>T8Uw{!BbrK9*Mps{NrcvOi|x!Sb6hsMbM z_z4~?xymbY)w*bmtjkP1ST1#@v*lFb?s%k5qcF`Y=~c(RDzdhFd(Z3rC*oy4sY!bjgkE^6AzY; z<@J+me`t*CkDuVda;ZytySCOvV`N=s;=yvMyk>dr4~>!iF%A!weqGZ0$hG{RQbF|sZ*@nE@B-q)-4hsMbM7>5T-zw(}K zwfY((t3MMDmVV_O`)Yq^jO>qbc(C+qp^2g@T>Hm8|4d9-`nAwGimF)qV;-j0w8wIF zZBRv4e=Z&@{kqb8OciT?e1<8@rLHvVQ^i`jahS5y=}L1cRjk#Yi789Ju5|XGD%SoO zlj*rwJN=s8M^?q&c*OLpR$mo<^xK}p`{EJPui77~$o|+DkC>0u{!m5s$5wd6Lq z60u{!m5s$4oq8 z`cbxUgx)^AOj#~?YX9$7ezG@WI3F_}s&J3Y#sjBc_H9*>)!zyaoJ*NsUC!~^G2 zroJk&`upO6(=YRfDzZQJ#RKPK<_}e5f6T-Kr(dSNDzf_f;(^mI^M@+3KW5^A(=StB z6s(jiXS%M!kA}L!&LB?*brp>1G2~L+7>wyLJR^5wFs8?FpWKbXm>$E`v>SslJyE77 z>eCZtdJ36R{Yg)h=_x#Uc4IJ~p2GcUHwN?RDO|nelOj&r|q# z!sn-WM^Nd(uAv8V6dlMhbRb92foN^}(jdibMKjcXB1aB87qK%DI}fq55IYBr-;R$O zc7|2^*7@P{9=krOeRO{K{LJot)IK^teEntjwrc+_KYVw{o*dLZIzN2>&z=j_J~lu0 zRIhfN7Hppn&NEnMqxRAH;l%Ai@)@;{&JSmjEN@l&*7@Ol=R)#RwU5pZ=RfSX5Vij{ zKb+58$nO(s-#R~>zg)=gOKKmTAI^U+LdJ1|xKZT+n1 z(077X5i`)b0#mdxun(;Qle7x#MXSIxtpfYeDlk#2z@D@<#~9PRE?LDiuS`}~Fs6BR zvU&{0G_O!rkHM&GjCfu$?Z+X;j+eYbUF{Ez;rg5UGx1<&%L6^1s>0o2I}FdogI_CE z;rg5U^YF;)aaY#{Rk-$c?C*^Sd$O=q@I4=?9W+w~dyYEN=cv5)d`*nq^XIka>oM3p zOkR7w9)q3f^4jy&7^=wUk5BPn$6VeMpjJ*}xOTSA_)I+5c`WY;QTszoOA$p7y9Bt3MBqyw6y5?5o1Hw`=y^c(C*< z??hKSNMpE%%t15pVCh%hiLmyE#>oB{hX+f)@;;Ka`WhpvKNAm@e&u~OYkz2r?2nmv zu=FeM(^>mNV`P8)1P_+=<^3~jT{K44WhNdhm&*HV*8b2K*&pNZVCh%h-LqC-V`TMb z;=%H!iF%OTt_hqHNDqMTZ9OvS}(yzRCXzdS;;SMo>%*2DGUwLoQ+8-Jt z`(qp)Ed9zmi`MFEjI91=c(7b5?-^Pvr!lf}JYxD)`$HAk zAA91FcMGljp$d10T^r`&5!0_)eO0*rrv6rV#9XRYP8C_XnRvups#aeWS^a(Si0N1D z4^?D;%)}$6U$y$G$m;KlM@+wJf2bn+V_!U2a<$NGOBL>)$5Z1tOj$m*&;(5tYxQSh z%JQ)#t@l}9Uo?h0#8QRt^T_+UR@7DD%IzA#>17JXk(<{aVY{ ze@CwUp^EH}ad@zN?3&i;t<~2US^b%Kuzc*AcDt$lp)s;QX5zsTwCmT*3wHHTMfS%y zJXk)Kcg3yG4jLn?KNAm@e&tl$N#DnEhc{kkJ9~vY3 zV;&xPuh&X_Rk-$+InKp{rC)ik-`XD9RE4|aasHTzDa*%hG;>tN z+8^UEW$D+ACW@+9tG_L#w)%?gaUMUV{oAf{k8BH7Jn|1z@puA86^~~zRPneQ?(yCtpYQ(3hYy>z)Ywz2 z$8q#+8Pn&!#Qhk?9e>j2Zmwty#`L)ZDjI_^JyNF69Z=CjADti0m)P&1Y9E~+&exthFZaj4`lI{v?eoL=5}U)I_R;y_{OGxZ zbASA+KR*7q&Ijj9Z2pnjN9Tw0qvsyY{qe8<`1oghaK7{01G(p~{+R!^`IxTg^Q(P! zJ~%&m?%CTN|7stdAI^`SyBPQSt3N(}Zk-R#kDmJ&_xh_p)_?1KaDMjO4Y}7}{jvUA z=Y#X3=YGh&{_2nQADs`*kDmJ>_x@0S?2q5(gY%*1&bhsQ>W}sNZ9X`^dG4^=>!J~&@`?vdO3L;cbDfBXD!ezcI4dDK2SKb#*e zWQ`!TkIoP0M+;e1OYNic!}-xd)}m7TZ}Y?X%|ceJQ~T)raQ^e$o43C|SATqezI8r0 zKYH%Y+v~6XSpTi_!THj2x7l9**nfFjy*Kw)`+9Zbzs={lukAzMcYV|z^SK%M#C)y# zerosg`;2^IzEpibwPXE9=M(d#N`JLu{lCj6<~tRCwPXIH^NIORrN7#-{-g7W`BA06 z+Ohtl^NIOTrN7#-{-g7W`B0_5+Ohtl^TGMqbI;s9pHYA8k8SgL?(y2`t9G2fjn4#zP;|E=@E`O^w`l~Te`(qv+rY`zT^6-@xsUoVsHy$i6G>0$; zsUkaQCLSz7JJ8Hg74D9IzmBGnc(8ozKodn(tkwSvQ>MHy$ zxU2BHoUX#Jgk6Q73%d$G8oCO1P+f7ROwS?9>BeA8&tXnYHwI&R4)@yK7>wyTTwl5| z7}Ik&ZtF2@wfE=z!mfh(^b+Qvbz?A}Uc!8sZVcwrOSs4F#$Z0ZgzH>42J`7cncB#h z`a+p5)Taw&x=^1kl<7i!x=^NZ@9>&>+`YT2U`(%+>6J3QQl?kR^h%jtDbp)u8u#0( ziNzg9qw~Xe zBypwXTK}2)AK%i8{QZBUJw88Ie#3$`a zU$tX>N9Pmsfl7b1WBo_x6Z4%)f3;)%$L3>ec*F$h-2tk|zZlQPBj!W3`l@gTnEG4c z5tE%-IaOrkX5tZZty+CmWcByO1Ltyf9#cj3$G&*rT*~~RitLY>c;HmZ)K^7Te_uRs zs%8FAMfS(Oc;M8_{Gp2MkC}Mj%*)hQMOJ?sJWLssX4>jqs))+X#e*eRra$wCDzZOj z;=%HRE4|avC`#COj-JM zOsl+9iL)x!{uqZTOTUhEj-o2o>d(ZKrC)IsESHKa7Nf*BDv-nRu}DE3RPN`9ou5e~iO}rC)Ic<4%2zk=37vM_!G&dg4=sYj26b z-gvOQ@I+@Zs$%V+ahS67>qHYpRjk#Yi789JPBc+e#o8Y~!Ib4vCz|!CVy(+eOj#~< zqREvi*8Z4@DNDaj^o?azto<<#QtxK9;SSzP7vU20_V9C`b%^s}P*BDv-nRu{l>yl;<*8b2K*&n0u zSZJcC3Rl(=fxYoy>DNN@F;%P`G!9die%T5ZzNb!gZBWHp{h5fd^lPE{m@3x(n29M% zzZRM(s$%VrpJ2*zsfA{Js#xnX6H}H;Ei~&>#o8a^FlE`+Li0jZtks{1DNDZ=nkcGb z?T?w5vh-`AiJ~gj{uqVnl_rX+$lC6W2TQ-MG*MK=+CeihW%<~ZW{#>@`{O5=vRvv) zvp!Xr=(rALB4(>DQGeimF(vKNC}yeqCvzsEV~eW@5_nu`A6SRk8NR zI80gkb)|`-D%R@H#FV99SDGlQV(pK4nBHjSsEVxqr+Bbj>PE9ZRjiepi7CsaZZzvt z#o8a^FlFi2jV6k!SgSu1Q6`^cBx1&%WaM?9o>| z?@#-R=N(F4@w|%l70>fnU-9&MU-9%uU-3-P>WbqR(f|C<+i`sbW@=+#rdENOS_Nim z6_}}2V5U}qnOX&AY88y>;j8BH#$m_w@XD0>3dYp-9cF)pF}2m9*cgoIfiku8Hv21# zsd2|+94XTy_34o^JyM?@DbpkM>5(!$Ql`F(d*?CVx4N%j$G-37+mFF~>idfJV=$lk z-h%xY?AZ4m$oesuPknEnZVcbMrLSPe{+aspOnrK$K0Q;Po~cjI)Td{9KJ^t+J7T^9 zW?gakI`Z*(%qp-ytOBbacY^OehwpseS77z+uY9HgAGh{7R1u#}=Hh|x9ZY>yWcByO z17DHNAF9ay*cT6Wy=8Z7<{*uc9rP1C*joB{hX>2Yd^hM`eT|XTpNR*{$9y;F-X9tx`(qp)EFbgTpnLT-Mppkb zJXkK}`!x5;X^gDgI6PSDT8Uw{yaQnI+$*OsvU20_V7Zjd(W&cOCB3SA}bDiQ?XPu=LA!gYF%qG2BDupmBJx^vm~p?$y^AS^b%Ku=LA!gYNyI zF|t2?f(J{Td>7_k7mbm1nTZF>rF@^}-X9tx`(qp)EZg#3n0xg#Mpl0&9xVOxeTjR2 zXpHQSnRu}D>z4LRsorQ;g}dXCDvZOFrC)hx>soz{;rd%5Fb|KsYk8%nv zrC)cNkEvqqpr2sMa;baThqpemHHIr=NA^rSST1!>dzIAw*y0%HuYIZVf2Lggq^h{5 zok(gPF&|UK-iXEYt5#nXewMK_%uGCD`cc;LLy)K^7Te_uRsK4$(t@wGs~;YKo#x|OBCng!Sb;KP0&=a_Qy<2 zSw411Gw$m1hsJP+*!g279xNX_&_q!c?vBUxWgMm~A3M-QQ59?TXJX3ou>(yMRk8NR zPcUVDGImv;i3dxrY?W^24^?D;jKhQFWA^?eQ(qNX{h4^Me9Y$BGk>Te z`(qv+mMCNORpHv(6W?4sSo&r6O3WXsaEF*bX5zupFZ;gCAF9ayn285Vzm7CfRE4|a zaees-rYx5_(yUJvYh7ky%5teA&H7Za_QyC(S^9OP`Isu!>d(ZKrC&#yD5_%ZkC~XV zeC$XwM^&u-F%DCfejRC|sEW1v^DsTpL{Sx4{keFs^y~D>$1FR#tkxE@C*ad7Q|c?8 z&&Ykn^J%TGc;2t~70-LRzT$aR?<=0?^}gbH>~|IC*AdlMJgN5;&(x`}U`)@i%%C5G zF+IPYEc!7R)AQ@@q921Xy-=n$$NG_Mc7NqUeR_GNU;P-&r+U`Ey-=%+2Smbp0_qp9|3S$Nc=aue!hg z_R+Povk>OznPfLU=I5zJ*B|rqroNrF#41OZ#niDyDpI*5@ z_xEK8xBXRfXRz?~eyNpZQzr(RiwAy6Fn_2b`(qv+EQ7FTXq@S& z!o6YtnvDm0di8hsyL*0BM2DC^W@5^+3zkwE4~^jt8H)!?o%{{`{_LPJvidXeV0j_? z4Z@BFjgkE^6AzYt`8)jm`9ou5fBXawmRzyl{_MEb7+IH@c(CNk-}3K|TaA(ZF%A!w zkFj6&?d+g2vidXeVELH8<=>wjG)DHvJUlE>Ml-$46RL>n&&7kKUv_n1{!m5s$4op} z8ffPS<_}e5e~iO}rCf~?e_b${JuK$A) zyUvY6jHO?EHoPj_9gp++OiWq&K6JUrN&Z1zOR5=B+GJM8>15)YPsu{Rm*+iDEg|8qQ8F2&w4wNI)svU20_ zU|An~gV@y97+L+9c(C+~y+LmN&=}bt{)YlkU{h4^M^oy+zVgAq<*&j3U zVCffIAH@8jF|t3#;la|c6PeDOdH2>6a=_DGmI4Jo4&-)#p$}J}URd zBj$9qKUCoku^Bb{;t|uY+8?UO{+NkJOuuUNRgu--7mt{J)&5XL_Q$?>#C)vwhbpo^ zX5takuUdUoWcByOBc@-qKU9(Z@fjX5m#TG9Mb>3sJXqFurs80lHMP28|EBk*=3s^IP1PFJACU&TxAZj? z-uSltB#+o^TX*%-W9LG~wU5mQ=R>yoBmRDBADa)(kMdr0)%jojvHpw? z&TsO5aTR~{$Naa>2j@R|x3@}v^~d^eoe$23^6q7o{_2nQ-#Q%VnA zI3LRUlU4f1{?}rSXSKUOw#O&$FZTZV)E@J<8TrKgtonXxN5^m8v2H|uF+Zz5zuK|> z-{lkYtBSwcG5^u|#C)dGU+q}`(fP!DsM25USpU)a#C)jIU+q}`(fP!DsM25USpU)a z#C)jIU+q}`(fQzfEbjnR_U+)SpTi_!THfSts7kFul`v7t@FY8(fMl?ef<5@J~khm zAD#bEJJxq}J~%%*|D$%S|LA;hesumv?O6Yx;$t(7{_{3}%y+n|+kFqDuKoFZ-nBoU zPrCN!{cG3$yuaz%pZ5n{`}6$SwLg!quKmfsYk%fnb^G#KS-xw>{Fc}Aan~R7TVD6q zU4P7Pd0n5o{+QqLI=;L9nBSG~yT0~ds>i<)e%IIYXV)M5@A|rb?fPT?U0>I~u0QtQ z^|hy8-Ty}T-3Y%M;ddkaZp42#!tX}>cO(36#D6!!?@svL3BNnxcPISrgx{U;yAytQ z!tYM_-3dQizwntb*ABG`d=9h*t4d?Z^1J{MXAKANoppAW49AJJBU&xy7s zAY8NmzIgCwV^w5-?289WMtF9j3ir>y|366@h3TK9UOX35h3o%k zN#Z!fShmGdQES&2*&pNZVELHuHB)EeroG0<>VJj@ORjvEm|i)Jk(C>V2g{{=51C$l zjgi%#i3iKae2L#^G%~pWVa6?=pWy%*X0)tBQQ=?~6yw z$7+A5BKu=sJYxD)`$HAkAM^0=-CgX?pi*BIuDzwj+u;#&saiQzxOS%8Ogv&PRjaRx ztp2`u#PqB7hbpo^X5takuUdUoWcByOBc@-qKU9(Zu`eDhLGxXE`sW6XksUM+50;Pl zo;|(#8Y8Pe6AzY;`JO(#KQu=6$4~HJxs>m<)9a!!vM%%RFwGw;ZFK6Z!nL=oZ*M$U zKIVJT^bXP(?jdu~I6PQBc1m*ttEWa)xb~0p$4pFFK6XkgP}Kg=814`|JB-7Fnc=#DnEyr?j?A?GKHS{V@{{mVTY+tUXn@J05ozKf#pcQm3?@Q+?cO3|Gdk z>ND|Rxzs7G=2iPcV`P7f!-J(?zI#xg2xyF~{yaQt3MMDmVWu(NWDKaM)t=zJXreWJ0tb#YmBV^XLzt&%J($t zmD3nmxp8=~)X8@=>ebg6S^b%Ku=LA!JnH?SF|t2q;=$4{-w~5T-zw&-e zRi3O0*Zz?y&BHYBwpFRGimd+Lc(C;ALh~_ItQ|BCQR=p02=tkwSvQveq!z1rMU#YJO*WU8vPw`->(?XLxRjiep zi7Csa7Mk^`V(pK}^jNH&o{4R{BBo#UCsl>(Z|C)yc*OLpR$moa{eAI>=~wL!Rb+qc zi$_eqYJaFA`(q{^G5xC5S4CETUp!*^Rr^B~*&m`D_fRk%AI*OzgavV82C<|x)@ z2aVzS+tp(x9xNZbra6kWKQu=6$5wc-Z0nll7uMQpjI8Zec(CN^nr08y+G>of?Mysa za&=9!2Wx+5jO>qbc(8ozn&!gQ>T8Uw{yaQxG*MKAYj00{d*i|Ku^Ua$RIzr@I80gk zb)$)*D%R@H#FV99H<~D_V(pL5FlEWrjb>Y_SSvRUQ6m#w(c}9RK;5TnV7Ql>rN9zRjmCn z6H}Ic-D#qzinTw+Van34J53Z-u~vU3rY!xs(?n4fYk$ndl%-#HnkeqK!q&Ts-mrfk zzy9BU{`v2J{_E?m?DTcztt&iL=qmjAwyW?boUX#}g1ZX859%uXO4wES*|Mwf~>i!C2dJN~ndJNll3^P4ZrYFkuM46r_(-ZZnoxRw1VLm-kpPnew zxbt~UJ??DXRj^|}?ik#S!H)g7ducZYV;c83?8aa|jr*L{W5m6mx(arUiu>VoW3X#f z+?%5t10VbNcw^rI`5S+B>;?RpnFrWW#q`H#es+#xXDD`lQae7^Y@ZKyKD+v;eRO{K z+{W%L)IK^teDz{?j%xodKYV|{?#tCaIzN2>cOp-+Y9E~+zQ1SB)M_7{AA5dNJAQ5- zn-9yo)Q&Ts@%iA?ilv=uADti0kIv-x0kx0L59dehmkPE2ZGJfaIg{V!)V_6oINxEv z0;+vD z`O<~V@KpQg{BXX+=0&RgxB21x$KK08zaOc6bUrvgVsnnwJ~}^~FI~u+4{9HsAI_I9 zB%f3J==^ZLbRqNS)IK^toG)ESKBxB4`Qd!&Lf$x3``G;KJwo(+r}p3GgY%t*59db6YftRr;$xx;|{5AI_I6YfNRsK+a?2oPU!THiH z&7Z6ESAVSkw)xyiKBsn^&yCLq=Sz2zTMemGydlYCC?qw~Z0(VgUTYX2@joZs9@ zKBo53`QiNMPVzOikIoP0M|YCXseN>QI6u0Rd`|77^TYYjo#bz7ADti0hwdbQQ~TKb z4qy2jPMB2jZ+feEe>`x)WIR;i9{C&(oc!45P({{dUp#O!Wd2Y^_Q$?>;N;5up^EH} znRwvb%G6gyR)1eSaIR(kP(}8~zIfo=%lx5=?2nmv;MB|1S4CETUp#OsX8uq`_Qxl9 z7Glwt-sUkaQCLSz7JJ8Hg74D9IzmBGnc(8ozKodn(tks{1 zDa*$WG*MK=+8^UEW%<~FCW@+9tG`92$Mk!+ePX+c#ZOvS#C%K@hm@a+$06l~HIJB} zsp3<_VsceeSB0Oq?OeDo9x=J9{h^BNk9l|;Q(jo9uL{@R?v(b%Bc@-qKUCokF@Nlf zM@$rJf2bn+VG(l6vTK$=rvV82AW)If)g&M;hVyVI?JWe!GRD~;R z_jG&X!Sb;aP0&=acF;^rSw413a}=wqhbq?o_(`VcuQOIn{h4j`70+~|uXsM+_7%_P zsJ`NPC*4;(@3#7i=k>O$IKQrQeZ}*r>?@wS^c9Th`86l6AA>PHznz=E)GN^?!x=^zwQ}?#Ez0y}a%VyD=8ZbfHWa%5-_n z9PU2{JN6gKbfG?7DAR@dbfHYIlm1~J zx%Cz7eCqo}^vv=L>f(I`yGHp6&HWhceCn&r_G92{ zl&6LD2%aZ(?fBZ`&tP?bf8tPkb@%uCeDIO&cl@0`>i>A}Z&W_`9CISqO0|#94_}o} z^-t};%?IZ@Y?gr9 zx6TjeLuZn&seN>QI6q=Dc+@^RKb#+(N&cqx(fQ&0h|RuJ`{?{|esm`DtJFR=KQ=Q~ z?KpoMpAXKD*t}@9|299I@32|vY9E~+&UY>(A5;72{BVB6-Y8M~*7@Q5h`kS__R;y_ z{OCgFzo~t6emFm3@A9dAbbdHLx{&#AY9E~+&X3r8xN84he(Wu0wc~tjd_FkeVeh!B zeRO^}KVmBwsD11Fa6ZJ=pHTbg{BSLLbJJx4(J~7{^^jAC9e{4Q^MZ9wIv2lvil4^jCkZ|JM27{3x%#U+J&@ zSpRMF$-5`K>#KI0zm3la=WBWIjLIMCkBbH+j#fN+0#d`fQyK&Tnq%{m@E(^~d^eoe$23@_uiX z{_2nQ-#Q6y&5b1)gSBsclqRd}=Y#XHd)oh? z@`w7P<9qx3a6XiG$*uHPf2{v^`QZHKp4MNh^ihAT&(`_i{3h=}UFom>SpTi_!THcV z?T=9Dul`v7t@FY8(4FLOY9E~+&WG-4e}wAzSATr`|7|`v|GATVP3@!e!}-rW?SD`m z-|CN#?``ur{PUl$|Ijy3#lLCQl`ZkW*_VA%Rk(Vy@xaNBeOpyz_4maCCrjoJRb+qc ziw91g%pa=A{+Nje&YetsRb=(|#RKP7<_}e5f6T-Kr&6ZADzf_f;(=2y^M@+3KR&|) zr%k4dDzYwn;$iyZtWOp0j(@+>vw3-(Q>tm-+P-bf3stc<9x)%Q)mMd|AIu&5;t}() z+8?UO{@53fn2*)|P(}8~Ogv&fR;#aytp2`u#C)vwhbpo^KEop>SG6vx$hz!{M@+72 zf2bn+V_!UCf>!%O71cPL$jU!&@ZbGSBi74GD&!u`=zFsA2_I(1_(rswbk+>ODQp2K}|HwI&R zp-eB~d|LmNOE{vs3dZz8nO;Js)cqCa(@S{r?8aa|y@b2ZdW?lKT`1FqGF|Agzfh(N zWx7zGE|lp)eY#MlSIRW*^6J2#d-ispgZVV>E8300d>Z#AtjCDEvvn2h zd>VJi>c(Kl{{Lg|?Uozab!FXoy(7+}bi|faKhpcZ*fF-2OrQj2_FQ(`1S@0QbPRyB z^d(qgWwA(q%1*Bjc0Khcf%N)d*HeF*K(7yWJ@q?s=Y9A+nR^-RH_Gq3+v|hG}li0Yq<2mWoa`cOu!kC}Mj zxs<7|jHv!7Jn($Xlv74jZXO=q`Oass%4pjE`4|gl^CFkk9MohxOu>UhpSW@5_x!W(rIm2s?(I!u{A zcB77>GLGv13{&P@-Kf{6jH7aOm@?<;M!h~|9MzwRDf7o})KOH%u|DQu%GRLS)9kj( zYVH{*Bi2VH9?bn(s6VERqxv&3W$xGV;ljW6VD4QVl+h~0uBS8cVE))b9Ytld>M&2K z5)bBnv6bcaZPiE9|L1rxUuvOVpE8>Z9pD8xQ7wE!0s|MyrnJ z)u9ek=6{s>6O8=HlVq zuUvg)H2qEebMf%*S6&~=i1qO^JiL>a>!OUP%ei=XpDwQtWyJb87Z2}#<@KSASRb?S z@aqHKl~=T>{wJ)Zn1dCby(;R}uSkQ{jRT~Uf+r|@Do@?y}lJ`T!^!x zIQHS{^I_hK;>fAFkf+eUAII*AofL?_pWN9TiGn@e~fB-3B*vHqj;!LH6Fyb+S=ul88~(fMH4=Mvud$n;lx ztp9KG!LH9G>=KjdtM*vmvH4tyf2KJ0&+7BR{#ZOa=Y9Mu{#Ab1pR%3*(e*{~>U^+& z70;c@#-G~b@i96d?El!iyZHMlUYig0f8uFw+4xs`tpDhIu>TX!bIbHsd#wL&^TGa3 zJdZ8YSM9OBqw~T3PCSt<(_ihe{-g83{!cvDEz@7^vHqA(JSps*uj1I>s?P`eGw~d- ztUlBpjlc2vVSgx|jF#!I_E`VX`C$Jio_v<+ul88~-{yn;uXu7+GG7k=Y##9c*0qxzuIH{|1}@%-^4S@GX2yZ>-U{}9&dXK z$1}nd_wQ5Mzh~zY&%AoqUvclRRpjISuk7?|Tb++z zzm(~(IM%;5pLhn;yZ(w}|ExYA?4QL`qO$r>dvtvmpC9&z*6{vkroY-_{ePPe_J7u} zzgecQ+GBl3=Y##9HN4-M>96)!|F81F{>>WpH_P-w`?!{m8uU`E1``wGbuJ670Yy9VNWAgOhdhr+k zUi{_X^x~M`{qz33*BXm=lr499`kz;evi-k%=>?k`g?r(PrdfI{vMzA zzrFUj{vMz6>t1_Ye~-`K=e)h0|BEZoGH?xA2ChQOz;$RDn51RkTC@yI(=u>9S_UR+ z8Mr3x%v{E_ovYi^rJZcs&tOd3>6-mM7}IvbU%wB=w4D;x?}IUIC++n5XlK#%GgzIr z^EUc@usUsf_V@c>b=vj?@Atv#wCye2>!a=N+RtEPzwMye?}OE8+odn>!&Je_SqA=NDPy{vi-(^{=k=kCSRXU-@OMeM`pSsvpNogT zN6za*8L>Xj#lt%!d3`7&*2hddy!(}_uZ*bvxp;WLFs~0~#QHcF5AUGm^`VSdA3wu` zIaf>Y`f}yeM^tVe9&MMcp4X?0roDN6bMavQSleZ*UmxnDRfyHcOgxxB)^;)L*N6Iu z^-+fh^T*mAXMOe6M^t|%9?TzWd!Y5}Lw&^hn287T$J!oj{rXTJu|8_>@T+9s? z+)p4IAEWcb?n&GYA^U!6kLzP}KG=J?e7tRnzn|i@`CxA*?qrgUf3?T@|27}&&0NCH z8=1apkM$j$5B6^2E<>6AYLE3Foe%bQE@7vcOnkM;R&KG^lS zkoP+jugx#+p7%a}703QreLmR#iF+qz^`Z9Y`aV8C?EhTD{)(CYYLE5*Z9drlvc1Rf z=U2QoAMEegE?4;bDPEfo_J87@#M$*-?Xmt}<%9j1YuHyf(?{*GKEKTe`!8`n?@V8{ z$NG-W2m3qMu$OYCzuIH{N9Tk6p|}@+roY-_{XL&+vbXZ@#^Xr}@1IX`@2^$lgEUUvaE|bw1wz$@Eto>pwal?BB$*#xniY9_v3gpLjObyS|EJ|ExYA?4QLm zy0ZFEdo=!kpC9&rmazUT(^u`WzF*~o{h1}KAItPnd#umse6T;Xg!N;Y{%Vi)ADs{O zhnDbuW~RT|WBo_xgZ-f;tWV4IS9`4gZ}Y+a&l29h%=A@ztncW2u>Z4!^=X;@YLE3F zoe%bZ;`v^g{%Vi)ADd4+kLq1t#j(Hkbw1diiswOP`lvk`f8+DR{!Ba}E7M=?vHqj; z!TwJ?BP-Ki?Xmu&^TGa4JOeA!U+uB}zs(2xJMj#wOkcIf`i{;A`#US~&lIoD5BonW z@z)fu&JX)Pc5)%UzA64SKG=U*!~SO3@2}cp{$umm!ug2r`YMk7t@?bhKemPQ*0cIh zdo=!kpC9&jHnM(9@#_4rzq66`X^L0phy9(6tWQ(CIzR0HY-D|!;??in=jv=e_# z@#_4rKeQ8nP4Vjdus^gDe@*e~{IEZ?6Ms!{&+qoOKXK%f#l1hH_@4v8J@|Vw^6~yo z_WcxZ&!=bPa)$NJXha}WO6yZ(xM|7=D+-XF@opWmN%+WG1Nz1^sXc?HMW#D?W3{2EAa7|u5eiIo}%XwZ`d(4h@AP^K5k z^g@|lDANmNdZA3)N$)*k?X2&92CLI{9&^7BR;TSu*M1+YPTRSZ{XSTowzKVeeYDfh z`WdWFZ?sNtv`%ldPH(hMZ?sNtv`%ldPTPLxJz{Og=Y9rb+IHRT_rb2GZD-JaAMASC zb{FjR!G2$C)Z%NQWndnbfyb?7U>=r%$E`A=xBquMa0OW(%4l5A#{>V)84qQ|`k09a zo@<->%82TZ!UNAOO*v&m{K{zc^XKF4W-cD=evY|c z#zTFy3aQ0|-K#Ta)4r|xi0aS8gE=+K*S7jlAF)3EJ0APnbHF3hf0yB1xcsjuBWimt z9^Nm^>q8l_K7NLW_oZ@Olo53~7Z2}T<@KSASRd!&;r+3^K9mvbV<)OmfVk60gdcrbtL8rBBp>Z^~a{!BcWKNjDS$m>IW#QKGgE?36ZR5N?)JLq3Iy{*B72hP!)mI-;{h4?$_bcurkk^O$ zi1jfO59W`>T_p1QP#>{A>hNIhSKJ{aS6_WZ^=IP2+^@JlOkN-ABi2V99?boUd;jF> ztB$FfOPZ`Jhn29NKzv6Cd`SnA6v{A>hNIh z*AjL(%+*&PQT^}W!Ca?>t_@U1Q|0Ly%*2%WQcKw3Fdw(-qg9CA6VAh9rSBsvqiJtf zhq-t#_iLq&qB4&4F%whfey!9WQ^v7AW@5_Rua!EA$~e|X9j46vTIpNQ$~dY&6I14X zt<+Ie#<4!W$`tQEq^RdT9}PS=Rn)6rkp`Pv;=RWdZTgQ%63-14ZTkHocOE~(>i)L> zxc|HFQ9t`rbUqq>_V%u?qJI2Vq~V|EzU!-~*S8`K|HSrPUq!vXW76=?cHb3L)GPQ~ zH2m|`ca0SF8danb&wzVZSaI(>RpjHnlkD>=-n^C>`FQsv`+kaJ{j2lAE=N4oE~^i< z$MrEfAMD&*!gJwFf3?T@|27}&&0NBB-ArG#$NG-W2YWY{u%C6NzuIH{zsd)DFPHGH zMy8M2V|_;FgPog8cqb&&U+uB}zs(1`K9}%@LZ+|UV|~Zw6VF6@*H>}upVjAs{j+!` zT2>!wkH-J_{IEY{r{dx7r+95X*#EJeu<`d(yfz=~|HRYgvg^OvWBnN)?9as0+%o=Z zkNJLI#_^UnUKRO@m&%|@UGX2#a>pwal?El1*z%u>S9_#TWJ{L1uKd#wL&^TGa3JfSMn_bl!A zkMpf=Z+q~zGn{(ym%q@9zwYmP@z?yn7k|wUd-2!&q8ESt{`BIn>r*fOs^4DxRUdhL z`#d$Q7svdz&-c@M?J>XYbN`rLd(3b9+@GS?9`oBi-=FWb$Na3-^ZJsv-#<^?>cw&W z?Vs;|_1fe5+dubj>9xo8w}0+0(QA+EZ~uIMJ#T*}{O*L`oz&l*@Vk@xyAytQQh#^C z?@sFPPWU|tzX##>Ap9PL--Gab5PlEB??L!I2)_s6XZus)5o{Uw8fY1K6k7(q4q65t z$(Dhyg_eOwvt{7xp=IC^Z5jBQc=_PPm|70HZd#l%W#5&3Q}#XCxBObX?Oc#w85PGh zRG$wX0d41kUVW%Nx`K?)4`1Kf&JR8P)gJ3VIv+eEXgfdj^gnxhJYQ-%C-nIJc6&UV zYda70KEK-I@jp5rJb!IF5A^g`d#wNHeDM8A+j*d;zuIH{N9Tj@Kikd&J^d@SU*4Si z`2Efp_x?fl{S|NHdpvy`$L)jievq&^YQ*rroZA?|LT0a zf0pU5IM%;9AMCHSoeO&RmuipeV{AU{&HG$m#j*eP`+Ts!)83r#>8ti={Qf>a?C-Rl z4SM>jJ=S-0KG96)!|Iztif2r+!(9>V-vHqj;!TwU) z`Jku2+GG7k=Y##Fw(~(xf3?T@kIo1COKskOnK<<=ZF2Hc(PYE{?#7;etwk?_HTBweob-DZ++X}Ir14X?){zY^C{lO z-;8{`f0TVc#j*a?`FMXR(_e9{e|0|IKg#r19P3}5kN1}{{T0Xh*X9#X9)8zfaqrK~ z$jAFj+4oZ%jsJKu_iym?{!sS!703FG&d2*ZnZAl+eXH}q{?a}8b6I_;J+6<@`C$L; z9@ejA`l~(Ge{??BU%H3)OEdk|9_v3kAM7vP!}_^Qf3?T@kIo1COZV`8Yo@>2WBo_x zgZ-s@SU;EPul88~vH3j0`nh*~703SE*ZE-o>k-~B&Gb=wH2%ithy9^PSihF(ul88~ z(fMHi=n>u@&Gc7$tpDhIus`%5{+r^}`C)(PLHswxtMkMD(1ZAIidW}{{h~2|oC?nR#&+x#mlj)+2sLQ!{ zU{}iOLm9C?&cy?}Vpbo@i1jfK4^tPdS-5=oMauB%pN$9e3#~#}1t}v|&`dm-gLa{w zqcU1`{P`G7m3T0J>_QzyWgOL?i7E5PF4R#}#<4!WgDG>aF4XH&#!;7L@DXsQye$nLl=+j-oP-^-+cCmHLIsh}w?HV+$)O z?Gu|X;l1GhZH9Nh@;;Q&D#WOti$`-5*N=K@B%c2=9?c=?Wwd+bUPilH>t(e0dM~5R z*m@c5SG||fuIqWm&5gNUMyror24i}oOmEJq>HQVP^ycmwdwnpbH#fKJ^}(1fle)U=WF*eSe-7E>Ee8t-d|yLy109>ULUMZ7dK_A}dJfdfV0F4urYo(}l`>r^ z)0NigN|~;-PFKp*pIDzW^=G>GGT7Mn=RWuPVAoTBc5JT?R;T{_%U&O>PW>5rc_021 zwq6FSQ-4xZuMal%{b?z^KG^kir**p1I^AiV?zB$*&e{2Q@p}jNGFYA7>Dc!>g!cXl zW9nBi=6(3}biE8#r+!UM-iKdj(92+T>YvT4kN9M@$AeX&e>$r^W@E~(+Wu*EPkr^# z?%Aw9>hNH*9RDo3r@s1#>i-N6_N(rnR`--sA5poPc(8j9|FpVSAL=94M;#u_Q}WNE zd+Mu?sQyem*xj0cTHUJ;^%3i%4iDxQ`)AQT_0>mIe;ywGnP;xPGMe_sr^II<##}i6 z{I9cud9P6VFQ|5kM>ADML9MzwRDRaNBbk&VAj`cAU zQ|6Cd>6$BL9P6VB)4y5K&DPSYkEs6l@L(?7jjjq;#!;7sb@G(aRC$iud6@pqP6N#AQy;ND z=HkKpvA@}gLVdIfv3K<9@L=xO-|RA?KBD?F@nG)PLj5siwCb?gMI|20{ra2zgVaaU z-_)Op2XhqvX7?!d5$j_n9?bn(s6VERRvph@kMCg0e5t?Lu}yt6W$d~>6A$J~E!4SE zMyrnJxUIvKxnF!QMr9n;|L>Syl3iyb)8EUm_aWOpo7v}3MpXZ7JiPmr*M~A%h1kwe zGx6~5SFXM?qWb6J;T^@iK9mvbVMpSUds1>M&*Q*B;*C&94sXqv>x~hnaXV_iLw)qB2@_Jg*Ml!Ib$@d)VPHAGhkG zDP!Yy9v*l4KC&{J_BJZ#;=$anJ9QM5ajcJ-m@@b4PW>@u9P48yrp*1iQ%6x5$NH$l zl(}Db>L@DXsQye$nfrC8{+Ke3^)VAu=6>C&qo|ByeS8N~=1bkFbES-z0hj+j7`cOu!k8|LJc7=?#-u5#s+5tW;Xhxes&^_3CTKNk=0ZRPc$j94Et@$l|fuD&v&`sd<- z9YvevC?nR#OgykZX6h>=s(&sX*dMd{P)4kebMe6bnAL|eVtxEQ4|_*;eS1!L{cs&# zPF_FbusY_PLU&-v_JH z+vlo^ejlt(Z=W-zejlt(Z=YAoULOl(x=^MIWx7zN3$4?IGF@n$E|lp)>$II&-(%X& zM(<~^vAF?}-h*7rs>iK<*mzS$oBP_XFK6R{ueioT8LdKQ z#=s~}~>3Yv)rzArQN zl@ZmSi3h%GHuaSe)jt;x>{(fTC?nR#Ogy+Jsf?)pnRwXf$1_J|wCXTN@oYSpU&xXD;9NYIFJ*56;gPM3V|~;i#@sLVwvmkn_0ja7jR$kTu5|UFGFo*! ze?4Ym%KS0*rlE}&_0cM%77ylrUFix$Wi;)dSBIIHGB=RDLu{i#eY6VsIUdZpx>7e# z8BMq6$gabb`BLn?eXCR7$M&|rgfe_}JnLf=V&0d^l~YDj&no#$JmP*ES$!y@Rfmo2 zv+?lmS6&~=Xcc1hF%u8(2IlH3BdUKc9^U=R>q8l_KF-C%yMcLqC?nR#&+zcRRIZCM zqAus+;eEQiK9mvbVTKzm-g_)Q#2QBVdnqOhmN2?HX z6{_%vyUk|WDx)cDWB+VCm_HVGBhD*GeY6^~3aZ0{`D1aX>0EvF5!L@09?ZFlJAmiP zsgI~!9Ujb=io3h#>Z^~a{!BcWKNk1)&+9{d#QKqC9S`k09a^T*=phk1Rdk60gdcrf=X zo@|+`uRfysGx1>V*Bah7&g(;c#QLbigSlU8c&9m6UwuUNXX3%!ua&M*R7R_gr>pQC zOquJn(v@z?IO;MF(=F^@m|eA%5!F8%59WSt)KOH%v4ZL_W$xET{V`=6)t`webHBE* z!(smWqCQ%M*ckvb@nG)P7WOa9>qC9S`l!Q$xnEn@;V@TUeMI$V;=$anjXH|TXw_k! z!T0cBzSKs&K4lzrnTaX$r8esIDdSilb(k{uYom^$GLGuc!*r*PqB5fTXXC-#ubn!I z$~aa~9j46v+Nq@u9P48yrp*1?siXM)8GEurd;BZ&XLw&K|F+6# zK9Jr@t}_2u=Uj94Et@$l|fuD&v&`sd=|-LJeplo9J=CLZ4X%GFm!RR2so?!i&a z>O&c=I_xRn*?4&OE3Xe_v`KKXwnR2lFe8`e+qm^TIkjm_K$8YZPZ4VNUHNC?!5p+lSUs56hx&;1QHKX}zaG?4R7TVOIWL@v zDRaLb)E`sEu|8&E%KWhh^&FLPtdBZOnfvu{j-u_N@4u=2+vZZuA;~hXAHKx@{m=jR zpa1jmJ7mwU-utkOcDL5cXfyg=Mw`?1GTN_tFQZ-gdl_x)_cEILy^Kb^m%*4`DANmN zdU5xa`RA}RgRydUZYaxOOl^k;)(2y1&v{rMjH%Tj?&C_CUMbTnWqPGduWnA4D|e+# zukO0u>w_`9(y@P|OmCFwjWWGarZ>v;Mw#9y(;H>#&#cd>`%}8}41d;hFN0lA{Rz3f zKG@jzr*-!FU}N8(*w^cWjeUQvSFaB?_Wfx$c^~$F@zueftI_L&G4-br^!mU|@imNn z2lNf`XUD$-_%qv?B=}lm8CXO66=C1q@7kHswLb7X!!j@j%fKv@5oeKq$AeXn-*>I2 zt@>!>jd~p(c!p@-MHx}sbMe4)1gj5a#QOLd9_&}$@0r%SYO9Z^+)O<9oK6{0{dsu! zJ;L&_uZ*U>d97#Tf$vt0hca4)oR0^)SNFTB^{z1LBUVry9?XaFd#3f&S07RRnRqZ4 z&hKW{s}J=N>tiM!%>DAanf2;JeZ>0s4j#<8+Nsy4jHb%-zF{V&%(>dB*QbnQebiyf z+^?NJNmRyB{h63De{84Ek(F_*k19<49%1>6O&L+!v+-blq2EQUS3&Bd)ll4btv)g4 ze%%v- z@nG(k-y^J7AL=94$4oq!`{nmt>(z()i1ks22Xnvtu4+B?)kjo+CLYZF^1G__>O+0R z`l!Og?-7=3tBj`X^L=pk7S>$Em>cMKX6sdu`e-#|I|_UU59Z|gJ=1!+sE?@2Ogxw` z<@X5d)rb0s^)V9<=6?BI)q3@zK4N{;;lbQ5zh_!cef1I5pNR)^zxj6GNSrF!-F|jc3uTjP8m_TIy{&!W&3zD^_3CTpNR+a z$KqL+`E^}=#QKeIy{&!b){aPGMe_! zdErbZ4VN&G={H!Q8JabrhA+ zs^dAksKWF{9YtkCZD-`+zoFIdjm{TubWWiRPt};RIYp%m_WO6EzmUo})<+$t?APr^ zXAH_Xs{a#A7y4_jjHt`mc(7+(3tfS)jAI4WValFlE%aHJGLGuc#FRbjTEZSDnUkc9 zV|~oTls!>f!Z~bteW;ICA@)?a4iEN3ZJ|#omC>{}A7(Bd?1|b!T_
*HsbGUsZc z-j*_s%GF`Ye5r+ceabkhKNC~tTrJcM95dsV?4B4usWR5!C}upA5y$@7czE|KuMcIk z3bA#X=i=f0vAjN%5$j_n9^U=R)mKJT|6Dx0`<2&+GGcxF3=i-1<+>;%>T(_){vGA_ z+EBFB#UFC_G$t!NKULK0TagBvU$z|x-bc6EdiBSofoG74dIc-ez%xKay}t9&!1GK+ zz4{et_$R*azrTuleJj%N&xPOh{rAzw$34mN_T=mJyfTlzo&e_2wyS$D{+cEC;;(sB zFaG+K?!{kM`Cj~W9q7ehb<~T$RO!Vry|!ap-oEW&)r(_(ZHJm(d(5xxEz)a``L(?T zdhId4_O@-WJ+8m@#$Mk3_W8u67svH?`&{+fYme*i_PH*u*B;kjdvC1Q9@k%c7bkDu z-ht@Fas9P5;l1{_{@NPIUVB`BZPi$>J+8mDdZpJM*I#?$o40RI{CaU*e=DiK^>Ynr zuYb&M{alyVYmfP@pX-Bq?J>XY(Z)E&#pKmSn+T;4$2)~Vt-;MCwK3C86J|7;x z+vob4y!}r2&95&WKVPp8RzHeAJ;S^{H*)>@{W$*p=GO%ZD#{YU46 z=imJIUG1^{j1Qh)^7)h6WB#M_Ve?XnVu)nwy z|3~ra{IGws6Ms+f>in>OwiEwI@#_4rKeQ8nUh#j;5BoPec|M}}==`uhvy>u5U|E73#e%L>{ z6aP)|>in>ObSM6s;{Tc-_IK{YA5*+KKkOgfiT|ef==`vMbSM6s;??U_L^lWQ;(@&_ zQ(qZT{ZV*eSIU%AMpSMl9@uj-^_3CTKNAnrA9L@CsRmY!?(KHti=8s*dqo|Byebiyf{ILsl6qRvQevDW@5^ms|)q|lyR(&nV2$v>_QzyWgP3H4pZij#dBWY*9qD^kosu)&&4C2 z;+v_jjHbOg0%zmF{ITl?6YM!E<5)p;h%rYop5mQfKh#Il->x4s@nG)Pl{$*bXw~uj zefbWi%$K@SuTL3AU1nm+e5ot-`jm03kC~V{7q@lPp4j{u-u=qItuos6 z!Rlis9^U=R)mKJT|6Dx0`<2&+GGcw4i--5e^7>FltdF1Iu>`L#(?uCg6LV&whX?bemauv- zS6_WZ_2=QSQb$o4O?#Wuos9?c$5!f~DdSi{b(k`LYz=D^vtJKo9MzwRDf7qHutqVj z5B1S1#C~69;=vrWHLPOH>qC9S`WS@=^R`y%7b>GE`j!j$<^EA{%6an!aBQ|3#p z)VWf|QT>^iGWTnxj-oP-^)VAu=8vt^b5zE$KB_R?sH3QisO{N!F!yVtj-oP-6;y{Q zbH6s~C@SNq{`WGqCxZSj*uQN@`{qmaGMY2d%V_tvy^MC3)XQiy>0U;gOZ76^uW6pK zyI-+hMjLazjHXL3gE8HmKi2DmG2Pw0dan=0baylQULTCh$jJk$ZixI=#Dja^A;-GJQ~{56bjG$NqydeNd(kTBi@n^g-+NL73Wp z)9p;ZjJjpuv2Pi8>{|w|Q_H~DQ_H|(-!gEWS_U5bmVxWkGVs{99jO^pf0kZO-JcEC z%V13XiAudb7*l_`ORo>c)SvLs>w_^h?ysG|^FI7e;Jpl1r+&ZSULUMZ{obWnA3GUO zI~h$o8B6R}bSLA8{etdf46$EN#qkxUJ|8@mcXItyyf!~J^Hm)GlGW#f=ZoyVNAa)n z!?PTASE+b)e)zuNPUeq_SLcWCP?#g6cy)gGo}T%AidW}{U9dZG$rP{75BqV`_ zKkP5viNmdUb$-}CV$azW{~AB`lu~i*f7R!M{Tud-TJh@quz$o>AShm)ANG&f`Vz&f z^TYlTTRo(Bb$-}CVr#<`ug(wqM{MPv;??fwQ`CWQ;(`4qQ(qZT{d4ia{*={+GGcwq z!~?riroJ+w`ZMvs-ju1YjHv!7Jg}=|$|)l%cP<{-wX*t9My!u>@xZQ_)rT@-eayqd z)J3}w*nSSm@amt92lETrjvp3RAF+aF;=%kew%?0Yhx&;1QHKZf$1c=SR7TU@cIf*l z9?ZF7do0-}RUb{eT0EF@Wha=hd7(0*`ZMuh-WJ4R`BFXQlo6GiiAVGLdg?19s(&sX%?<3;hcaS)%*3O)Up@7e5!F8z zkLG^$>O&c^KF-CXxnI5dP)4kenRqleu&2HgVY?eVysetqsh_ ztui9@v+-cg)s1>v$~acgOiY!S`2=8xUn8pWRa>LaQ@6A$K(-P{VqUVW&KSRXU-VE)+6tx@dNhx&;1 z@f|#vb9HlT1ADrtkEqK`JeV(aqh6mfT6LJ$SBJ+!9YtkCZO_JoxnB!)6qRwTpqZF5 z_iLg4m@kwNOV<8OQpVi7E5P7V0@F<5(Zx!Ib$@3-$Vx zanz*_Q|3A?)X7uEQT>^iGWTntj-oP-^)VAu<|r=IQB=mUKB_RaCkU^dZ1SfG%81&Y zjR$kTR_Z7!<5)p6F=g)8N*zUI9P6VFQ|5lH)KOH%QT?A`%6zGndVR_`Dp!XobDdV| zQ5nbjn29O#$5!e&D&trmb(k{uYo(5&GLGuc#FV*TD|Hl=ajcIj zOgHK%DkExpHXh9V+Nh(bjAI3T2UF%cZPdwA#!;7FltdF1Iu?Md&(?uCg6?@nGY&^U#mDh(dT7_7B%*4aHU%C3qi0Yq~kij%pcps8pZtjp*~uL*z9vA9?T!x z-5SNm$FuE5;`uM*(Oi~ZM!V0>Gw$vlxtG!A{Jo4eFYINsnL#h3{WkP6+SQ?#(dwg@ z(Wv(_7}L939hUd;piCd`KC0ITWBPE6J3QQl?kR^h)dWO6%00?UVEH z=dScJSe^Ql6?%QJI`uo&_xfOC-|uVP>x0#)-($De2dh)R^JLZs8~JS9+rFh}9I!FZ zMm!tuisS3yzvqLi*k-S|J`}Ib2hUH~Z>{3h`Qcxn3z?lN{%`s5c`BR7Dvqwtohy5kC)=2Tu`C z^TYlQTVtzub$-|%x{>v1ir41H*1s!`{kQsjuz$1=|4s4g{IGwtkaw^Yug(wqM+@=a z6tB(?`$r3Te^T+U^27elLi{nstMkMD&O+WjR=het>>n+}e^b0VKkOeZWZwYAtMkMD z(L($;#cT6h$v!EHWB;u_AM78k#D7z~IzQ|mt;By*{Hy%1f3p(*OY!Rbuz#}>|4Z>o z{BCc%hpxe2Q~bEQ>im4Xf0XI3czeHSMn2v@%D$iCSpVvLynmGGuQ=AfIv?*JW%?_Q z^{>rm3;x@?{)&75ZA3oa|H(d|;%NMC!C(9he%`;y{=VW^zv_Ivf0XI3IM%;9AMYP! z`YVq0ug=G>-^%n?9P3}55BAr#u>LKp54FejF*+aYA8ld%Tc*F-WBo_xgZ-l|tbfb& zS9`4g=zOq$w1xF=nf_{z^~ZetN%wY=-tqaL;@JPH&jin=jJan(Qm(Bsn!Z-+ zqww&~P_CRZqH;6w@V-*6zA~cv=i=dgtGqsx5$j_n9^SRe)mKJT|6Dx0tCiP>GGcw4 zi-&i;^7>FltdE&^c+V?WUl~#Td3e|zZd;L&sjrNt{htqSY#biUb+XUOv{gn^*Lcmu zgE?0h>TM~bRmXGe&%~7ZW0$a6FaK>&AFV>{>QRRW^T#e>tzWLb`iSb!#Dn=`m#~&F zuMhPR>tiM!%t5<^wT5|psE=45b$Bp;>=ITQ=IX1DsQyp#u#*^hk1Hi zDC6mW^fRvi<0_zx=baYHc+Ry^#&foXGM>N4DC2oeMj6jhi87wbp$x|K`adi4`hDCe z)7$^ty`nxC)7$^dU{N28>Fs}J2B;6l^!7j357Y-^dZSDi%5> zu8sO&b!wy8+#b{itJ8&!{e?1JDbtlQT`AL*GF>UtmDcG>nXa@>SITsyOifd)?d#;x zzWN(wx>2SZWx7$OuQSNdCuMc|I>!k0!G5D&XN~mxc%3$ZGT8O>wc|hPgI!NwyMm)W z*w}yVER6bK*VCQW>1+SU-e0+XjC`!EW#G?Y8CcuvN2TNOVi|b;F;WJuG5e&-X!F?f z@xZfSthricur@^DI+R36Av~|zS5brGFo-~ z`4}y8@nCmJS9%|%jAMP&Vao4-mC@9-v418W>{)@`5i*BF8LfWo*JCao%>81|l8lG? zXcbb62lESWAN7u&H`upTMpS<$9?TzOPl>HQ)JLq3@8H3ls~h$Dl+jdq{;JQ!lsQ*y zWrmGg_0cM1HXh6$yHQ6`8Lc{=*N-|(nWMIeBN};k~}R zK9tca#Oh-v9^U=R)mKJT|6Dx08<^LJGGcw4iwASi;?6C31*wl%L3MaAe=P3GldG>j zqWZJ&@GA)3l~=T>{wJ)q_+D0cuBxb4p&|`78*Oj?yw{c5diBSofoGG7dIc-ez;iuC zy}lJ`;Mts_Uf+r|@DpG~y}lJ`;AgywdVMR>z|UwE_4-z%fuH0m>h=A1G+yWIJ@*oR zzY|p)`(gF@FmFY1S`WT%L_Scq=UHS3%Q@l1G>>n-vQ5@@Aoe%bpmj5V@^{>tc`$x-v z6vz5k=Y##Drv3Z;T=DAsuz$1> ze@^l0{IGwt5r0nc>in>Ow2}35idW}{{iBVnpHsX#KkP4U#Gg~V4!_5TmdE$wH|M|Q z@#a6|@pk{4#dmjqnaA7wIghvbRUU7@zj?e}pYwPdzj?gro5!0!m&Y-`-T5n7`#a%x zclT#`d(7|d=688}%xA$pTIKk7`6;tg_eQGv1Q;&v<%GBGB8ccz&tGjk7&!l zHECxyGN%4q$DF!98L^kanEKPzdVMga{)DDpAB?F#MW)vWW9m;@$ouen?e{WRo%;RG zdwsAv^?N4w`e1eH_kHd4!RplS9hvoE-xb%XW#F-I8JMYM;5xMo%+xY)ohl>F{C1K?f-nt zfX~K*-4*zKUwRd!K3WY~1=Zof?)VmZPpFKh{qy=U6H|7-zkJLdkn3rqK^d(=X5+!! z9>1$k@7F_p#QLbigE@JAPoJLp>LaQ@6A$JW`aOSo^`Smuef)Pk-p`q^Um)*XDMLJ3 zg*|7m-nq)_Lm7>kji__+@cvj{AIgaJF%J*F56$D_m!y5q=fCWkxqlX|jI;6Z?pLn9 zGTNxI@iG$+?|$X#Dt_JlXP@+;c(ACn}WK`PqxvvZtLJ&zg1GeAYXz7=WU znWUm#--a zs6HR&ttgJ}UE@v_+4vcqA9h#bJ{#HhQ+r$=qw~S;%Y}G1idW}{y_>j4PB#A49*_Uu z=7YVPOV~Lk(^u`WzF*~oy_dMZRHl#GV|_;FgT0vxd9OtA>in=P6!(V9#=qL*@&DU= zuq$*4`^04Wsy)_sY(8;c#&>-c$NpMyK-jrq4sF}kIxVLKi9AqOs2ouWBo_x zgZ&}fDGq->#s4iI?9bSH$oTIoJ~kih&&1uRv+J+gV|_>GgZ-at*nc_GU+uB}qw~T3 zP~1sA(_ihe{-g83{?C=}GNSfa|Iztie<+>;k&S<~$NK*+pLj;cyMBsef2}?r?2pA0 zTC)03do;es=ZF2Dc>YeNzuIH{zsd*uSMl_tOdqw!`usK@?0?0xt1^An9_u?gAMF3c zlgTpu)gJ3VIv?!+#PiKE{nZ}pKRO@m|HKo{?r%F=D(?A>$jAFT+2>Qdjo%shcz-AR zeu`uLYx9XGcfIScxcAro1t0HEW&JCT#$P-)tRg?}zhs|ZajbuJKHlHS^j93~U!9Nl ze=_|Q$NG=X$NM{(zKUagtMl>xPNu)&SpVvLu>TX!(aP#W?QwnlHXrPd#Z#^_ebpZ8 z`&B;JpIO5DnVCLnkM;RoKJlEWcl{K{{#AWG*dL4ML}m4%_Go;M&ky@QYk2=M(_ihe z{-g83{?8iTzs&Skd#wL&^TGbk8s6W`^i_MT@92E6|Feeu%`*Mf9_v3kAMF3E;r-4` zf3?T@|27}&->hMOv`k;M$NGMi5B6Wy@P1{ckJ@8>ewz>WZ&u=uDPEi37S2|DAHRxY z|ExYA?0;?Hob{|e)E-^m$LELrosIZsijU3@`!^f$#}u#55BobC@y`^m&JX)L8}ZK+ z|0+N1uWZD>QoK4p?7wWp-%`9fKkV;p#6MGfbbi?X*@%Cpcx`?=@y`^;{#kuK*#Fvz zf2R28{II{X6Mszc>in?(vlIVJ@qf(^`!hT7w-g_pANF5%;$JCVogempcH*BYUY#HI ze|F-ZDLy(s?CVgKh&{IkE0 zUq0^ix3~Rg@1OomFaEm!?ZsdBPrdkSe%*_|=3l+|>-W1Ce_h}6_~Y~X*^9sGrx$CHJvfFoaegP9`y@ldZA3MZ}wLh(+g#Kp-eB7X*(yr$D^H; z-Opf5+iAr8K3JW$6I1(rFsAKP#(p2HPTR?D{XSTow$qV%eYEp&`WbBOw=+=seXu%h z=PdO5U}L}S#oq6Ojr|)P`)$YI-d|~Zw)Qg^(}j-xg^vA&Tu*JZU>=r%Ys}7n#@9m2 zz~k03Fb~VX<5n4e!rbuZc;Jz3pF*A8L>WQ;(>p&O?_oV^+(}>=clHe zGNN)b@nG}98=W~SqgBVBkNNFfJosIKGMfIT{+W2Ndt~!i*j=MCTK(AdqY@8xzt0>J z`?l(%=|39}=JqVq4^l>}j_1{(4pZjjG4InxgZgOt&&GrKh0OUj9_l03$9M2xz7&7n zpp2%<^Qt`)Q|4UR`W5uF+QzLiT7}HUgZX3atf2h4sqs)Bu|DeXV2)xtNvN;B`iSb! z#Dn=`?IfdqeW;IEAM@~N=lJy0S4Pv`=9ZDi9#)4~W~~hG2Ik*I8BKrF_FO!?`<2&+ zGGcxF3=i+q<+>;%>T)g~-j~YjLm9C?&c(y~V|jfjBi6?(JpB5AcjXmrs{aXVDdu2> zXRnHS^()d~v(NUN;Ju#J)~i1z4Lplg)GJt#2A+i~>h=A1H1J$cQLjQp8vbec`|qHl zUf+r|{L|ZaeHHckR;1yd&%W!csMoh54gY-gU0+4Lz7=W2eO}%bRvi0q_4zPwMRDZR z#9ffG@iRIlroY-_{YU46U7xr!Wv0K{WBo_xgI%Gx?`WpK+GG7k=Yw6NxT|cY zzuIH{$L16F1b)|7aqPd<=Y##BD}BpB?a}!EIzQ~+#QnIl@vHV&pV9eX|Hk$`!{1Nw z+I+CTW^e4{@27ZeKG;99_Ym>-Q@l1G>>tH*FtXo&wa5C8&IkKP*RWqproY-_{YU46 z{iArkNT$EqWBo_xgZ-m;dQ7Ij+GG8{#wVW5^Uhy!?4Q-=gZ-~~GE-I`YLCX}`24Vc z6wlqt^jCYV|LA#^w{x z?0VN%aqPeSET8+^9?9|V|8L^nKg-%H-p2Qge7rxDeLuyq{?++-e<;&majbuJKHeY7 z^j93~U!9Nlhcf*Y$NE?2|C*2YZ!&!p$NE&~)%ke;DAQkY ztbc7j@rCs%{}xZt%D%taqwB-?{II{Yew>nrzn|i@`Cxx(4ezgJ<6rHu z{-g83{?Z!WU(NJad#wLg`C$KN4eys``lvnDXLLT;|5^W|IM%m1AM7u!;r-HV{Hr~# zkJ0&He`)=X;#lA6e6YW?{zq}Fe{DWnIN9?3`mQ+k=j!vp{@NDyf6MAa?a}pNe16zp z+lW7>_*eO1|7IipnBvv>VgF_${+Qy``C)%(BmSG>)%junXe0ic;??wfXJDe^VU$Z~vYT_P2K8k11ZAANF^4;*Tj_ogem>cH++| zUY#HImv-XMDPEl)_Lp|z&naG=ANH4a;?F5wogem>cH++|UY#HImv-XMDPD)){X@$? zhyQlxzh&{e^KbHayZ_DO?fxi_xA}7(Z}Y1>-hO}cc)LF5@iu<*c+)qJH-9dRKM22v z^H=irnBT+QpXKc_zlWROiV+hcwYQh%2Ze$64v{(@!T8ng^d(K2uyS_UR* z8MqcL1Jkq&T#uH4iCPA($;$^X#?*3N>%Ma87s~WPnO-Q<3uSttO#K<}z3;-9`g5Z5 zKKx0!y$r_GpLW{ogVm`&F|pSNt5bjKTCWdQr~c%oULUMZ{pl%rAO8G|UIrWc{tSa& zA8hRVeb9S-u(9v=QttJ^>eTNCoA=>&r0iv|Iz8Lffz|roTw%VW52pTw{x&GX&w#Ct zXJX2(r~Fq;8OQpVhw0zUP}saseZ=~x#Do2+U+J7*8AtVhhAErD{>^=Z`e@qOy=xsF z{EklOOUFnlVWi(}qh-CWwh$BEB{q8l_ zK4#+K-LG7IWkmJQ#lyQ_d3`7&*2kH6tYH_LtUi>{s>2+#xp*-5Yo(5&GLH2z6I14o zt<*tN#<4!WgDLZ+*09nozpkr~ri@+JXX3$}t2L}1%JQ#_b2wNbB68As)2V#<7}je32`IMzoUrp*1?s6VERqxv&3 zW$xET9Ytjv>tiOS%>CM^qo|Byebiyf+^>x~ipn^uKNC~ter?oIRK~GBW@5_RuZ=p2 z$~e}?cQ9qX)JDBNWgK;>!gQxjo-(4gXXC-#ubn!I$~acgOiY>kwNpn?8OQpl!<4yS zJ9QM5aa4aMrp*1?siUZjV|~oTl(}C!brh9xtdBZOnftXrNd-WgOL?i79ix?$l9K#<4!WgDG>J?$pUs#!;7X*;bDsZ zfB*SEAM=CDhi{x+wUyDdw_mZd@o4T>uRfH~D#YsJTs)fl)vFI>#QOLd9?h5P>7tCN z%eiO&c^K4#*9{V`Kt8BzUn@xcC=)rT@-eVmI2cE7AX zlo9J=CLY-RGWC@a)gOfi_N7cYWklu9#N+azKU!aS{cx0&;p<~A9?UPiP)AW2tvbvt zo{IM&*g*o8WZ$~dY&6I14oU8tj|jAMPw#FRN`b}BiWeJZ0>h|MlW z<8l4?4YF^&v@Of^)l=Z_gQ28jMpr-~(^ z$nIynwC!gwrq@pwuHOe^di`_+dVSm|)7$5LL%$Ek^!7Qs==Z^x-af}mzYoUrMw!|O zz%_QGOc%;@p-h+0*?8~UE|lr=`J3JEgVpIm$NoZ@E|lp)nXZ)SN|~;d=}MWdl<7+9 z6ko&G^$XP|zHZ_1h3f#1D}3$8;|X8$n?sXVaJxhA#qpJ?-P82iV`}X;yw@I+yO6PC zZ^$FXZM7nb^IuF>Z;T)N3+5T%zhN2tui)CYKA2KhGA^wTrj|0=4AxfC{}c~=g|W|} zjHb+NJlHkxO0Sa2Xw~r?w=*%tzkxOyl+pD6DIV<3(&k=lF072En~mGKc(8dPa~_O` z`e+q08xM9@aQnEjqq`sDp^R7`b$GBlKISQ!`syR9KNAmjzkj2SfHGQjJZBemm}0-u z#=bI|y65A;oV*+L`jpY?=XrIQi7E37*^@#WQR<^r$anEzz7%^tYo9}XL|ta$!JIty zbl&PieZ=~x!h@}=uoZ~RQB+3L-hS2R;=$ZNw(iDwsE<}5v+-c=7h82@Jk&?5k2*Y< z`^8q&nfmG@sy`DC=6~X}QT=oA@a|V$AIgaJaV{R-{mSb@8L>X*;St{|%G6gz)872Tv+?k5U|t`} zXcc1haV{R-{mSb@8L>WQ;^Ez|TzzFk^+)01eW_eIWkls>;=!D&_zrhoAL=94$4oq! zKemR|gL!?Zk60gdcrbr#4J-e0_0>mIeL@DXSRXSnW$xET9Ytjv>*MQ8ck1;iBT_#b59Ukl)az5mv4ZL_ zW$xEb{V`=6)t`webH8@#C@SMvA2Ts!?$=HoMP(f8qYhK%e(lszRK`*LnV2&7Yp0H) zGLH2z6I14o?bLHr#<4!WgDLZ+cIx#hi-N==1bkF*Qbo5a&?$8*Xd53JY^i!pNT1RzwXpgRK~GBW@5_RuRC=Vm2s?(Doh{L zQB+3Mc2*vC(u@D5_V3Hb$ZzhKGQ=ZRi1BFdSFb*l(Wq4+_BuDar)irXE5kHB7mqgk z?WwPfIOfmAqs@MM^`VSdAG7ede#|1<8H<_v%4o{lzh>is?-%UbDx+1vNIdX7-9D)@ zqH^cr(VleouItK(^)VBV_8hyXzA~cv=iXj#iKn>@70GgVtvfS1N&n( zw^T+{|6DwIn zxw&O8qx};0GTPO$m(j*cFQZjqFM~0?Id7}i2V;73_u0KZ7*liIU%$6`AB&q^^fDOJ z#a*>~eK4jAt^TYFtjm+2;|0+Lx&#;mCiQ?7y;raPS z?sgTg&X3*qD~=qOjog2YAIJCC8@Yc}ygEPZ-EG7lP`o-n?2m24|53a;KkOfE#D7z~ zHou+tZ;E68?cejk{?1PPF~zI%!~V`r{4vF=^TYnqPW(B=tMkMD(oXz2#jEqf{@YIc zC&jDt!~W7v{5i#|^TYnqPW(B=tMkMD(oXz2#ebV0_J?-juPHt@zdP~I6vzHqeLmP< zvNh4@`SDos>)V@5@$)HueADY5{I`sc_n#D>kDvFKGJO?q*S{J0cz-GTeu`uLtMl>x zQl`J+SpVvLyuXy`uQ=AfIv?*ZW%?_Q_5Ug#@9$*%703Lm^YQ*rroZA?|Jr;W!GC+# zUvclhosp0C-?HzoIJ!POf`3_&ANJoK#J^L#IzQ~cJ;M6AtiIJAUmr&2gZ-sPSU;EP zul88~(fMG1=@Hh?W%{c<)}Qgg{>~$;U(5KbJ?1|;AMEcu!uqvLf3?T@kIo1COOLRA zEz@7^vHqj;!T!=Ctbfb&S9`4g*nDjNPV7J_Bd&=#9}n!n84qQ&8aW>i>_8b0WyJcJ zi3j$VOnqfU^?!y3_I*qjWkg-h#RL07Rv*fU^>Hp9*tfF!P)4kenRsB=%G6gzRR3H& zu&ZVDp^R7`=i-4~FRKq_#QKb5se{GUN35Xl;K6*U z3w838(Ny{K|EhE*rp&pDr?utdR(-Szv8&ijJeY%ap`N2MT6H|HA9a{Ae=MHGm|q># zN7LV~4m0s!{@8^&ippr!@w__B#FRN`@hsN-`k_8rh1m6@4iDy!U8tj|jHdnb>M#>i z=8wgbmh-EF`e+qmSBJ0ji04;l)Robg+o(Jn59UiM&*Q*OmHX$~dY&6I14XU8$p}jAMPw#FY7CSL&cC<5(Ycm@@b4N*zUI9MzwRDRaNB z)F1nejN98T-*(sNzf1KD?@Q(1MHy{en)>JB;eDyRK9mvbV;&y2ur@GLUl~n%a}>|U z!@FO3eJG<gRc1S%)d}$8OX?Q^ryKnV2$v>=xF-<-afLqg9Bx z3iI$-sOPARroH_(%*BKGV+(cAlyR(&nV2$vYzb==vtJKo9P48grp*0X!V1J(TlLY@ zwcmzOcrfQ`39AQlZPiEAb|xOo+gifv!Mr}yN34%JJeWVWgw=z&`syR9KNAn;el65d zR7R_g=UrnRrp*0XsH3Qiqxv&3W$xEP{V`=6>ti0KD|Hl=5!L@G9?X|osn@5BqjEDb zWxmu(y*_0e>!S`+=3K4R+fv3+{h63D_iLq&qB4&4F%whfey!9|RK~GB>M&*Q*Ge5l zWgOL?i79ixR_Z7!<5(XvF=hVPNdu@Jh`9onkn@&UcZ(7jMw$FpYa+|{S3x*qfB?obpP~WdY@zeyc6$dFsA$G ze7)ZXW4eF-s`vX~O!v=`-S30d>76pYQ>J&y^!|AV-20?=%Jlv@3-0&9>h%8kTiNe} z)#;tq>4P$TP^J&c^g)?EDANaJ`k;0CpiCdMPTPs`xh}T<kja?Zey`7cHha|D*)9DH#pWZM(ep z`(RAlUeNtM7*pepiM5?c^S@%>1pgJ=p&S1d%fQN61|AKTft9liJQ^$mD|fyOJob%; zGTMy$d_3?~%6KRv*2hdd@UOb5uZ*bvC_MOYwlbn}^YHkayJ$9JQy;B5%wwC22b+!m zjmx4wT7_7B%*2D;i~WtqraoeQ)ZxMIv;W3FRUc9PnRqal&%}c{S9j|5DWg@#bKK6vl=)+P zC4w@J^-+cC->e~Fj-vXA>d(c4xnF;?#z=j%3bB)o>+oRS*59ljQy)?NnRqbw>u**M zs*hM7Gx1>V*WauiRUffFzJmwzrT%8cuKI|&%*2EFQh&2vTYbd(sKbM~Uw^X}UwuUN zXX3%!ufKT{Lw&^hn285-zu0>?c8{z+Vtv%$Veh42zfc)XSNqrbcwqO-cqpUQ$ZR~Y z`(@wuycv&=>p}eQ$m2INyf2l14rMg;Ou3nOc-JXcUl~#TbMf%*S6&~=i1l$U9^U=R z>q8l_K4#+K-LG7IWkmJQ#lyQ_d3`7&*2lScc=s!>4`syqn1@H)KPXdQ8BKe06n~0` z_vvz7l+lziUCzbBJ9&A1C?nR#xp**t%ue!dyPV|}q>NZWb$Bp;EbiBrtFJzy`ZMuh z{+R8L%&rc~i1jfO59W`>y*l&jhx&;1QHKZf$7~Nfc6CrjRDUKO%pZ%p@a9(s^%3ji zJ9sc(%GUm|ajT4|%RD@6)dW^w8BKfh`sU)n{IR&Jd3M!S#<4zTV#@q68xQRIp^R1` z#%m@X%>BAjM^PEAI-b8Tb(k{u>l)6H$bUW5N7LV~4Kwjz?$?z%ippr!@w__B#FV*T z*RaE3e*I7%twQYj@f|#vFLk9}pE8;%&v82wQ|3!u!w!e}xK$smLTudD;lbRmD|Hl= z(X@YF9p+(rqmH67qWW|3VD8tAuE|rzu|8&E%G@tIJrg^M$~e}?OvIS`b)$}=GLH38 zhbeQvZqy%B#!>yBVaj}|8}<5>aa67jQ|3C|s4u0Aqxv&3W$xFFI*Q6T*2hdtnfrC4 z{+Ke3^-+f@bH8rXQB=lJ{dt%!)KOGMRR3%|m_N2q&ruo23aZ1DxnB!)6qRvQ|7Vyo zUuvOVpE8ch)nUqfsfBud$~dY&6I14XE!0s|#<4zTV#@rng?f(4IMzoUrp*0XsH3Qi zqxv&3W$xEP9Ytjv>*ITw+PWwI7wq5m{zLmK|ND&Qe)alLMq_W(&%|SOj$&RP%4pSL zqw=SCG}o!8i!z!rrpvi_G+(M$AIgaJaV{Rs{p!_+GGcwq#G|=iJ@u6l)jt=H=6?0+ zLm9C?&cmbagOt^VqOC6ekh`ZbS>buIqF&#MG}t`%^-fVXy4BXJ{}mc|HmRuRT#*Kz zFDmNwtw;mU_Z0Q|R;1CM?`FS)ih6x3(r8a`Gkq2H`c|ZYpN%T&^{q$)KZRA)>syhA zKPfJ|LMx8lqkqqbc^`@+C&iz*m)G~`{IL6Raqp7k-%ssveT>cryE6WSyj*{^$NG=X z2fH@@jJ#Zbwa5C8&Ih|X{tUcaf3?T@kIo0XKK_imTz|F4`j5^ByF&hyyIg;@$NG=X z2fIf86uVr1wa5C8!)N<=)5QBp_HTb0UKaPKf93IZf1AhK{ZAfm^W!|;=1+ON{l4b$ zcKyxcZG7hOre7X!u3Q$kG4raAJdXMKy=&+n&@x5xG8-?+}(h?6q z+vECM-8;>Bdt863d%JG?c<1YQ{af98U|D<%9_laaAM@Ko{blVjzdh7n)*kcQN&W4l{_cd|o$#|a zrZ6GPz%^zWn3DgEduQaYFz-=3K5!I&Ge!N?ZcG}u@)Y$7&PM}ZRTTB=SERw_9_`NP z{dYlaz4~9F!Dc8(1-11m{1y#72UpZt*J0A_d#w+s>6leFBqsQ?buwO%# z>#z1`jxs(!>|*#ecDep)kM$p&5B6UC8oOM7wa5C8&Ida;evMtOzuIH{N9TjR8^6Xb z*I(_i{$J&T-4(wEF4srxu|A{o!M=`P1DETs_E`VX`C!k;uYt?;S9`4gZ}Y*PQCtJ} z{v<;2+Wg`g#&>-c$NpJ;KG;9I(ls<{kFM|I^TYnom8>ySygEPZ4_)aBIkm^*|Eqkk ze`BXL;J>eUZ9dq)vGu3;`zcBVbe%Qac5r0ha z>in>O7Wa_I#=qL*@jp5r?4R9;|E73#e%L>Xd%$GlU+wYu|7||lAG#5LP4VjduzwWy zXv)U7+T-y(Iv?yG-H89Dcx`@h54HF4tvL4I{yiV;@5DXsGX2yZU7yG2hyAmKtWQ(C zIzQ|m#XTys@vruH{EyBD`$G#^|E73#e%L>Xd(39zU+wYuADs{OhZeH_P4RK~*?zZv zw<7zu-{V>FGxBNvP_Dn?uj}{k@M-=|{`VEf`qbv*_sGxmSG@USbMk5aS^oVLN8^8W z>-TE%YyMIG`4z|dSLf6Gp%Jo+q>pwc5<`3oiDvtI2 z*L>Rgs$3t%u|C!LVE@aX;g;8j+T;2doe%bp{26_@{%Vi)ADfRqV=>cLaqPd<=Y#z< zf5v8BA8L=r|M>i{f3&&vZ@KH5dTf_>in>O^a%djgH-eu`uLtMl>x zQKrA*SpVvLynmGGuQ=BKt9-nFlkry^^RLdw`!|{Xievq2^SONZZ{A^guK;DlGkwm- z!#hlQeJG>Vh}Flrcz6dYuMcI!`k09a_MdDtC?l$WE*{vwv-(g*tdE&^V0X&YS4LF- zJ9*gY=lk0;6QllejrticU!kAzy7TR4yzY&98TLt@cUS$4*IcTf@%lCGXS}Ys{fyU` z>u0=l>1QyerUm=9jOpcbJxcF$Tq)D*=lrza2V;8u{8jJw!I)k@$9}&L#`H>=UO!iG z_5TX1(;H=aqfBp~PqKTT<3^d@K7T9weXu&c(XoG{OmCFwjn?Txnc8>6<7J^t7s|Aq zpx$HJ&fxB6usUt$0QdV~V}GGc+i8`(ztYa@>u0dBzfz_vt<#l`{gu|~O6#Su`+cxFZTo%p`(Sn2_KfTG(RK~%XE0)IXQF-| zj9A+}rQZi5)^_0d?LOG-qU{yY|D@`}&&KB>#>cHPqWb6J!F~zbUK9Q6hx&*WGzO2h zOF~aMWi;LXeB5_b;=%5c+8z;o_0>ny-_)qC9S z`k09ayGL$2T=eTheZ=~x!-KiSZGVft`syR9KNAn;ezpBC`t_kcVtvfSgZYJRe~f;8 zsE=45Kf{B0TWx2HzH;g#Dp!XG^QGFp7Jc>AM^wKGkG5w-Pg`X)Wz7vd8xQ7wwOu#* z6{J2|4Os=v#Dn=`ZC8$deW;IEA9Z*z_p9y6(N|x6MD=Il!Q8J0T^**3RvpjzM;)fj z{d&-qf66$j|1(UPFZG}+GL>;ut`1Y?Iz8xWTV)*8pNT2+wjT7I0A(EOVG`d5A1#!4`syqn285=zf65)MD<7E zfqf}cP8m_TnRsAd%G6gzRR3H&u={28p^R7`=i-6=F{=+{#QKHp9%%{6jCr=rzexCD>I!u{A7Ed9{uOI58 z>2I@(nRqaN>>Ac6=JlaIVtvfSgZX3e1hTw7)JLq3@8H3lt9b5Pu8aDJy3E9bIak-P zdN8jK^%3i%3XgbRW2UV#nzA;dKN}C`kHzym^9oWQt%j_EX5zsdw0N3pULWcs)<+#4 z%pZ#<_2%lUkEs4kJed0x&uPxv(fW$t3H}` zHtVaygSk%e-1}U8^%2#di3fAPZsC38ygt-NtdE&^F!$?59Ytld>UjR{S7Ex)HHylJ z+MbOEbHD5?1iZ>s8OI8mi5PRgmJb)6)rT@#h1i;`Iy{*BwS>2xv$>@*n)Wt#_$eOD zms;rRL1i43tHYG}QVaF^lyOvlCZ^2&TBtv!jAMP&VanXECG20A|EjBxroa8F&%}ed zUkh~r>IqRE=DRaLT>L@DXSRYlGuGCRfM%4CfJed2nQb$o4#|rumrp$F(sV}9B zqb@TsWnSM(y*_0e>tiOS%>7!aqo|Byebiyf+^>~7ipn^uKMPa550au@_lh*|>{C&% zZ$%nx7K@+nE86rQlO&#nD%$k>L+)|D!V1szsz)DhdyV^VbcU#(&AoqLMg1tNNW(wh zeb-k}uWv;f{t528zKVK%E7I^!VBhss)azT3hJS+kuCJnA--clhOGX2#a z>pwal?D|~7J0+R^YLE3Foey?}F5w-COn`6rKKetut% zygjZzzu!XM9@n3LBRg-8>(9TlnYYLF=ihV6+WWV9@;I(P|8_y%9@n2=f1J0+^|!kD zYu+B$-|Bwu)FZw-bIlslPkncPISrgx{U;vt3zng<1w?Y#F#p zHp9__xgJLm9C?=HbEaG;BYaww5FRjZ#Ld zj^_?5KSK=9!A&`3G-YPvf$y;F+bScfe=Z*E{>AV9*}Ja)cYWLvpEUjzWsJka-@WF# zC?j4!X5!(UiCleUMD@?b!~1`EeJCT=$GLcTM=`GtWyJcJiHG;ca`lxF)gOh2cdl~f zlo6Gihev!Wo~f^lroB0NXXD}h!n{6|(JI91<6JzvgO=BaGGcwq#KXIRx%$e8>Ys}T z^T+(2tJ}v@<;LpyFT0+qk4B{y59W`>HIKRa>LaQ@3lIN1{9SoPo9chUYK!k>h3Be@ zdKD_tU~|p3BKy6r)Yhv%CJj8BRMab2kp`aoD(dyENCVI26!rR6q=BCRE9&*FNCQ8? zRn+TSkp_N7tEktvA`Sc`S5dF;zoX&zM$KGc#jzh&pAYj^6h}_Yg*hr<=THM?A-G5QMIzQ|mU5Wpucy)f*KePSb(C?e#)%jq5$aapx`YT?W5B7)btrPtH z6#p6@?9W`o-qqRsOYJfL(fMG1<{EZu&h%G%tpDhIus?JSyD?|_t3B3#bUxT0x`y4B zGyT;b>pwQ1cs9&^;g{cZ!_}o{!#Y*6i4Gfo+?+7pZAZl&#ySv|6lX*{#K@s z;#i;2`Cxx+3G2@?{nZ}pKRO@mA1z`1S*E|*WBo_xgZ-l=tbfb&S9`4g=zOq$w1o9< znf_{z^&g!N_K%jZ{w>pA?Xmu&^TGbn64t+E`l~(Ge{4SSOs#i)703SDzvqMfuXyHF zrk~oQ@i{&}?C-2$eOji!+GG8Hn-BJf*6{vkrmxy#eMjem{h@dUSEj$(WBo_xgZ-g+ zPFJSC+GG7k=Y##BmH2OpSLcWQp_TY=idW}{{h^ikZ;JnGe%QZRi9e=zZGKxg0rGwR zr8xG->hr<=*%sap&FVw#(foXTe%K${i2tVe==`uhWP5Vr`c=F(AM6ipWc{1s)%jt6 zXd~<26tB(?`$rq`-xU9Ce%Sxnh<~Q|==`w1vk`wx@#_4rf3y+*P4U|NcH+M&j{Ud# ze6WAE6aP)|>in>Ov=jeL@#_4rzqS*9PVv$CVgG0+{+r^}`CSB~FrzW6=(Z|~nvaqqv)$jAFf z+4obtt$&%3kN1zV@25D{e{??HAIkI{C2ntOzn{Nw|MZ7?@z?!vFaEke>&0L5_g?%p zzw5sweigU3S)Yq zOfQt_g)+TRrWeYzomAgr+Rk$CXRtbL=Rx=TU`*SYv;96;owjo``+cxFZD;TG`e>(* z^)uMmZznkQ`(Sl?qhtR@>-0wJ^hWFSM(gxO>$L5--Q&^r9PVeZI$h}4Z#$3n{|dXF zw%rT!K5!M|D=n^Gc7^5FS9WFmTAb;lIOaP#AAZHc-%ssp^I^a7ier7N^I^Y?ievr1 z$_LLZ_&tf*V|_;FgXfO?j#KTi{-g83cL&^0PZ zNc@fY7P9g&~+U$W1q zIM%m1AMgKU`YVq0ug=H&KbiiDWBo_x;F|g*q>R#E=QR@YLE5#T|R5rf9_pB#j(FNJ|FCV*=}8^ zJ{7Od2m3#3cz-e*|7wrN$LM^p|FeemXPN$LkM$p&5B7i7@cw3|zuIH{f13~Xf7Y-Y zYNoH+V|_>GgZ-a1yuX?0ul88~(fMG1XC?lb;$P*5{gsvYSBh8Xhy9zC_+yHX&2Jin?(vlIVJ@zMEVe`hEDnBt@J!~V`r{4vGUfu>W%>{+Z&V^TYnmo%my4kNf-6 z^*?_O|J}p={fu#c|CfC~#oPNaGxG8Gf7$m_9P2+iAAf(B>8m)_w>lqx|Ci~nIM%;9 zAAkRs>907}e{4RFaDV)+uj2mx_&50Y`>*WpD~`tBBi!FtU^+&^dSC`;??x(Pra$#?{SWdl~H)xtGy?340lB-1ah>a=i@3^y)me zULTC<)!py+`e00NlmIe*nnmC=aXzs|=4-<=o_WwaVO9}j#VWjvG->tiM!*mp4Xl@ZlH7Z2=^SbZoX z*2lScU{A^FLm9C?X5xXpEmL0^QT=oA!0wmThcaS){0tB5OPMaph`OAM2ll0`K9mvb zV;&xU&3Eo7Dx+y{j^f#PFu%~RlJ8ZJ`e-#|6*LnM=8ySR;l27$AF)2_@L>L!UjyG$ zUwuUNXX3&9F~0`BS0Cyl*2hddm_NqW;@hvO`iS-M9XyzGb)jCLGMXyS`-YjAGUw_- zy*_0e>!S`+=8s*dqo|Cd`ZF2quevf?g;e5UelgZo8BJN68Jvv=bHA+G zSp_Mh)sR)tOgxzTW#5<8hcaS))ZxM0uPa@nsEnrl^Y`Uvm@;4LN>>jmZ9pD8xQ6N zUa4QGj8+}btAl5{zwLu&6*NXh+>tB$q{@ieo{fihzw-J}Myn9>M}CHfcb#%wlo53~ z7Z2}C<@KSASRd!&;oYyiK9mvbVMpXY?JiHs2*M~ApbF4@fmexH0I{xo{a}{uHs1oc?GGDRzp@n zGx1;!T0BQ0uMhPR>!S`2=8wfQLUQ%hM^t|%9?TzG!WzZAKGa97kC}Kd2Q8itl-Gy) zi1ks22lL0`*-yFp>LaROhX-@N;<;YA`syR9|1&(8a~029%av0fQMs9TFkdR3wwKq3 z`iS*0507|~Vy3<_n)c>7&c%bdU-2Bxygt-Ns}QS?nRqbwYyB7z?S16DK9mvbVh-NigUufCY+TW%e?^jbZm4Ke_fOa>>HX?GCM!JqQ`GBQkp`XtD(dyE zNCQ9dRn+TSkp_OItEkuaD>U#ESVcYOiZt*OR7JhM6=}qi;@)T9iesm(J|E_-D2}|C zcurn6en#hq-IaJUUiSUe9@od{e6YU~&&JF2S9`4g=zOp{6VJZO^jCYV|LAhDhY-3h-t;ddwe z?u6f+)Zd-(yOa966MlEX??L!I2)_s6_aOWpgx`bkdk}sP!tX)&JqSPB-vM6%Ed&3C zSO&fdS_b|d_Pf&NBawYdbQQ;+?%zf6cUIKzE>n>P{_R%O>syfqo;xV&^{q&Q&7IM2 zirRYhze0n}u#pOC>s1(&2EIdA)GJt#26hM(_4-z%VRvun8m##2eAxZJ;&^;i=Yt)R zwufTw+$cUeKkU7d2Vo!gy$NGPj4|Z4D z9*8}C)E?_IIv?!ov^^4g`l~(Ge{??B6>57V_VibKtpDhIuxr%z;OptH_E`V1`LsO{ zbA1)Z{#$)M*gv|G^*M@<&JX)TSF*ZF@#_4rKXj#Q=PI>-e@7vHzY*i!zsWwI;%$C4 zBOmYIWZzG5tbcVr-XF^JR~+kKosaj2GW`|D`d8=U{h>^M#j*a?`FMXQ(_e9{e{DW( z4?pwY-t|}9`)@Py@%~Zv{S-&zzwL3@8$XPn_jfY>ievuO`FMXT(_e9{e|0|CUu%0D z_O35#kLzP}KG;8MdmQ%kS9`4g=zOq$)b=>+>96)!|Izti|ETS8*wbI_vHqj;!TwR( z+ksduz$3K^=X;@YLE3Foe%bhmaqq6roY-_{YU46{h=l7ahd6__E`VX`Cxx& z3454k`l~(Ge{??BA6mj5wVD2EkM$p&5B7(aum^FbzuIH{86WJ=EMbr5jKA7r{$ulr zXFR;?t2p+@>hr<=(Hh?W%<4n!(fA*qANJ2y;=d_gogemx;u$^J_*Z*8{zvD7{h^ik zZ;Dsvhy9^=##T1|)gF)k(fMG1XeIue;$P*5{h4@1T{iyI9*@7#`Cxx$CH|M<)%jt6 zD4sEyjeoVr<9}>Ewki#Me#K|!gZ;C3M(q3eSG+nu>>q8!e^b0VKkN_1GoG{YulD%& zb96q~KiY`@rubL+VSgr`k)Dk|wa4RcbUxU>*@*w8cy)f*AKJ+JGsUa(!~W4m{5Qp` z^TYnoM%KS6{@?I>{KubHYX6S>em=ej|Ly(nEAIWb8ToksDEoejxB2~ye7t{@eLuyq z{-g8p{!gZ_;#l8*&ByyUnLdhReX8^E{!pgB;#mLce7t{@>907}zd9f9A7%P0j`gq3 z$NNW_{)%J$tMl>xQKrA*SpV95?!pwal>>u63{%e{3YLE3Foe%bp?qU5~ zroY-_{YU46{iAzW|CZ^m_E`VX`C$L(9@f8Q`l~(Ge{??BKe~tYZ<+pTkM;i=p9k^B z6vzHpeLmRVc@Te0@zMEV|Lj5hH^r;-!~W2N_-~3==ZF2F2l3w&ug(wqLl5G=DPEl) z_J^~U~WyJcJi3fI{OnqfU_0PovyHi#l%82!GE*{vuvieX)tdIYOhn*hS zT0j3~Oq*xa%V@4bFQeVp_A=U?Po80)w_`9xV!DVk1J(*b@TOJAB^eM{i^r+U`(%WWcT`DOs|yb)%jDszryPDMw#9y z)0>+G=bz(7ncm!QWv>rbr#CwGZRsg);T$tLIGp3EaI5R;T_H z-(DYV?E8~Q^FI7pjJ*tYJ@x0=_4;7fQ-3B_uMbwI{#>12AM7{EpAFLMgN=QE{y^S` z-+{iD!LFx%m+M|1?0V{V>h1Nx>eTP%+3SPVslVUP`|$UK|37i45&J0} zF%l_}{QnL3Wph9NP*p`7}#=P7Z6wubm5=9-6M6ZIqT6XP3Ph9H{Y}QH*r^ zZGX(elsUEwHSnrv)6c||xvdNRtw0rRe`I3H{Mg_8qNz1%hm>>6QFt)>b)kMt6*bw% z_l8lJGS|niB2Yz}?JP|H=K2rjrL=}mKNk;Xzy9X>Agxh5r1+vtJeX0uQlqGf+8yQ0 zU?v{Se*Mjre_EsFU($a+kJsmvwSUKdTVd^2yoM@#`sdXcSo;7R>-HHvY6sKWP0CLY#)#p$cUr#}i0X0H7G$Z@t>!)H4W59Xy7clBVLzSi*R zXX3&9n19kh+#g!Q_eUlk%#Zo!OvL@6HGF@}!-M%T{|u2heXZfs&%}fIG5-XaxIeUp z?~gn@{L_J=^i@%_FGevJ59Y`Gv!UYt&>FQvN`JhE2QydxnO$*mTEizd4-aOp{PWo2 z^tFahKNAmTzx>nq;{MPYzCY&S!R(iR(qf#x*6`_P;=%0K>h4F5`$KE^{>a3G*)RW; z)wn;jhVPGgcrg1_o&s8*gcYZ+3ZH%^9?X9E=O@Sgp*4Jee4U4XCUrzz6_t50d1vFn zywr`FD^;`|l!+;`U;c^p@exLA)D9^}n0a_G`*m}7*T(5<4WE7{9?X9Ey(r@T&>Fr! zGVx%3>_)F*R7LHM$NA|zOqu=iyUfH#2dz=_FXs-Kcrg2QbIa3G z*{?hGW2&g#@i>0W!<5-CzZYkGbkG_#|8jK5#Dm$dyW2A*?hmcu`y&$%X21MCym5bM z4c{N%!Gn3JJ2h9TsHr?Y)iW_=Udr!%9lvk2M(vRDxjzpNX20(A>Ooc1>>o#mOiY>m zx>KX5inc#yWLmDiv#+E4ciFY6?wO*B^YN(mtCzki>bs`&$GLb^`_=0YRrvnM#G~4; zUizx=>5syrdZ}J=s_@BW;!&+rFMU<`^v}hk+OJ-JsKWQhxp-9j)$0#c`2NVmquQ@t z`l|5hpNmJeU%mcNh3}6u@z|+RR7LHM;$U;}V18_;22B-hf4qk&GgrI0dN4lntD;SA z9;VD(?dDpzUiw<2=3kEMnRqZiwwtR5d;Os`e1FWtgZZ)D+-=-TUu*dEGx1=4Y&X{^ z_WDC>`2NVmgZZ)DTyfXy53S+*V;&yNkL~6f#a{Ya!>6B#2lHdQxkj76D%$>-hbgmP2Q`YSXw%Qcl-aL?8bwvK{qY@4nU^}K>r+LWOD3kwOC8kp zsiN(VEKIK-#u49-tO}d`pAUbMix{?F<<+X9cEI^~VEa{gsKWP0CLY*+mGo8N(?1sv zY`;o>sKWQhj6BNs!}=;7|5dWBZmU;O{YS5&egp1R)bC=wih4F4S6n{+*5`hny^4C4 z)2pb*^D9Qc-oL__Ud{LHc#VZJT`1FqGF{APcJJ?CeY(*1{z929l<7kIbfHXF%5{L= z_wnmsp9zQo{@d~U3;)gd_>c3)$0(dT`xL#9_fZ+g|9+`pe*^p6xqQ4=ac-pof0maD zoL{NH8J@2KcWvRJih34(J|6hERd}ev_eUlk_;abGf8L7d3E`f{*cJ9uJ^o8o;osTw z@UZ7&aki@P*`A4qHx^NUsG@d9xnt#QJnVO|xIa`;JEZhSCLZ>CcAUN{eER3&VJ%DC zAFA;Ek%@;jXmR?g@adn6hxLVVf2hLu$0$6kxr&ohg-0KNk;Xzx?n1 zaR+G)-$C>6V1CSB(-EhyHGKMcc=+peqV!c!voA*RY&@7B^Vf659i%mC50ws@hX?ax z{#v~_eXZfs&%}fIF@L3I+#g!Q_s4heVCKqS9~f{$i##B zF@J4*+#g!Q_s2Xum>*l+)q`>RTEnNGi3hV^{;rp}KeUGLk9l}7`?b2eO5*gjhEG2a z4}Z5>l)frz_QfckjR&(|{%*#&gS1BNq0&L$!Gn1ze-CM#i`MYDWa7cR)Xm++8TW_Q z@cl6l4`#po-QjWiTEnNGi3hV^H+MgB+#g!Q_eUlk%zoY6{m5~DXbs;V^YCEy>qd>D zDr)wRZ;hFlGW&IN&oYUR4qBsjNcm2fi3jszH|iW!QM==D{P;T4yL&QK^sZEer+zjb z%uC&=xl%>jLGv(W_Ur!f9Gd!6xA^#>ikg3U8fhjT%zoXeQB+0kj`FEK6Axy;?(Ug? z@zFtR)ci~OnRqb!b*DyA6}3AaM~6&Inf>u zRM93k4^w8H?$qR|qD?;!(~TNMRrvIC@nCLiqrOlTZGU89%Iw!h{g^7+{>a3X8O4nn zMOC!@@nl*)Y5w)HGuh?id)6owPy5yXOI1yn3+TA6morMmN`I)r_eUlk*nXAtRpHY=7Y}T|N`I)r_eUlk*nXAt zRpHY=7Y}T|N`I)r_s1wau$L;yslq3hi3j#lC4E)+^v}fO@{vFGW2&g#QH)|P9?TbB zs8Li!+aH;jGCy{qMo|@Qe`I3H{MdyWMOC!@F%MJb$1c<;s-jJQ9;VEGm0cg%xuq&< z{^i{AJv^AXDtq^^&N2$P(|&K(jS?4So;;HuL__3 zyLqf1{Z{{i$A6VBtX`^DQQbwaqJF>aRn+fMy^4A!-K(hQQoV}$ITu$f=2NU!QQwul zike)nf-zl;LF=u-m@ekqd~XfLbTMc2y)_uql`<_WKhGWFe`WpXLsr3se#;N?Bi^p1}Qpk6HM=g?j+M zr*QW8y<~rbj%i_D_BXkBK4xaEeLNp?vwkt2kJ(wj5YNZ_>=}17-=1;B%#mP+HZ z^TXfoSMvQ-J#R*)HFjnB>x`%CuwfW~L%hyBk={Hw-C=ZF0c`|VESKg|#OnU(y0 zq4C-IVSmMb7uWdM{Mc0s8pnQYem>a$uxnN{K080`f7lgC8Xuh>_B-r)GL6s95Bnc> zwV=jl=ZF0dyB1XAqw~Xl=SKXP#($b0_A@tf{g=i^=ZF2yjrcK*&(06~og2BnN#k?# zyOX-k*_#* z@4w+={Yx}o+1&MCQU02b^B z<*WHP-_iMCzq7gP%cA@>ALlHQVU%d?Z)ze5#1m!IQdjbi+-sKOpUN~hL$)a=BpAB$g$Dt!9q;$i(* z+#jm&{qY_i)?CH8sKV!RE*{og#r>fQ-yfNHSo;;HuL__3xp-JV7WaoLe1DvahxKD| zf2hLuMG9#`iJqyA7u?T$Ymw&-j;m>;`RgQkkMgT8|)Ggnu4^gK_#=!>6B#2lHcBclBW0A6morMaJ0Y)7Kh4{Y*TVAG^A16yyHT8ooa=@n8n+>aJpp`$KE^ z{`fkNg}OdfROZF?os9?cQVVr`s%SfC9;VEGE!2;xqD?;&Q)a&wY7|w`_D3eB%#SV9 zIjW-Vk9n9f`?XM`sERiIOiY>mTBuP}McW^lm@+@MQ0F*eMR|&*O|ATQ`CeIVPp_hW z-;XO+^KHIYQNMfiD(d-ZucDrz^eXCSRIj2Q$9fgDlY14lKYA66>1wP~yvB_(y_s*o zy)_uqn>kPJt-+Yy%%^E@4aW3l-ch|Z7}FbNdZ$e9l<_SfAd_ zXH;(u)~9#+-oI0(8)dptrW<9tQKlPZy3szh``pJ&?M~>u3f8A~x8-;ZyWecDf*nuo zo}s-p*zwfvOW0e3^{L(4thWa1Q@ejsZw>YtW%odd*RZ>U^eWi#)b2#kTZ0`>?bFPA zYp~;~ePVKN4c4djsjtx*U$#pGGa`d^GSGs77u2Gt$7{$uw&7osoup zl34WpPvh*n>FDG5+p~RQS)9M-KcDC}Cm(D;%6*FX^=W)=KG?mKUk~x?)A-zcu$#Hi z-&`~w=l|P$u$#FM^RDrq=7-(NuIDgH@`H#)VK2s~oSL4{fjn4=B zG5dtDIDgGY@9(ek!+yp-!z<25^Km|-^TB?`KBFtnU-NPPqw~T3$3BBA&R_F!{=dx! z`ycz1tvFxJ$N7%V2m2rU6sbsrt#7FVZXDI`!h9e`E4&xNA-M09JhWa`uj9q&!02$ zv3@6deHzF4&(6pCpD2HgasG@C_A`E0 zxQM^zWB#M_!G7lEo^KZAulYFt(fMHi<9Bq7^4ENv|JZ!|ew?rQY8?Bu@%dms=673- z^4EOy{vMwn_B(zr-6(&}$N7)W2m2krQ*xBQ=HvWF=Y#!^-v>L&U-NPPU*&`S%-ucz zKgvh*aX!Dz2m2SlhkTT;=Hq-v=Y##v-R&O`<*)fT|Izti|8pmPP2;2U!+z)P?!S!Q z-|#;yN}*4KFb zefs@;4(GRC|9y>Hzm<`X^*7P$(>Qv69?lPr$j|zp=s6G0 z=kYzRU-3K(?pHiN_xlyk&xU@*^XSm8c=kuXf-${NrkBs_p8Ed^V|t}bubRs<@21b|97xHT|STN{WVyh zE|lp)nJ$#+N|~;d=}MWFqZ>ZLth7&8%5BYqWx7(Pb>GQe`gP~Meg!+8*4@qe zYp_18J1F(nV0~J5f$6WoKBMYR61_F*v-JBF>@%u9&%D0|>(ly78O_SfK_QS8-b`t;zRFXyWGn@>}AUZ^$dx0iCho{I-Np8n0*me!~pQu-qk4|ay~ zH|N?~!}rH`@L-?nfAbATYxrC;@nGKy7W!RG6}3AapZoJLW#3Nz#$9NQnt%CJ&%}d$ z-(RR@QAO>J$I&4ZQ)VXq##?HQ+9BomF%J)B^8Ut2YYm@%CLYW=@?RuWQM=>u>5+%& z-~8IdoTJw8{qa3Kn3wvSUjem7P3H3P9Xb;a=B57TH(;&d`(qv+%zpjN@B3QAr=N)j zvtNI6b%)mQ{gH_W^J9N=ZI9OQ{V@*@X21UCx-G5Y)6c|%*{{F3YENtU{>a3G`LVyb zW>ahU{`d|a%uDerWmQpADXwoG9)EL6B%2eV&)a}B)Ks2y_oxXK_C4`#n^ z^sW+B)b1#s9y9S^_Umu%ZqXVw|B`+t9?X8-=rxL}sNL~6I%HzX?APDi*`_sWhm_;T zJUp2Fy3uPCRZ+8l939@nlzFMYxtmmL)a=Upb{-zgI^F2q*Q%)5Ki;>Qm@=ct?-N%= z+aGzD{>?K0m~+$`zCUK-!R*(a`Y~0s>1SffjN;!s|3hok4!L}Mi<*ZAvtM`W$5c_X zFXxuO!D9`cg6IE^|F*)~uXqhr)ci~O@8MysQ=E$`d@kqWVZBt`AFA;EaV{R#e#QNv z3f~`@cv$-tr>_d1{<(Nq`xW?}WK{So;;HuZo&~N&j3t zto@4nLlwS1-owMXzBm_E_*~A#gPE(1x-C`I{&{@v&%>1YvCUoS79T&fM$Nx`?q}k` z{MhEM9*p}#Yxw@i#Dn><&0TR9_lMT-{V@*@=EpX7jbfa>*6`_P;=%mb=Jp4Q`$KE^ z{>Z~)r$$i~HT&|-;$1wLx!S4QQbn6wCZ^0>?e1E*=(w(mwm;@!%KX^wt{#lj*BUkd za$L{EgW0dL3t!#gGVTvm`2LuO2eV&0^<%22*+0(uGBIWLYo|t06>WcHV#@5-PK}}} z+Wwe_DYIWYHHxZe(|-?B=B0M(`c%;-Hw)8)nmkqbY|qAn*{_2dMOCyNl!+;`Uk5dc zs%ZOT9;VEG9n_DhqD?;&Q)a&oY7|w`_D3eB%#R(^IjW-Vk9n9f`*l#GsERiI_b_E% z>Y%Pq6>W0!FlAoqpsr69ZTgv*GW&H$4Y;w!uQ8KJh0m;*{Z^4I}Z=+rAoG{@Y!bKfxT2o zUll(6bMe6TtMrE|e1Dva2liv7KUCrSBNGp7ze@V5@abpeaeH}o`t`#XS)-_mv+=OL zFiu|;_ULeNhV?gzS#uTt9jfrjor{MxS8;!+!uLle9@cHe>8rx0e=Z)@kH!6=3f~`@ zcvwFcr>_d1{<(NqKNk0gDtv#Oi-+}Naet`7_eUlk){n*MtHP&029M%;>obU=Qz+l5LYb52=prIH=JHYJ;&`;)U%vkMg1h~Rn%i)ucE$RdKI;UdKHZ6 zVy>2p*H|gj)qHF0t-+YC=3KkC24lLKPvqVjjOl9Lx4ktO)0Hy4QKmP_^k%-j#((LJ zGQF8|+};|vPpg58=Ck+O^V@ec7r)1FFW|o!_W*uR;q3A8$zF>Wy<&SURy>a1MHiCy zg`|BU@1Kh~=ZXJ5%&t5mA0>XF?;G50)?P(_pY=WQIPN+7jWC{%`_7&-#`7^h{t1cu zk9|5WO9{3Zf^oJ^Zf1Ha4J{KC#FY85J2i@V zD_);GU%nGsV)-kqQH)=$D(dl}^hYKh))&U4qIO3yif7|t?N{6% zs;C`O`Xdt$Yro?3RpHYgg@^T0adN8g$z|eUty7%7Dt!9q;$iJq+#jm&{gH`>wO?`i zs_^NbiwE;#8#QREsQvT!)|iPY^J5z|XsT%YV;-i=k8SQ6#rX3@Yt;OUGsweZr$$i~ zHT&|}@Gc(AOYPKLsiI9T6H{icc6aq)bX-?O+aH;jGC#Jvs|Vx$&>FQv%8`E_9?XyJ z?%KdOeXZfs&%}fIvE5yx825+P@cogA2Qz59yNWUH53S+*V;&yNe(lsKs-kB9_|`ZN zQ|7jI>I+rTrvDzM%uDUmT&bc>E)Ua#x;|C-^v}kF`LTmKM^&^PG!Ii|zYb~?RnexO zi7B&Rj%Uk5dcs%X>C#FW{ugBnFuwEZy(Q)aFXY6Df#W;+T~ z=A{nm`c%hQqD?;w)3S@LeS-h%H$GL^?90x-XCsE~ zSK*f{ zn1=`RV^?>LVw}F#@aeyY2Qyb!clBVLoYwHk&BKFvsjIs-Fiu}<`1JGeSg27{Ma{l^ z<2xG7R`UvtKJUimGTkXdb4_ey!9fs-jIl6H{itR%#Sg(e}r8FlAn9rLIpE zZ7!LZGB34K*QbiMKQb|8_G_g^Q59`}%)^w~uaz1_RkZ16V#@5-N{yl_+WyGIl=-oh zI!9Hs{V@yE8#Rim@Y$Y?2eV%{Y83yIin1qb^t83xr@87^Jim$eE1us8`xVb`1#!jm z2?6owlTSygX7=2xGt5YMmo-}lCG$JM)yd-HME)%)*y^Ks|ZdzyOl zarf1GE8_X}TJqjF?!S6%ZErsAzk2muZ$9q7dW}zSKJLGI6+mx3?!WrWSvpO+kNMp`ondc2=6CzF z3cdN5U%7)9cW|lTYv3-n_msqc=igP}tjZdysOQPqc;F*hd9|wW>7R=SJ`*VYp$gw0 z=i-4siA#T|!uQ8}c;GYel8Y*QF6ZKb&wxvRsKWP0CLZkDNxcuF|II>c`2NVmgMBw; z2BsW8w1)4Gd3bQ|pbDSunRqaJTAucZe@#+F?Vj>q*?2Ht$ozWYp*3oc%*BKGv3egy z@7z)qHT%cW;XO>5xnjR-l|I!PHM_ZZFfUc_!|1*-Jmsme`Mmp z{8+sYqksI+8ooc~;lb<|yC$U^9khl|KNAmTzv_J${iB1{@cogA2Qz5wnzVBK&>Fr! zX5qoECoI?FGNY)9ntgEw@8ZEcUA;r1cU)IRo7_B1nU`W$`j$S`8a4lHJeUn+S9%v7 zTEq9pJUp2Fx_z9pJ)Q#J|7=i&Pd^h6X1~~d9OdYsHGF?$;epThHCj{uL%ti0$qJw2 zYSiXCBMo*|k3aV{TJ!%3NqnxT(MtIb`JOQ*D||MnQJe3KH1OG+Ms2<`(!js(YSiXC zBMtluu10OXGt$7nz-rXyJ0lJJ3#vwKzBAI`Px8X{MDu6o!`zC-k&C&w`*dD+f&cor zwI9*?8n5|e>={x%ptfRPM^fuV3SH^TB?p+@XPApT_6rgZ zasH$8!T!we@)qT<`8fZd=7ar?--Rv8PxEnpzs(2x8^6z5l&|LFd`IVl{gK}#Ey`c> zasH$8!TxA*&n%Ae*LXs`Kd9Q(QX`Cz~1_c@FDL-W!5e|&z}ANifmqWm=< z=RZ0h?2r6@X;J=~kMkd$5B5iXPqiq2&BytFl@Inie#f#XAI-=4jLrx9A-`u?l)vWV z{72`5{gL03EXrT=asH$8!T!kaN*3j>`8fa4`CxzK_Y{lr*L~H)IVNw2?kMkd$ z5B5WTf3GNi&ByuA&IkLW8@az!;bNequ`D;GTe{??BFKzDnxF~AMA%V zcYRxwpXTHIewz>WKO6C98lRmX_D37>a~hwU-%k9T#<8E9pAYs+JMnWGpPe7}OFQv% z8lRmX_G>%wa~hwWANEH(@pBrVonQ4wOeiV<_^XF*%Fz2W7 zc>Vm1$LsMq99p?L4H2?C!ub#p7Dlo&c2BuglFvn7X zNtO!CvQ$*t)q5?tAIln;XsN(GdHFaeW=u=X)BD7K>4h@AP^K5k^g@|lDANn+(ehdu z(+g#KrA)7s>6J3I`@zS#*d4)p6|7I~uEM=FSfARRQG08!KDE0C#%tL9<9ZeBy>IvM z>aD@v`*t6o-Wu$^Z}%$ct-<=#?spKcVW0Tkt6=Ya`&8}T8tiy#pUm4^gY~I>dT4JA z)~EIfgz*~o8lGMS>oNN~cW({WWA?Yk-WrUU*05)Y<&%LEWA9u08(=RNtx>rb>X~@3 zBaHoxvDY73!}muf9_%yQ{s!6W53S+*<2!h;vrqfmU@w>dY>nl`Pn2V!T|*V4@UXv( z6-!+E@9|&dJEQ#;t%_Vc?029zTUFHeM0q!yi--Nj7x#xMe1DvahxH$Ef2hLuMO9@aX={hiSes`{&R9Uzd@GslOI1I)13ar=N=l^J51!XsT%YBNJ2R#}0ROSbY4@8nr{pHG7$O zFh6#<>n-E{&>Fr!=HbEo*x|0Fjnmf}KK=LbVCL#@*PzA8X$_y;JUp1W@^@Io>1z$2 zekLBwkNG=n;{MPYzCY&S!Ti|a?o5f(*BU8{e`MiN?l{9&AgZD! zU;Zl_4{X26t5rqqfb;Rd_N(wvh3}8|@W9rofmkKDj)@ ziaAGB)cz^X@q2hMljon<7AL1QYBD94Ogxym^3Usw`$KE^{+Ndc^JD&5jB)x}!>6B# z2lHe8Nt|(iXbs;VnRqZi=AXkF_lMT-{V@*@=EwXqcH{K5hEG2e59Y`G6PDxt&>Fr! zGVx%3%s*c{?hmcu`{O%!FmvUfY98mJHGD34cof%LpYb21uZo&|F?qRoF#F~AD~S6; zYt#-Y{gH_WvtNF8{e`Mmp?AMiE zqxc&Y>&tV#%cq=uEvon%9@c)v#8lzm`=ju%UMfyb6+XF4Jgjw!(^rL0|6Dw*{fhfT z6}~^t#KZ5`81;uLYIhW)n2U$CUvc`XsQH)l&&9*qued){;rk;K4{N{T^i|>0KNk;c zzvBK-h3}8|@L=}K?|mI7r!{1X1>{Mh2|M~?eLYxw@i!((;VC`Re4qGn%=VlE!ckFC_8siN(VOiY;{ zTR+|r^&02+_@Rp0A?5h-9Xy!1THO;4<6N|c&m|KNX0BHEgu}Q$w1)4GOgxw$Tj@1< zs;J%ZI4_)sDYIWIHHxZe)6c||*{{_-;V}O6&>FQv%30q$Jed7jsZmr#&HnM(kcla? zUn@0=s%ZNo57QepimLGGzl#U+Qa9@QRM94vi7E3^H)^g_(e}qYOqu<aN7 zzBAImzprZ4<~t(|zX#l_h0-`SPe0FxxetvaSK{~5i~9Sw`C+@^cgKtVe$B`EkIn~s z6~8}Tl)vWV{72`5t&HFQF3Ml?asH$8!Pds_Zx`jCY5wiyDcAn>XB@XyCwhGvukY`S ze600}UZ2Ks{`B-Zd<*#v^|IhOAJFC6sqjBrUGV-y0D0+PwNAFL+ z^W2F1tRIU0K8@piXXj)6P?W#MasIROv3@AZU*kCc+4)$17Ui#Tod4{6uwT2nC%Q!a zq4~H!M(2b5(bYYFB+6g&asFTBgZ<9cJyRvhNAqz$qw~Rj=jxuB66LS?IRCNv_<-07Ui$`=>0uDKkSbd_w1A?f6d4FkIo1Cqs85o80D||IRDZ4V1Kl@ zr=vvqYd+3@bUxT0`90jC{52ov|5ZNN-}pV$qI@(T=QBDV>~H)YX;J=~kMkd$5B5WT zm$WE<&BytV&IkJ;zYAKFzvkoof0vKnmFqP>jbpzyKOgMR{4Qlte`r2>e~-@(`ys#U zR+PWykMsX3AM9`Z-d#~Xnve4toe%ayes8WQ zf6d4FkIo1CA;0%ll)vWV{72`5{m_lvAFA=$`C&hFBlm}Dd~|-;58cT9r5c}|ANE5x za(}7D=jM0+2m2+B|27}&x9)WFDx8~#gzsd*uoy}c; z7UiS)IG@q^V864u>(iqAH6Q0cIv?zhHg|nml)vWV{Kw|A6aS`h?BC|+gZnrJ3s7?4&vW5K080` zj}GGBG(I=K%ZGo%hDjBF+*7@>@xcD5yjoS%4j73CHb3PrRfSJ36A$ctO8Tns>7R=S z_EM!kRN?#MTs*M1D*d4f-yfNHU~5&8rx0KL(HT?yq<2M#-t7=2niDxp-KU7pJd^ntw_ETs*8Fi~Brllu}|3GUnrpv#77ei|>rpv$WIa-4;T`1F) zGF>Ut_21W!^#9V8GF|`uOEX%7_38TW-=okPtWQ_^-d`!x8)bT1IKR6G3 zep;BS!ZRI(2S1lmg-`BGJeY;Mew-zyy%+p<|$x}t!AMatxjM0@k zHdVCA&BK)Wper?Ks%X>C#FV+ME46{DX!|1*Q)|%Hm+QyMcScpz{B!Z}*Pun|tDGEJgohS(^rL0|6Dw*{fhfT6}~@4;bF~HoSZ6ra+!EoFBPY+ z3ZMSDcv$-t_lGKce`Mle?N^+>Dt!9q;$iJq+#jm&{c$cH%oqCm_~H)I8oq;O;oM$p#Dn><)m=Rp_lMT-{gH_W^JD&LCvksh4c{O0@L+yyb=N4y>1z$2 zekLBwkNM{q#r>f*e1Bx(!R(iRidEbnTEq9p*LnCSgGJO;QJELlcQzi(OZg|q#T}$I zY7dnTnuiCoU;e3par#=rr=N)jvtRz1ka2%#4c{O0@L=}KKkqY6Uu*dEGx1>d%RlWk z?hmcu`y&ev`;?>CZ->>;N|Izti>*DwPit^Wdod4*2 zu$A#Ux<&bGKF)u1KG@p$z2&0(H6Q2y+kCLK@q5EX`D#AScXU43>iE6iqWm=<=RZ0h zY<>Jbby5DBkMn1Iu$8%xCqMsZ0!FKkR>&k0<`%*QfEh`C$LEeC!5@U!TV3=7asv^6_ML{Q5LLHy`YW7Wd5K=<{Fm zasG@C_A|>r8pnKR=Y##s;+`rTz5g^H_s4JZ!Tx9YN8>oZ+4*4q0!FKkUc+j$~2(nve7UZ9dq4`5ncgd^I2E`&B;J zPx(E+qI@(T=QBDV>|gwzUQzyOiK?7#e8Qc-_sK6-zT&ky?@ zzyDU0zvkoo86WIl{Qg!Ef6d4IN9Tk6j^E)b%3t$w{-g83e#h@%73Ht_IRDZ4VE=O? z*QaTGc7E9Z+{pE58Xuh>_B%IneVWE+=ZF2y%{@OY`h3@X{P{jMpS#;z@ikwKW54!w zKG;v)-CpTYKAMl-f8+DR{^d^Yzts5b{ILJIllw0dVLzl`G1v<^)C^Bjbr|E z^Vyu=dd*+s)^BCxWBpk4`ZSK-|C{rVBl5HUC;Iy|j`N+JkM%!M{u;;m&(6pCpD2Hg zJ#er$8spGEI~&ByQmukyiuW^>n%Mfqqx&S!K! z*bi;)`mrc~&ByuwE}xzFGmT?^Ha{Qi$9Cd}G(I~&?1y%DecJ2sUE`zk!~SP?*PliC zYCih>9-klfKfAmBEXrT=asH$8!Tx7=*QZ7KYd+4O@xlIOC;m#~v-89LWhZ`1V5L^Yg*}=OF$}x`=5jOGmX#A5Br~k_%n@<&JX*YgZMFx&(06~pM&@_ zjnB>R^5M_0AyS2ZW^<#1Rs_^Nbi-+}Naet`7_s6+-Sc4Y#hbnx3Wa44{Se(8peEOsCu;waGP8B}6 zOgyZ)iqltxPyb9juFe-m{h^B59e+N2(%E=0gLb8kO%-hi&BK)Wv8%hjFg|{0jhcTs zeq`do{Mgl9qZs#x*6{t2i3c-iS9cX-+#g!Q_s2Xum>;{kYZT-3wT4gsJv^AXy1MHN zRTEnNGi3jszS9kSb+#g!Q_s2Xum>;{ks|VxswT4eW508Z! zMOD=7i%~oq4`#m>Y7|w`cF;Ubnf+R*A5%q}ekP{Oel64}s-o?W?_kQT(?U(2D%xB! zF=bwAp{`FAZGU89%Iw!djiM^r{+Nd;vtJ7}imGVS&%~73uZ0>#RkZz)i7E4A3w4gF zX!~OprYkjys_@yKjR&(|D>aI$XglaTm@+T5QrD-7HkV9HnU`9r>r+MBAM-F}_G_g^ zQ59|anV2&BwNj&~inc#8F=h5^rAAQ|ZGX(el-aM98bwvK>1Sff?AJ<-qAJ?{$i$S{ zuaz1_RkZ!_b*4A!`c&bmpN$9eQa9@QRMB?OJWQGWx>2L3iZ=aBOqu<2L}y%pu@<$Lf{^V_Gn z>Q_9!iT5h*pWn0l70+)4{fg(AW542g?$EDzetPsPo=2E|#k0ry70+z@6;HR-uV73! z%5?kuZrb}-w$JY`{R+l(`#gu~ufdpZpGUg>8jR^i`*izsY`uSFr%ZRsbf--B&u<0& zzk~JZ{(0`uUxW4O{&|Gyufh6sr%VsZ^q@=+%JiU2589^(WqQy)tvlHFnASbe`xW@T zU!Dp0+;=5jqg3GIX{o@+(^7%o`=tW+X{o^P{ZfJZv{c~teyPBHS}GXRx_3*DY5D&j z`J6;2?Q14ZbiPt-`d*e8ddhcd$KF*@v zW2pJj+2hyw;G;*qhp)$9^U?cne17<|q28m{%U|FMrL)`H#*A`>}dQTQ7gj$N7)W2m7CT$67Cc z&BysOKG?t1d&YYFH6QaIoe%au^`5X^{+f^TADs{OL-n4oUjCYo^Z#8w^=_#+KaFF5 zHa{Qizv{hVz5dXA^!^^7AND`>?yz3|nve4zoe%au_3p1;{+f^TADs{OKlSdeUjCYo z^Jjdpf2sFZ_4sQ(=07?g>|g5rQzif7tCXL zG>-F`osab|QT`go`H#-W`kg3WjpKZ0=Y##v-Q8y%^@rx;{urGP_G5SV6oDvz&BytV z&IkLUyL(1Nl)vWV{72`5{m|V#RVB(_^Kt&a%f~-M>@`1)V}CY3AMD5c6Xc@)(0ug% z{yIPGZ~XK7qI@(T=kwcqu>aZI)54;BH6Q0YIv?zR{IfNq{52ovKRO@mhc@@5zbJpr z$N7)W2m2rYT-+#s&BytV&IkLSjrcW4tv`29UPAMAJh6Un3eH6Q2y zH9r1%@2~tdj{Vp8e6XMLPxFuR*L?K;8=oKcJASW*D1Xhz`H#*A`yam(N0h(j4p!0oTl4Yz`>TAg zf7!|PVH%&EANDVPcev>NsrmT*`MZ4l-hHq6X&n2p`T1b~<#%q3`a|>4`+IzT*zfp# zIivhFALswue6YXqyQ)U{YCg_)bUxVc_&sx@{52ovKRO@mcl?gXQU02b^Z#u=*zfrL ztfPE2ALsj3KG?tb-Nd7OG#}?PIv?zR{9f@<{+f^T|7||l-yG!rNsZ6V@AA*TKK_R~ zR26^RQ&-Q&0~@l!Llw10&c_2AqQc|d71xh{vnKNRFaLL_;=6cMf7D~DirR~X`nh;i zztrmwRrvmR50C17dby~==W;F{)f@HtLlwS1GV!QZs+YbheER3&QLR<4KUCrS<6Jzd z73=kfDtv$B;ZeThJdI+UzA9?=e?IKl*?3f6*y|5f)D9{AaV{R!7xwx?6}~^-!-JWt z3w2wnsJT6k{F#_Cb9FIyyY}AMTBCMIIquKHgZZ(Gc~)F6eXZfs&%}fIv5UDEw$~q8 z!}muf9?YO!%(Lct{h>8{f6T*!`LT<+Q@5AC*6`_P;=%k_*&Ul%Csp|V$it%?5pepd zsM(iqp6}wp%+-~;EmgG1Wn#+A)zw@*7=P}oqV11)m@@lyrAAQ|ZTgv*GW&I@#imGVS&%~73uPZf*s%ZNo6H{ituGA>1qV11Sm@>C@rM^%VZMLH@WnSt^ zU7sr2Y-eG*P?M($pY7RrF#EMoqo|6ugEBE?_G_U=Q59`}%)^w~uZ0>#RkZ16V#@5- zLXDy-+WyGIl=-oRI!9Hs{qY{A%v>$h2CAY>ZXTx0OD)v(siIAP9;VD(Ez}08qD?;& zQ)a&wY7|w`_QxztS85bh;j=v(4`#nsY7|w`c2Fj!%zmxZD5|3Ek9n9f`?XS|sERiI z_b_E%YNf7E6>W0!FlE+hr6x}mZTgv*GPku-U#N<fQ-yfNHSo;;HuL__3xp-Ln759fKe1DvahqYgEf2hLu zMO9?TcssB=_B?Vs|DyYJv}r>;*Gp8DB%FmrXMZc7zy2hGEj`LVmZ zHZc0!S4EqCCZ^1f-QCrLaeruy+973^fJ{7?AG^D26yyHT8ooc~;lcda-Cd&?r>`}9 z`k8nzKX!N5D8~JvHGF?$;=%mb-Cd&?_lMT-{qY?|xs8Ljf&-QFQnEl$QQB+0SLGv(W_G_a?Q59|anV2&BwNXE&inc#8F=h5^ zqef8`ZGX(el-aM18bwvK>A#05^HLjieX3}an};d0P8&6Os%X>C#FW{ujT%K&wEdBZ zDKm;2HHxZe`(qZSJ2i@`@Y$Y?2eV&0HHxZeJ7^xJ%zo|ED5|1OKNC}CzjkUARnhjx zcQ9qvX{RPn6>Tn=m@+T5Q`e`8wm&j4W%g^QMo|@Qf6T*_*{_`%MOC!vXJX3i*G`S1 zD%$?Y#FW{uof<_|wEZy)(}NmCRrqYr#)H|fgBnFuv>o&vOqrKDsOwWjn@c99%u5~A z^{Jxmk4#LNA3LaX%v*5{o{a8a?d%oSe#Ngv74_YJ`S=EOE*{o?#r>fQ-yfNHSo;;H zuL__3xp-Ln759fKe1DvahqYgEf2hLu$ItV)ewe<0{qw*7{Lja)L6;9V@S2M%Y9{5s z&d0-gsklE>QG2BHMO9@c)v{hjbhv%s_^}hi3j#$<+D;1 zKK*m?z<#Xshbnx3Wa5GSSV>7R+mA!~uGgsv)?kqV~_~ho{!OYc#x;|CZ>>r=% znV2#^cA-X56>WcHV#*9!xf-8+dZ?myNIC19g-0>UI9pZJWXos6*?2JfRl1#ZkSb~q zl@6MR2eV)0)v)wc;nSao2Xk9j>I+p-vwwVgjKY+8sVg;Cs%W#Fhbi+?SL*sy(Wak? zDYIW!Y7|w`_QyO-nfq`BYD%$>-h3P_#qAGm0 zH6u|`fD(z>*u%m{u+$w`gzXZUxP7SKhF&MYcQra%JfG2^hTN9KHXOD zFTGKwx6g0U@fy$HUgA;K7Z2|m&&B7@cRnqkKa!?_j)CF{EF*!%e`@YWU5y- z_U2=1_3EhJd`zxhgVCFh>DAvH!);Y9KT-|a>QB4@n#`Mn}r-}7IO4nKEKn)ua6yd*)f+LaoO?q=f`n>vZKAm zXXl4M_t* z>(e;Se{MdT^KY;DYux&`jC`y=ie8__(fhyb0yX!z^+!?u8prw0&d2(rD1VLP{AcH5 z{ZW*^#&P~X&BywkC?AdEd}ilk{Zf>_#&Q0$^Ra#@%3tF+|JnIq|F*g7;bJxd3`D;GTe{4QG@pBr-er|p~*e~tGKWTh+e%LSV?)tdbi=HvWF=Y##x?ygUZ^4ENv|LA zjnB>x`?Z7kIgQWG5BsBo_&JTw&JX*egZMd(&(06~ql5T4jnB>x`=f*SIgQWG5BsHq z_&JULG(YTr4&u)=J~zMee0OY!RAKiG`SancauLIRsk~ZM)DAcw5A2@`4^{a7I2RA> zr%HdQ!uLle9@tKm^i|>0KNk;duS$QY!uLle9@t%#^i|>0AB6|DP9-^2_~bJ2z|N_p zuL__3xp-jbRr*5}zCX^yqvVgSDK2|Ps>1e1E*{Jm`aMHmugNdtTEq88CLYX>U8qr1 zMeUCAi$pFS%#Zm!gX80e)~Fp)`eQ^M$IH{Q%U^2!m?~!CVa-*XoGSdgG7}GLuHy7n z;nP1C59`O`{!oSQk4!wQAB)phg-`!nJggs!`$HAJKhDIX>@8f4V$>h1sNGSFKrSBE ze#PmlqUK-HKNk;c6yyF-h3}8|@UYe?&P5eImvix8uJ1~1pekzrJU;g`F=c-2>aHG) zk1$%Jc1Srhn1=`RV^??eV4S|z@abpb!Ti|OU85NHht}}@F%J*s$FA-g#W;Pf;nUB= zgZZ(myGAkY53S+*BM*;-8bwvq?8`Tccky86YN2jR6>V~vm@;#Wda!<5;tl^R7= zwCTTxDf3b*b$zO6lbeSr^HM8yeX3~F&%~73uaz1_RkZyv3)34limLG0o{a~yUpHzL zRnc}(CZ^1O-KbGiMcW_qFlF}ZMvbB>+VnFqW%lbvjiM^r{`d~2%sSnu$x}s}OD3kw zOWmmJQ$^b!nV2&Bb)!a66>Wda!<5;t8#RimXw%Qcl-aKvHHxZe`y&t2J9Un>qU;x9 zS(N|2e4KsMrzEOkE*{l>^^#LX?f8;yCLYyo_0m^`Pk$61)l2n~Q-x3NTs*3m>h*^z ze1DvaNA+X9{!oSQk4!wO{pzK!3ZMSDcvSn<>kn1<{>a3m+OJ;vs_^Nbi$}Fzz5Y;z z?~hq{Y}Dkbq9$A1=S)19x!S1PQbn77CZ^17ZRYC1_{gt{wm;@!%KX@7t{&{AuQh7^ z<+C9Z59Y@OD4509PtLRHl4i!aQ@gW0d0 z8bwvK{gH_&vtK(kimGV)V;-i=e(ltcsiI9k6H{itc4`z=(e_6srp$ir)F`T=?T_zZ z%DmK0U7sr2Trx3bUTUYVPZe!{%)^w~ubmo2RkZ16V#@5-PK}}}+WyGH^q@vj6+Zo3 zJed7Ds8Li!+aH;jGW&H?!<1R4gPJ^5 zwCQJJ%Iw!cjiM^r{>a3X*{_2dMOC!@F%MH_zYb~?RnexOi7B&R2Q`YSX!|1z)9Z&% z#7`$wh0XrYhd;?h4BM~rYE@A?U?d*cOO?M=6+XF4Jg}E4>8rx0e=Z)_ewF@Eh3}6{ zJh1&L>8rx0e=Z)_ewF@sf5qkH+3D@yp$ebN&+)MKEB;qh;g27gcv$-tr>_d1{<(Nq z`xWqt{=`O%0(45m16SF#>1MtxIa`;JLK^$V(+L-#H=5S z`$HAJKQi&Kek@L36+ZoQ@vwd@?hjS?{>a3``ms2DRrvJJ#l!l-xIa|k`{P_Zm>(<8 z17_#iKU-1G_u2RKb5#`ojx$k3eNPvoa5f(7+i!VKu?|v2?V-{^nRu}8$L001{!oSQ zk9l~o@5fhnjZ$>hsEV5XaJ0W`$KEg4k<^|Ogz{(=&QSmDee!g;rrt| zc(8A-S9kSLoQu}*xn$zOzNcU5cYRgV?s$Ce&%=~m3v+e%BgRJutx@wYpX!--FvoVK z7ETqlJ03@eS(q-=D5}C|do~`-el66GsiN(mOiY>mTBuP}McW_qFlF{@p+->^ZTjzF z%DmJ<&6O(JWcHV#@5-LXDy-+Wwe_DYIV-^<%1N z)6c||*{_8fMOC!@k%#F@ouevz`nh;8`?XS|sEW2f-ouo6sg=4uRkX>?!<2ccmAXDv zwCQJJ%Iw!ljiM^r{>a3X`LUHcM^&`_F%MH_zgB7#RnexOi7B&RD>aI$X!|1*Q|8B3 z>Ks+k_QyO-tNkkbN7~m>{=3|FQ16WGRn+guy^8u>tXEOb*LxN9jICEuKeM9>{5sfc zc;34gt&IP6{CDHOxqc2s|86}BMWeL`qfwl@eO_2JyF7Ib5xE#&5zoiWF6J9eJRftr zm~)&5xc}@KNjx9-AN$n1k>lTu9RF^{=tY0ujU4}O<{N!HANQa2h0*+<&yW3mKRwR+ zN8{-8-F_pC`)721`1s0?ADWN*jg; zG#|Y`f1e-z{>9IaH6Q0YIv@P~kbnQte4PL2e6T;^-)}V^=RZ0h?02}o(0rW#Z}Y)^ z=0^Ox#%Je;{m#u?QxJW>*7)rFu;00n-_Oo9{`%x6|N2K9w|*!3`!rrZpWn~t?ykys z{r5F){Z&Rj)_+B>PvhwQd3V3x&dAUDpXl$`IL?1|KGy$4`D+~KKRO@lccOeXj`N+J zkM%oI{u;;m&(6pCp(uZiWW9nE&j2u;047>&K%0(0tq< zWAoXFU(-1DYxDEL{%j-uNaLgP!~SP;_iwx&-!(ovKkR=tcYjWlzviRQ_wo5*KeV~~ zucG`lALl|I{ z8vkv6*x&5Lk7@k3`CXHA|`0RYJ|2c?1)A;QCu>U!TKhyY6^TU4TAbv~Zqw~Z5<{p$gw0nRr-h6{oKXpZ>XcSnCz{hbnx3yoZOiQE@J+@VT6c zM>)H!SIb5Hp^Dlae?I(LE*{nw#_6k~=3ml37Z2;l;{H&D?~ilwuzoD=4^{a7$i&0? zu{eEI`1H@kgZZ(GyH+snAg$p$C=(Cn$1d(#!ni-QhVPH>;K9t*#a-hU=b|-yE}3{R zb9Hgo2*&-PHGF@}!-M&;i@QQFPG4*I^z-nzQlqGfntd^fxp*)?cBKYQ6>WcHV#@s3 z)m@_)eR`;(?T<`MnIF5lYZT-D&>FQv%IC{GJeVK5x@#2U^tFah|2;gIm%38dr;3`} zyy%zj;|QB+0SADNgk`*o#8Q59`}%)^w~uPZf*s%X>C!*roW zQ58P@v+-blY@yCk6>SI2!<5;tg&IXwwCR5bQ)ZnO>ZMfC=8}mi^HK|SeX3~tBNJ0* zzZPl~RnhjxJWQGWTBuP}MVo#mrp$gV)F`T=?T<`Mnf+R*QB+0SAM-F}_G_U=Q59|a zd6=%$D5}Dz|1KWPI<3^?siI9T6I14;R_gjx(e_6srp%A6)H$l6?T>kwGW)esqo|5D z{Y*@m{aUF}R7Kk#nV2#^wo>P)inc%IVan{+N{yl_+VnFqW%g^OMo|@Qe|!g1=A~BZ z`c%>8l85Pyx;|C-^k?O<1kX0ABBhYQgL#s@X4KvhxJl%f2hLu zMG9(QLHqyA7u?T+#!o3rs?M)6J^n=0B4nujU#V|QxMRMDoNi7E4A zcXy3q{Q06aYKN51m-p~s=IZXQFN~AZ8a}yscrbHycUKR_>1z$2ekLBwZQb3~gK>Xo z4c{O0@L+!I?yeq;)7Kh4{Y*TVAG^D&2jl+G8ooc~;lcda-Cd&?r>`}9`gwS4)F`T= zW?zir*?2JfwNay}infEkgDLY;8+CoEXmiQLlzFL*nk!Yb{V@+y=C(HK3supkpNT26 zUmG=ws%ZNo6H{itHfj`A(e}qYOqu=Ks8Li!n|>yy%zkauD5|3Ek9n9f`?XP{sERiI zcQDr;i#B^M87opx&SRMGZFCZ^1O?bIl$qV11NOqu=KsZmr#+aL2VW%g^QMo|@Q z`k9zA`?XV}sEW2fGBIWLYo|t06>Wda!<5;tof<_|wCR5bQ)ZoZYVuUk=8}mi^HMu? zeX3~tBM;Mq8bww3^mFlG_UoWVQ59`}WMazf*FlYvT|)r;0Y0OiZnpT7xH}AI|luA{P&9zv66FQQ!TS z4}W$p9@c)v{h0KNk<|$4Y;w!uQ9Scw9d6$3{^VwL6MY%*BKGu?sb5 zs%ZP;JxrOoy11(cqwfu>Xp@_VDf3bncWq#tzSgMum*aXS9?Xwj+|`3|e`pQgADMVC zKUVgWXXk~g@cl6l59Y_p&P^^ZGU_R zQ|6@>>iSgC=8}mi^HK|SeX3~tBNJ2R#}?`wRnhjxJWQGWTBsjWMVo#erYkjys_^OO z;=%0KN{yl_+WyGIl-aM98bwvK{V^ZYa{jlyJUhKyU-q0=-&F6U%d*lHy`t>*Gcu}V}AAegm`}a1-mzn`PEKqTJ_$)kNa=^w0phznBV&O{Xd>x zjt@BDQi1=*Qh`%075MKg6*%c}Dt2a3`+Ko7URrvJJ#lyO-xIa|k`{PVJ4(AJ_{!m5jjz1rMEf){#3*+=v zQS&e9kHW*6t2jAT_~bJ2uqH1~Ull(6bMat)tn4~ofBlX-NEN<=GVx%3>~O!$$Nix- ze1FWtgZZ(;U3U?uuQh!7nRqZicDSo<;{MPYzCY&S!Ti|q@k=s0cTj~-KNAn;#}0Qr zU3_%V8oob%o=3S}+Fl#@nu{uGCgs1f@xbP)yjoS%4mckV?8gcZRrvnM!~^@WlD;Z@ z`sd<-?N{j!Rrvlm7Y}T|N`I)r_eUlk*nXAtRpHY=7Y}T|N`I)r_s4s9U@uj2QH9Ut zTs*LsD*d4f-ydh<;h$j<8AVmp?kGkv7Z2tO{WDDB{?Hn=LrQ;S;=%mbg&IXw)b4m3 zKjvY|{Fr}2QG9gJ8a4lNbjZYm`LPQ%imIsH@i;nUV#@rOe?nP&{LmV;L(1{vJ9sd2 zb)l|L6*ZN|`!*9(X0FQfw9xfqrB78+J7g{%%#W3)yRh_C;nUB=gZVN4+|T$^U2FLM z$it%;Wqfo{Ma{mPJLKZQ>{t0LWc{Iv+99PsGVx&ctGr&;AFA;EF$xdnw)_*hqca0l z)MOu@4Wlq+UaIW*z}~m2sOgsDTqYjOOZlhi$M1cu;rnAA9?X7SsZmr#&Hi!Z&%~73 zK)+W;e00znwL{9MM!srKRpHam#KW4aIDJ+4^v}h^+ON1jRN?#M zTs*A(iu*$qzCSYYu=XoXUll(6bMdhDEA9_f`2IK-4{N{T{!oSQkN5CkUTUG{N)C_F)6d0&*)P8*d)yydqjpHS#v~ID=Ev3#`(3X>iu*$qzCY&S!Ti|j z?yil~*BUFr!=HbEo*y^rPjMLW|KK=Lb zVCHId*TTigX$_y;JUp0}THUpQar#=rr=N)jvtKJUimIsHQH)|H9yfPCa&&Z1g-<^h z4`#n^)Q_p6?T<`MnfZx>1v- ziZ+)lOzrcBUeEV6YIC2F20r`LsLeMY4R&scfBn~J?T#@?;bqH*L}{4ROX`(t!|*q-=Z@1obI`M5tu=Y#Ev-{&pLU-NPPqw~RT#_wwv z<*)fT|KH|=-HhLdEy`E(alT*WgWZbXpDxNr^Km|-^TF=L?>`siulYFt(fME}u7v-z@IN$H%b9~%kVQpUdZ=275Gj8`pi{@**`m>yTs{e^!pT?i> z@0@(9|A}9p#&Q0$^QrzP&R^p=|KH|Q{Y{*o#&LeX&8PaAI6sZ!{ATA<{ZE{~#&Q0$ z^QrzP&R^p=|IztWzZ2)Hah&h$e5(J6^Vc}ee{Mc@hp;GrjbpzyKOgMR>^@|1e`r2B zK8()~`=P}=^(4+;^Kt%+5B4*QxwkLoulbn&=zOr>S-G0!ZH^VfWw|LA0c7KkQ%ZK4EeGnve7UZ9drV*qy-Q zd^I2EJ31fickE7IasHZ*^B=HvWF=Y#!^-4QI# zU-NPPzs(2x9lPgOoUi8Ne1Dn`_A_>esW?B)$NBv(AG=3Xl%K}2{~DhU_Fr~StT=zo zNAKV9`C-3f_q>Yp*LZM}`!6*x`<*+vzf+cioAZk^^0WRY`ujDG^PioM^+Qqq8prwnG#~44 zqI@)t^BJ9w^)pev8prw0&c|N=6y>jRod4{6us_?}^aZI^=VQ5nve4zo6k=Cn#QqTo1YK%XFKsn8Xuh>_CLG3{_OSmuJNDdhyBd% zt{;o?(R}pzJ3c?`e|C5MSd_o!Xc zVEa`1LlwS1&cy@UsnQ>+@cogA2X<2>eO37MN8y33Q%O!0KDkUhuyZQutHP&$E*{u< zmHtqL?~gO_DEXsn>MkEfNfov~a`9lku;kDBLlwS1GVx%3?Ba~#_2rq-rGM-is>sE| z8nifDRrsSrCLY$0#p$cUr#}i0Yp&wtRN<4$#KW4aIDJ+4^v}h^`mwk_RN?z06A$ah z;`CMF(?1sv>&N2$P=)W0Gx4}OUl{d=Dr$H9`F}rR4eRX0to@2#iz;gV#Ri>=2eW}! z>I-vLtRKJ9uYo_keqOcLuXtL8e#P_KYro?84X0o6Jjd-Cvxv zzF+zk&mQYnJS|+mf-zk_uZHTc!I&(lk~Dy04ztWVd^Dv;_Iaf1{T(;T^hTN9XrJCF(;My68)bT< zeOmXQ@A0TRkoPNCpVnQV`)jcGe%(p7zXp5n-zn2OWqPMf>z-}BzqIaJ)vsVoH`=G= zv+eOaa{pgp@BNMTY26{A|F5v)X?+TNZ;kpK>V5_LjH=K2?XST;qw4cY`)gpPY=!#7 z%=llZPfYBM<707s;#zM$J`UF>c8xi|K9MT^`!xRi=9`rdJ`U6;UiDtT=A%!I@%iCT z&icfwUjCYo^BZ2cLD;CsOtJYd+>bIv;%gTc1eP%U|g*a{C-)E;>s4{UbI-=PYh%bYxJ!8I>F+qlA-A63+6dzCX8 z@u<(T>hrMfDki21e}tKbhxJl%wyN;io{NX|R&jr*!uQ9ycv!C$_lGKce`MletyY}A zDt!9q;$f{<+#jm&{qYVS#R*hf8Repino4nfXX9Z_Ufdt5s2x)J<6JzfL5urC6}~?* z@nA;r;_h;Y`$KE^{>a3G*{_Sc$0hC$t>OD)9v;k(UEFUEKYkaertH-yh$>gPE&~y9+nYMQiw6GVx&M>f-Lfj{8Gv`2LuMM}1ON z?mx>BR4inc%IVan{+l^R7=wCTTxDf3cS>iSgCCYOmR^HNvp`c%>O$2?4# z{kl@4sERiIOiY>mx>BR4inc#yVd|f69DUzM@qvl`Ux0!e_ z`?XM`sEXPhkK=kKrp$i%on+$Uht{YaQjQ<<@L=|9p+->^HT%cWArn((zx*Ci@zFtR z)D9^}hgo>|-Myl0RZ){I@BNv0FmvU1Zi~~`8a4lt{wO?{by}&HQbkSn@y^b~l({~? z<6`{Y*BZ4$%6mT(4`#poew%TBXbs;V^YCEyYo&fn6*c?Er$;8H%zpWubmOCg)~Fp) zK0Pw=VD_urkAk13rHa}ekK@NY#F+i^dt}E)2dz=_FGq*>@UUL$9y~jJb>>PHnRxhJ z=c8;@QQwp0n0z)K)@{Z8p^Dler9aNa!}_tfKUCrSBNGp6zvA>&;nP1C4{N{T{!oSQ zk8|;`ek|?}RrvnM#KYRJIDJ+4^he=gy;Pi>DtvO8cvvqLr>_d1{<(NCqj;l6Q5Cg+ z9@c3VrgyhzN_2Ekh0peEJeVK5Q-h|8wu3S;Wq$1Lu40UjFj}K_NO?~DJUo~mySppy z;`FtKPd^h6=Ev?Iznj;qOyd4fh3}8=;K97q-CaEx=b|-yE}3{Rb9Hyu!o~feHGF?$ z;=%mb-CaEx_lMT-{V@*@=Ev^tTDUlUt>M$p#Dm$dJ2i@`sNGSF;ygSyY7|xBvppLR zX1_LS6jjl7P$s6#er?o`siN(V?_kQj)J9#OD%xB!F=bwAqpnXCZGX(el-aM18bwvK z>1Sff?AJz(qAJ?{$i$S{uZnTCoLBX!mQVVjLdUe#N<{qQ3htAK$~@!^2vqI2Tp;T+YSAda1ZSRN?#M zTs*A(iu*$qzCW_?xPJJ=f0-u?y{4~_d1{<(Nq`xWXc zU_Vy+LlwS1&cy@!vC3pHq}XgeqqQ|8Am z?i$7T2%|M>hm<4Cckp25>f){*jC0W%K9@{9n7O*Rs|Vx$&>Fr!=HbEo*u`Bv7^kl_ zeEOMqFh5qF;?BM|sKWP0CLYY7U8r+ZMeUBq_sV&gGCy{qMo|@Q`k9zAKUS``W}hCa zs2x(i6XxMjj51DN6*c?v+3+qN%uAI%WXY+bW>=ES#DjUM@_Jc+sKWQhJUp2Fx>BR4 zikki7xSokAvtL(g6jjmo$2?4#{kl@4sERiIOiY>mx>BR4inc#8F=h7aN{yl_+Wr`Y zDRWy_>I+rTW;+T~=B2LGT&beXb{3`!HF>J=*`AFDvtJAKW2$I7C=*j=zZPl~Rnhjx zJWQGWTBuP}MVo#mrp$gV)F`T=?T<`MnIBuIb5up!AMatx%+*3|peowr=3&ab)IwdK zD%$ktVam+aLT#Wb+VnFqW%g^KMo|@Qf8=4hQs<}&pMEYL%zmxZDE>yp{_^bfa;=Mf zEvon)9@c)vOjS{j52Xt;@v!zQPG1#1{ZV*WFBK=J3ZGmi9@aX=>8rx0e=Z)@ZN>ee z3f~{+;$iJq+#jm&{gH`>wO?`is_^Nbi-)yeaet`7_s5xd+?-L2`a>19JIZ})xp*)O zccY$86>WdKhbc2xH|n-j(Iz(!Q)aGi?&`t#xUMy7{^huyi3jszH+S`5+#g!Q_s2Xu zm>;{jYXjr-wT4eW3lIDJq1WU!T2uc+z8lTR3ZI*5)TTcp4R!`wpHTGr-q&24{+KlI zIjTl&f@9LaXOSAU3H}@nd^V?1n?gPs`1fIr+Vp3nfq&oCsLgjq8u%AnjoN%?q=A2d z)u_#PMjCz}xz}%^8pm#Fem=~tXdIauzpG&M{u!Mgwkv)Yxajq1KJE|32fGo!KVHON z^D+O?`Czl+_rHts*Li8Y*qWm=<=RZ0hY<>LxbW#4A zkMkd$54J*nhq@?#&BytV&Iel~zvEhzzvkoo=jP-0Tzk!5i}Kfeod4*2us`y9$wm2VKF)u1KG+}mz2c($H6Q0cIv?zh{BChk{+f^T zADs{OM}9ZBD1Xhz`H#*A`y;>GTa>@%@t-+#UFXFk1g%&$K6H=bXg zw%QxV{MOHV#e4HHzxDI}+unT4Z~fdOpf?}$TR)#79?!4OIO&b!{;N-x=*`FdSMN^m z&By&$WPWbJF-%j}Lgx^m1?S$V> z`0a$>PWT;!-$D45>u2ygxK!X{V5z|G;!=T+gQWr=2}=b&7M2S9X`%{yJ^r7M-Z&dE z{ApNtsG{~rE*|V$r(8?+{IxXxG*(6Jjq+bV!Q=Mw9kl&dey+lPSBU==Rn!hBxx9ym zJwu6eQH9UtTs-XgY1|*G@cnTv9`@Tw+#jm&{gH`>{pJ~`uL__3xp-Lb5ch{Fe1Dva zhqX>|f2hLuMO9@ZDe{h`KvDD{?Hn}KfZ$pGgtm<*Ekog;d9BvgPALT zwR7AbTEq9pEIj;`>QT0;sL2+ics3r)e))SD;ttXpwTDUvW#Yl?m%o=K?hmcu`(qv+ z%zpVhmE!cZhEG2e4`#poooaD^Xbs;V^YCEy%io6>r>`}9`tRYvyp+E~G)_)y_~ho{ z!K{vsFdSwfxulcwqZgc&MWG z$oqI;FID~yRrp-a#RGe((jThu{gH_WwqGTERrvJJ#RJ=~(jThu{c$cH*nXA%P=)W0 z5qaESo{Zim7gt#OrHX$!e<~jTa=tL;Vf~mY&PL4IuQ+{G_)m{_@VI<@YS&+hqg+%` zQz@?RY&@*Vi~B63f~`@cvwFc zr>_d1{<(NqKNk0gDtv#;!-M(4@}zI}%~KUV{ZV)@lUJU(#IjX|&o&beX0FN|bgVyA z;rnA29_800oUJNqvc)K#jR*5%#i6kdQbp~d(m|PcFoRZJFY6Cg`2LuO2lHcBca387 ztx**<`^V=?CZ^1fUENiTaeruy+9Bm=`W_z4ZC%~iCP!zVWn4`!~e?&`rfeXZfs zpN9uCS66BSRZ+8le5z++%Iw#b8bwvK{gH_&vtL(g6jjmo$1F@2Y7|xBvppLRX1^Bd z$5hdFP$s6#el64}s-o?W?_kQj)IwdKD%xD;Valx2LcNqK+VnFqWo~PszEBlye`I3H z?AJn#qAJ?{n1?B|Ukf#gs%X>C#FW{ug&IXwwEdBZDYIV-HHxZe`(qZSD>aI$@Y#;T zgL$cyx;|C3+0Mh1S*MknJXN&mXJX3i*Gi3|D%$?Y#FY85l{!aNwEZy;Q)a(bY7|w` zrk{x^vtKJUimGV)V;-i=ey!9fs-jIl6H{itR%#Sg(e}r8FlE+hr6x}mZ7zA3-l*$S zg-`!%Jed8uQKP7ewu9zj%Iw#T8bwvK>1SeU?bjAOJN@R2qAJeD!`iPneO1)sL%GK{ z6Ax>@;`CMF(?1Un`y8a#-q2|6i$Cr=+V`@uXQHnwYt*JNBMp15`I@grZN4+oz~|o@ zwfW9S1D_3Q)aE-Q4Sc?*QJe3KH0oxv%+Z)aLthH2kh{uQ_NO`>^@>Ft?)d`b_8O{V_Tp>{c%BSLEpRX+F+>bUxU< zT*$A)8lRmXb~6|9tEa|i=ZD?R#obvF9se~SAOC-w4|X>fcV|eHujb=?N9Tjxj^E8L z%3t$w{$J&T-HhLnF3LyqaX!Dz2fG=+qg<4)=Hq>q){>AUU7UiS)IG@q^V87#cSBvu3e4PL2e6auVyQf9@ zYd+3@Y(9R+u-AMwj{VyBe6auW`=3SmYd(5^kIxVL9lyU>l)vWV{72`5{f^&9Ey`c> zasH$8!T!hZq!#6``8a>Z2m2SlQ(44c^D+O?`CvcecOr}O*L`B?uG<*#v^|JZ!|o>Q;+ zYTWv>8TnYh75)7hNAF+1!`N@|v;HOe_cf058=a5!Us1jq$NA3A2m3Lpx;V83;Dd(21uq50_jIX*w^f9`I7fGB^> z$N7)W2m7JB+aDmxU-NPPqw~T3=kE3gi1OEbod0k0!G7mX{F%mQ=ZF2yo%l12&(06~ zpF8nu8viOk>|gH0Z)tpXe%R04iQm%r-267;*EEj(+WdU5AKQpu)A;E8u;1B;KhyZ^ z{IK8Ih(FW#?EJ9b*@!>W`0V_!AKHjt)A(=m!+vKYeoW)P%@6yTjrc8%&(06~p^f-8 zjgQU``=5>YGmX#9Zzujt4 zU+n*VjknJ)W_%9k&tCay-1@VOe60V8UZ2M6{W~-Av3@7|`!$a9{b@ed&qVoX9OpAT zAM0nL{56jAADxf&KT*CK$NA3A$NHZre~sh(XXj)6Pn5sLasH$8v3@7YSK~O}+4)$1 z7Ui#Tod4W>E+7638zNPBCpjXI@)V2Pi(4*#>C=AoE1rI!U-A5g+OK$ihv`>5&w~3E z&-0{y#q*Q2U-3K^_bZ<7)?P(n_ISVdD;U$u=QUgXH5k*&=XD|dH5k*&=WpBnH5k*& z=kH_vH5k(?WqPH3dZkRSpI1`#{?aRDdi}f_q`wC1)9dFi%KbH1pI$$Iwd$?0P^JrI zx=^MIWx7zN3uU^{K3yo&x{rIG80*uz7jkcnx*Kl4f*numj-359*zt6wOjpWurA$}) z-d|~-*8PKeueR>6(yw4lZ?sSAJ_`MRg&j}pv)KDpf2WH5k)+A3<*oRoL_3a$dmBl-^ar&d2IK68&to zMoqV5n~4WI($#w?`u(9be1FWtgMHJgcUbh(*BU!ZC==X=#@cl6l4`x{FeI5PuwT4eW6A$i# zRN>P<6OVe=Nbl&NirO82K5S7g9?X6n)Q_p6?T_~`WnSu_zj>;nO>Q2h%u5~gcS2RP z>1Sff?AJlBW>7`jADNgkKX%aTE>zL>$2?4#{W|D1HL7US&%~73uY+DurHZycGBIU- z?4Z}vsiN(Vd6+UkcF=1jRneyZ^GwUN>G(P}RoGPieE5@G#ITntuT~Yc1J1_-+poey z6}~^t#RL1X(jThu{gH_WwqGTERrvJJ#RJ=~(jThu{c$cH*pHR|P=)W0OgymtD(S1j zr~e)v*gBP5RN-?u7Z2>EN`I)r_s5xduxE&rr(H1TsEXP@#W~KzgZaV>HHxZe)6c|| z`7!qVpz?0e8nr{R@nC-JLXDy-YIi(7J?3G`{1|&OSa~;m_Zs(?XUnz!iYh$ypW|Wu zSp2W3qQ3h}pT38O^-^&zs_?m-i-$E=aet`7_s6+-Sc4Y#hbnx3Wa44{Se(8peEMhN zQH*kZDsj{ws;J#jzVYSaVeMC(zA9?|CH-^pur@I64^{a7I2R9VzvBK-h3}8|@UWgP z&P5eImvix8=F0C^5O`}9`gwTx{iCAvRZ+7qMsX${%zpX3!Q%9_M$NyZKMD_K zuKccUakg5+XPb!!Ggp33zqmiNhVPGgcrZWa_iK#P*BU8{f6T*! z*)P8nYn;B;@abpb!R(jchd1sIt>OD46Axy;{4UIKe`pQgAMfG8%+=!VSdNp^8a}yM zc=&zIqij`ClP#_<7Y}Bx{I2$Ke`t-`A*DYu@nH6A{dh;eqISpQ(_A#05 z^HQsO_F#Nm*BUju@~J)#4`!WKdTpR8YW9z#b|$9GZLQQ7s-o?WJWOx&eq>en^mFlG z_UlIdm@3--$i$S{uNyUrs%ZNo6H{itZq$#dqV11)m@@lyqef8`ZTjzF%DmK#x;|C3 z$<4tOKYvK0Hr0GI@VTi*ZTd6PVCRs==Ev5x|kXHSbGxv{Tj#l&d$f$l_-CW zVJ+$p&By&QIv?zA{7!CB{+f^TXMC_*xwv~dBL13>`H#*AyO)c*zah$B^Kt&8^TF2V z;_eBF^4ENv|8Mib*5~5x>4@^xe4OvteEgnhulZ^m`?LA^U_a(}O^f(ltye6as1Pcg@TzsBe0gZ)mqLmj_9jsGkk>|gwDZqetj=Hq-u=Y#!^-_I?| zU-NPPzs(2x9lsx2l&|LFd`IVl{f^&nEy`c>asH$8!T!hZxEAHF`8fZv`S=~eUh~yB z_G{zw!T!td5fSQNEgw^BtWJ_B(!eu_%Ad z$N7)W2m2krM_H7==HvW-myh37>oq@(V?Xxue6XMLyIw{4X+C=Yjn5DJ7r)C_l)vWV z{C}Gd_BVc4swiL0$N7%V2m2krlUJ0#=HvWF=Y#!@--j#8U-NPPzs(2x8^6<5l&|LF zd`IVl{f^(CD#~B;asH$8!G6c@*cIik`8faI=7ar>-*GF-SMzbcU*qHVczWfpaqGAC zmuLQZJ~NJ6{}uiH8n5ra8TnX$6aD=f$NA3A$NHTpe~sh(XXj)6PL#jKasH$8vHm8? zSK~O}+4)$%6XmaQod4{6tlx?9*Er7qt9-0qiTGdh=J- z(7Yy~iofn%@pwF}0gC%W6}?AVe^laO{ZO2~Dt!9K;$i(!+#jm&{c$WF)<4Dlp$gw0 zm3UbD6sNBWpZ>9USUVN>hbnx39E%6Gf9+aZ6}~@yh6lDzEf-bzT#m&9TdCF`s_^|$ zhet~nIm^?VA5n!(|7bjzA8Q@LI!G11gDUZ02JPhT>We-%sG@hr-?yVF6A$LcPVSz* zIDM_r^Ka=_;=%mb$=wqe_lMT-{ZWYrGiWDw&tTjiTEq9pSMXrw>g4X_i*wN$K9@>7 zn7KMp*Qbi!9q(6td6+UkcA`d66=V99m@+?hqDD~_V}I0PdZtEE6+Zo1Jed7DQ=_Pg zu|Fy?Wk&H#jiM^X{#cD^d)EK!4o=N{KJC}M;^{x;70*w=^NQzZv3bSwYJ6VtykeVI zJm0ft6_<~9!g$evd`vz=Ekrk4*3H(!G>y?hvf`5KJr<>Pb1d=18QqfEDt_m|nf zvVELk<`sBK4;I@V12rMT#e7x*eTPUGTkZDogVu;Wx7+QJMGh* zGTmvP?v!cY?S4kR?}t9GV8?#nlX|`eJD>J_Z|7^UKJ9yV&evdl+V}sPt9j^qrsYzJ2ftodg-^c{5BB-?pL|-=8ooa& z@!+4tRpHY=77ymOxT#S^@1OUpzC28sb?W=1%&+;iM$f-pTUO%1{8-;dW!@iJ!}mue z9?XyReOTuGp*4Jed<75YrTYFT^IWus&!rBJzB|Y)eO2`A+cjM+9?X9A-C5@Sp*4Dk zwEn2XgZZ((yUV;kw1)4GJUp2F>U+D))7Kh4{YpHTAM1O=%=<%Y`2MKGgW0dXcg(y$ zw1)4GJUp2F>N}sz)7Kh4{h#5%ywrong=zcEGrl)a6*l|7Z@;gqMGV`o_G(qpJK%Ucu>ER0RN?!h5)W*@TKcN+>F42r z%~i`*6+YWMJgjwkeQsdORuw+mWAU(FD((+e`2IK+4{N{T{!oSQk4ikO{fg69g-`!j zJgohS`$HAJKaRws@7>bACye?-6}>x}QLM$o`ocJURrLH@`m6A;<|eCv&KPvHHeys0hGw%Fr!^6+4OtnXAaPhV^J^egdTeys0QGw%A5nnBRvcet*##KK)8Om>)a4I}qdk&>Fr! z^6+5x>rC%aR7KDJ{pzz4Q)a);?syY4c{MGc=)|Iqij{tlWo^@N8`cl*M;6Kr;4$IDlujD z>q7mQD#rfE!<5;ti~But{Qjafdj9SGr4kQjzx*EDaertH-yfBDFh6#o&QTS;JKnEP zzk(_AQhwk2__);?J(+f1uf&6SsS9;|s_5PEe%$6^%Iw#L8bwu%=~rUP?AL`FMOBRb zk%j3-?@?5R&-Q3MnEl$QQB=j)L6w*?`?XP{sEV;a@-SugYomTl6=V88!<2ccjov+| ziZQu7Oqq4ssL4~sn0_Uu%zkaukEvqpk4j9L{o1HeRK?gId6+W$wNay}iZT64Oqu;^ z&$Yw9j8(@IY1{+f^TU!4!OLUxzAIDgH@ z`LE5#?#>qFt8whtKF2{Y#X;#&Q1H`B?uG<*#v^|LT0K z--+_oIL(h93KGu)D9{+yND~*r-DnB3W&-{K=QU02b&!4OF!G36W&sU4` z*L<8mU^;O+0Cx@asHZ*^Ix40_CvebwLZ>Y^Kt%b^SKhgrg7}o^7Fxd?dtZFe|`Vg z`0D(y-?_T|0it|0AD!Pn&ky^TEAd+z&(06~pDXce8eg3s_Fq@x&orK$AND_2;?Fdm zogel;SK`++o}C}|KUd<{G@hLw_CHtR*EGI1zZ>yq8prhyBlu_%n@X=ZF2z zjrcQ-e>XquXKuuAX*@T-JMmu{$Np=5KG^@YyKLy{;VP&>xZJ(r*U-rKb(JDk)QQH(ch2{ZN#@#&Q0ie|A3BZ$8>YrX6}~?z z@xXqmrLPK~{wh4M8EVO?!Y5aW2lhfOeO37MkHrIftJWW?@cnTt9@uNO{!oSQk4ikS zwQA|B!l!>M9@uKN{!oSQk2*YBy2yE+-h7cNZ2Cvz!F*xs5Y|De@E!CsJeavUQP-!6 zp4;EIKF`F1nX40ZeX1DKuf&x3u@g0lsu=qt4^!sHPShx>VobjhQ|8A`)F`TA?2k%J znIAh*qo|6pKk_hTe(XezqAJGpD=}q$>_m;?Pgk^O_dH&Hk>5V=J?+=L;`wQQUh(`S zKCgIwvY1yquPx^l&+CtQ#q%9#UhzB!%`2XLI&^Vz6R^l z?c*J2z6N8uQ>JZ~Xq?MVneMbtcgl39eY#VoJMGiHKl+Sm-$8p;(f1IZS1_i1AJX|6 ztWW!1lJhlKpZ5Lg=4-G%?R#F$*I<3x_m!Eg(RX&4SFrPG-#uc!20NejC(zH=VCU2R zlDc@|CKCtc3r~$I+iy(f>_oX$L|c^&4-=6G>-Gh z&WD{xHIDPo&WBxjXdLJNSw8sPz5B2D+Cbyk`LXLajpO4lHy`E=HI6^ObS^TYnTe ze&$TR&D3~ye%KG4$@l*n&(06~p)4y5EWO)i}=g zd->SsY)AQMy!)%1e7b*$|9*|5b=H6Qa|oe%aiS9AYYoWJJd{C}5^-7_u9Pvh8+<>!O_nB6fi?hnmJ$M^dD zu>ZN4=ZnSpYd+5ZxA|ayV|TNR^VNKu@9KQ8zqy&`i^chCKF)u2KG^TrooM6yH6Q1{ zIv?zJZsz%BasHZ*^JjdpU$MJ5$NV)P^Ix40_B%K8e6cux&ByuwHXrP7><;U3zM7Bo zU7OGS?KeB<@7H*BKG=WV$^BItU!5QJH+SO4G@hLw_B(CYa(w>Rcy2z}@7#$$)A(ok zVZU-G_kU?TJ3s7K?!;ede06@<-`vUlT^i5M5Br-t@nag#&JX*YJGsA1<7@MK5I?4I z?8ox+!G7mK{FuhG^TYn+ut{jQ;P@lQtkD!{!m5lkjASL59Y^C?rysH{Gl~`e^lbZ{MgCetrz!) z*6{t2hX?axCwH%3oW9oZ=~v>x{MgCe3mEr@*6{sNi3jszCwDJl+#g!Q_eUNc%#WSi zorH1vTEnORGd!5NI=OoQM$J!{bbiqAGg!%_ts?2lHcR zYS2_Mc2FLs%zmAzQB=j4ekG>Nex0dNRK?gIm6$R=cBalz6=Q#_!j!qKGxde47_(i4 zDf3ci>iSeMW}Am8^HOK(`cyHdUx_KRUuS9*RWbHQ9;VEGovBe&#h88_rWa}yRpHY= z8V_c_F4QQhV(g$iOqu<OyUx zD#re(#FW{u3pI+W82cj+Q)a&|)F`TAOurISX1^}fD5_%Yk4j9LAG=WJsEV;avM_D? zBI94Rs={Zx4iDy~HtPCRF=m^GDf3brb$zNB)33yoxvh=*LRF0YQHd$@V;gmjsu=qt z4^w8pHfj`qqvHJXjP&-qdiz>b@ijcG{fe2Yq96UO3oG%k_A5?b6+ZoA@v!zQ?hjS? z{`eUl);h(xsKV!RBp$nSeNlg?qIXC8J@V0bSo;M$J!{bVgqAGg!?V9drJeVK5 zQiG<7v4iq3Wq$1H?oo{1JybEKUx_L6V^?>NV%#5EqjyMqf2qWS`LV0JM=|aXt>OFQ zD|j$3b)~LP6+M;r>%vM*nU}g!*QbiHKk_hT_UlUhm@3BfD=}sE>q?EHD#re(#FY85 zD|L>l82cj&(;GF4s_@w!jR&(|H)<4BF?LWMrp$ibs8LkKnEuZ&WnSt=&6O&~qd>DD#re(#FW{u8#Rim82cj+Q)a(z)F`TAOurISX1{LKD5_%Y zk4j9L{kl=3sEV;avM{|?K(V|m%3Ber;0J#JWQFFx>MJuiZT64Oqu<yJu2upeu$Ruw+|WAVU#to4T~e19B^2R3M}KUCrS<7aqabJcQDh0o{aEV{Rrvm>!{hXp?!W*1>+Kz){r)I2Mylx9 zH=}qo9?XxOs6kW3*g>l?ZFkmPU+&0kz5euL^NOb-nO8hNBhM?IpVsCT&+GMh#q*kO zUh#ZapI1E3>$8gXUif~toL4-vomViX=MM`vUxP6{e;9%J8jR`r<8#A&4aW5RaqTc$ z<3gEUKF%=nH5k(iWqSE=Tl0T~_37o~bM|}<)~A<`tMU07tWP(}bfZi+dhECB1$;DY zl<7wMbfZi++NT?3y3sz}Dbt-Y-6_+ZGTkZDzH@QhLHHcT&R-~T+z<1Y#g7NP9*OWNxSXuiV|siFyV2`?nI89c2_>mwNtyAj{Rrvm>!~+|}mcA-{`bXlyzCEyalgx~f*697?@4xvBF=n0E_c|>(tt+3+3f~`fQ-yg@~VeMDkAFA;EQHh7OUvc`X@aeC@!+NPWIaT=ND)F#h zDo$S&KK*0yu=XqN4^{a7I2I4<9OM2_h3}6_JeVK5xH}Nz{?Hn}KkD%C&jpUsS4Gdh z8O2&Wm>=^`g^v3}YxE9j{ZWYr^JD&*;BkLw4c{MM!Gn1z|0MP}7p>uQsl=`IFvR_#HGF^M;lccv-(e$8Uu*dEEAe1{% z->WX}53S+*qY@A1$NWx(aertH-yeB+F#F|qp^Vel8b19>Jed9RdyvNcp*4Jee4PL4e6aQL`^!c7SDJr+ zdD^vq{T0Wp6^dS;#{2R8^?dx!Xs_#Q-1@DGe5~JzUZ2L%@#lAr%gE3ApXl$`IL?1{ zKGyF<`Dz^Jo1KsKJ5l}`$N6XHWBpE)zs7O?+4)%i6XmaQoPTyc*8fELYaHkQSw7ZJ zMf^36`Df>Y{ngn$B{}L3&By)myL|jUV6XXU9Q(8Ue6Sz$JB3C4q50_eUY{TKKbN;B z_2Ad1@!Wi{AG*Bl6^LJ-#&h$*e(3V{+;;r>G`=<;?0+tA&+5W|zsA3p5B4*cKN`pU zv-81z=JH45IRDl8VE=RZqj8*Xc0Sne_+7@L&)1rd`(tfBepjs5d^L{!T7Ev*kNI7( zqW;i)bo~E5KkUE!K44M4nve5coe%b3e!sCOf6d4Fug(YiFTbByl)vWV{23qYr~H0h z5r56c{8#6L{g2U^;O@q2DX z`D;GT|9AQLU7}v|(>V5L`T1b~<#(Ej`a|>4@x4Aj?0@{;TT%X+kMn1Iuz&G;TSfde zAM;=a&mZ>ueq-GFo#@}!cz^${$jADh==EtF=bxRA z^+Qqq8pru(=VSd)l)uJt{;Tt`{wK;;<2c{%<#Tg>>op&ZTfbG2kM(2G>(e+oK5x!H zuE@{&pXl$?ILaD zXHmYIkMmuf5B5JdcYj)xzvkooKg$REnVY+REXqgoaX!Dz2m6_uyFV<-SMzbcYxB7i zf2MKl&+_xZe(X;CkjAs~!+z-Q?oWF?|7(18e%Sxq-Th}#zM7BT-`D4d{m z`8fa8`Cz|uC;m+1pXG=B%boZwjc4bF{mY&BEsbaAhyBi-_%n@X=ZF2zo%l74ug&j4 z{F%nFKg-Vt`=1B#XByAW5Br}7@n;&(&JX*s2k~nf&(06~p9k@48viUm>}MXtZ)rR` zKkSDd#II>QJ3s7)9>lL{e06@<|2&94(|C4%*#A6;Kht<_ey2CTh7FP`{<^24RO5mD zP9;)#D@iRQI*J-(^!sl`<9@zV|{!oSQk7Mz`UaIwnDtv!b;(@JH zOJ5Z}{bTXK)~fY~Dtvz&iwCw|tv^)Z`=b&M?7Uj~s_^L_iAT#n`c234|GT`6cRKI? zb$YW*{RmOTN<4b+&T>&j@8_1>k$9ZV(H{4QDtdSPed~@|Jo>i-v-DNb^Ka=Ni$}NN zv;I(p?~h~g=vIE#AFA;EQHe))?z8k&;nP1BkM7)O{h+ zOHLI&xnuEQuJ253pelO*yjz7lOqm}$Q-h|8G5tDB+dBsSu0Rz&{iE?<2JJ!}n<~Z* z%EOfTv5UDQIllT-#h892rp%9B%$?D*{?Hn|Lr!nJeuf8gTNiWB@+>*6;gie5gPE&~ zxg&X&zSi*RSK`6k*2UbjJnIjw;rk;G59Y@%=8oi9`dY)MUx^2^Ul(c=Rnfbn8O2OI znEkp?qo|58{W?rHY7|xB(?1#yX1_LS6jd>H&_89`_INtKz1!IN?Y~cNpZ4Fq6smYP z6R6_-6ELcH|CEF(-mjBU#rw4ss(8ObK^5<3+Gi+Y z$!HDMr#H&FB6}oll=nm_}=`_o(MnYS9|(*nd80 z6RpAe^!YSDvz1rZ56mrTLos?DsZ1($-lwQ*jMrn$Iiu9^6tjY!&mao zrg7Y<+4->dSdHWJP<}r6EXuC1G@hLwevf3=&l>+MKYRtkKAmVhJ3oAV$v%5(JUc)9 ziHw;Ajc4bF9R~A88eg3swk0?6`Ca4L`C-4voUX>R^TYn=M*N$`bMtEs9DU!S@$cq? z{S5oIOXJ!3VLx*x-`{9FJ3s7)*f-T0U!5QJKX>x|t;VzS!~TceMWXTS{ILJIlY7}T zo}C}|L+lPPjc4bF{m`AqVeqfupfGm->+zVb$;0Yu-}7eJUc(^e;(xiw4WW{ zUVh#0|NV;N*3U$*Pviamnv8s`pNal{jpKZC^J%-BT0`{O0jls%bU7XmYl!0hP(|;N z)*qF4Sbr3!uL__3v3OX&6!(WJe19B^hxJc!f2hLuM&)!l%Cq59^iU2bii^^h0moD z4`!}T?q0q4yskBTe^lbZ{MgC;RyOVrt>OD44-e+YPVP>>IDM_*)33yX`LPosZ-PSiQ7V(gDBOxr#v_>+Yye6~m9!R*(W8bwu%9rP7Und>`K*Qbgxmr6{T zmufp|vNOLbdWSR zUuS9*RWYVti7B&RXKEBxG4@9#rp$hwsZmtL*dL!~dZDgQ6`uOhcrY(@p{`FAV+ZA7 z%Iw#L8bwu%=~rUP?AL|*F;$HHQHd#Yju+}2RWbHQ9;VEGU8qr1#h892rp$g_s8LkK z*dKYAGW&I*Mo|@G`ai>zd8rF^eX1Cf%fpmerwcWCsu#`G&OW%g^MMlox}{_?!@_8VWzLlv9zg)tB7$5c^^n6+PVwyNmw z4(e0;^b7}ldHtTdZ{>lRrvIe#lzaKxIa|k`=b&MYro?3RpHY=5|7;(#i&12 z(YvGlF6n4Ito@4nLlwP4T7OjHVeMC(zAAkBm3S~ewo`+qiryXX?;bzHlzFlfR$|J`)s@;nRgC?ShbgmPS85bhF{WRMDYIW!Y7|v5_D3bA%zj;|A5+EHA9oC1jqo@j>{?T|a`*o*A zQ59nc@R_~a__u+}L~Ull(6 zWAU)|EA9_f`2IK+4{N{T{!oSQk4ikO{fg69g-`!jJgohS`$HAJKPvHH_Uqw{V%#5E z!}muO9_Kfo_@6)j{`0T5?-c&?cDK=M`l{&3xBvP%9@tB@ze5#0o8$4o=Bn{fh3}7J z@xXqp^@l2ae^lau{a8z16+ZoA@xXqp^@l2ae;kVk_G7I-RN?!h5)bUhTKcN+=^u*+ z_G7I-RN?#MXLw*Q)pAjV&*exwPH*{R*Qbi!9nJOC;=z33i5f*!jQvrGDf43|Y7|v5 z_D3bA%#WR@QB=j)A91I zKfZzoGgl|-`c%W{i77KzC+hlCG4@9urp%AEU(m6$wkmr5?OnYNk7kr{`l{&J zxA%rxJed7z-Ol<$6}>}Re^lbZ>{oletUpxY`=b&MX1~tVD5|1&$NT$B9;VEGovBe& z#hCujFlAoqOwE-l#^mxaW!94h3aRrvIe#)J8>3pHq}7&|BrQ)a&|)F`TAO#f$?GB0(Z zu1^(Xa(S3CFLj}=PZeYOm6$U7b)iO46=Q#VHPhS6v(wwRFZN&gzgAfL6|bR+o^GRl zEFRW=#r>fQ-yg@~VeMDkAFA;EQHh7OUvc`X@aZ3k$L5S;)E}zo-O;{n`Y9gPI>ouD zq9@aGITjD=rQ-fjh3}7J@v!zQ?hjS?{;0&m+OIf$RrvIe#e;dNjhZV}^!|CjF090q z8MKW$HdT!Mk%uYsW1G82F@As18a@B^=_C&iX1_Lf2V$JQ*6`{73=d|mHh1@6oSfG1 z$<^VpQ`e`8o_)KfI~osW(01zBR55l?9;VEX?e6Zu=-opVWBQetGC#JvdlcjT&>Fo% z+WSi-9?YQa?k>i-KeUGLk32k>{o1KfR7KDJ{p$1knc625y&jPowTWb;fv-L_YV*xV zgI!4uzT@4+eP_nKF)u2KG@Cpz3rm>H6Q1{Iv?zA{9bKQ{+f^TU!4zjJAU`N zD1Xhz`F|Ckb|ravc~Vi|qi#0-{Oms)e|{>B$NRoMv+?Kk>umga{WBYXzCX^!pXbln z`1AOhjX(L%#-HwMHjerAXZFVP`%_G3+2lB%a^zgP)D#{_FPz z&*tO)>vs;$=Hvd`KYpz^n~(c%C;hj7{H`Wm|N8OEi`h8lcm25YdNv>PyMEkxIh&99 zT?xPI$FJLF>*M~r5`H(r@AmP#g!tdT5q>vv{N4z^+sD0)vwt5Szc<3~M*8nY_%;86 z6KECq9NMlMo|ZCxm8}BzajU>*(pG_cxmDn^sVeOE1%Lnl6(2sn8!=UMYRBV&&rgkq zDtvz&iwC|wYW<-K-yeB+uqy-h>8qu$HGKN3@Zi^Us_@Cx;lZp&`&Ncs(W|0&N4t`) z#e;oXV_vNB&>Fo%s_|f-)i?TSUKPDN-p?O-m@*H;tam#av_{Xr8V_dSwzvG>ztx=i zLRIwcct1N-BF2m&`_`)+FIuB_$j|X$ZmU1rbADuN4WC>d9?V>^Z<|}6Y7L)$9v;kG z^{0Q%kA1D-)33yX`7w4cNjp1e4c{MGc(D6`+I_yvD5|1o->&&<@nANvKOc1V?xBjY zKPoY0_KV#q*p3&i(K{p;4`u`V^DyUU2d&}L{}~?4OR+n2Tc2tTpIjau%)<32cg~Mn zyT%s$0>!VPicCDL+lrG@g+KO>#lzaKxIa|k`=b&MYro?3RpHY=77uH`;{H&D?~gh> z{4e98^i|QbZ@%zoJgohS`$HAILt20Q3=eDJ;#^eWb2%0d>!srUP=)W0WAU)|EA9_f z`2MKGgW16An=kJ7j>i3=3f~`;ufc`HGKM&crZWapW+wyht}}@QHclhWBw_QaertH-yeB+F#F}7(HW<&HGKM& zcrg2Qb5A&o`$KE^{;0%**)RW$-nc)shVPHB;K96QTQi`MYDDS?LcfU4{(pN>#z8S@%@nH7rPW_lF#tzEEl-aMl`z>*N{?Hmd|91YU#Dm$dyL*0N z+#g!Q_eUij%zoY7Z<^!&&>Fr!^6+5x>rU@cR7KDJ{p#~)m@+SQr>;*GV{&&*9@nH7rPVXL6MemOH^Liep%zoY7(+T6VgVyNzx3fbX9uI01RnfC= z$NtfHF#GkOMo|@G2jyYP?AL?(F;$G|S7OTS*Mk~GRgC@d6-=3RdQg+6iZPc;OqrK@ zP}ir5u|Fy?W%lbqjiM^X{>a0W*{=unW2zX_uf&wuuLm`Xsu=qt4^w8p9@LMiVobjZ z)AO58v^%1_`eaqu?Ek*`lcN#C_N(#u>Wcm4`Rn7qqKf}GlNa-_=1LVuBWAr+oW3gh zxxJlXD)F%PD^6b(KK*0yu=XqN4^{a7sKmp%tvG#E`1Fs(!`iR7KUCrS<5)bb{fhfT z6}~?z@v!zQPG1#1{WW-;oa>8{Q$^3MxxQLFtf!09S4GdirGG3Q%om=hb5up|pZD`e zC8o@eov1-m#n>Ntm@+?ha`!04?=M=T=ilC6D)C@`tnIPg_e_cVLlwS1D)C?jt?doR z`a>1IKl1QkeylwUoTaY{pZ?GAVCJg*!jdJY3ZGma9?V>|Us$sARpHaG!=v3bfzww- z&%POfqw!z{t$hk&9i)ohL#>1I@L=|r9QJD#rf!3Z~3DovF!F#h6Parp!y7sq0h4*dLXcGW&I=Mo|@Gf8=4x z?AMtZMOBRH*I|00Mo|?${iE?<_Ul6Zm@38&%EOe|uM0Jbsur=(pA9^DYIV}Y7|v5reBBYMvbB>eEOMqFmtt08>osg{Z*JUFSSwEr;0J#N=%u#+Ncdw z#n>Ntm@@mdQKP7eG5tzRnf=U^-9@jJIg`D;GTe|0|C z-T1xiqWm=<=l|P$u)Fbl(M9=cKF)V_KG^N}-RPqHH6Q2y-F&dS@q5xm`Ds4R@4NY6 zH{*Aei}KTaoZs4f{4Qv(`Dz^dv;2Ip-|>5#Mg5`q==fisAND_fU$`iL&Byt#&IkJ+ zzpGo6zvkooSLcKMkKflV%3t$w{=dx!`yIb8Ta>Tn<9t`=gZ+=+|1HX2^Kt&4<%9i< z-+wL2NAqz$tMkEr$M3He<*)fT|JC_mKje23=BIJ&*Yfkhe$4NH z7WIebqvLyhe%Sx`J`LE6g`x(DmS(Lx#vy8RPvbb>@8)CuOO%hsaX#7k zSpO2`uW_9J>U^xvy93HIDPo&d2(%D1VLP{Im1H{><+-74?Va~44a zD1Xhz`LE6g`<>nGZy)8a`8fa8`C$LEyItX<{52ovkNI5P9*3`dHIDsOem>YwUERLx zQGaMYI{wz@hyB=<_%)5M&JX*aEAeL<&(06~uPgCq8qdxT`>!kUXByAW5Br}h@oO4i zogel)SK`k!{@whrf4LIBrSa_in19hY{`{Pq&yDysjbp#IJ|FDAZp5EyJUc(^e{RH| zX*@eW?1yf|uW5XBe%Sxqh(FVKc7E9Z+=xHZcy@l+|J*+OS=-6zKQGURx_$VU+4%GG z?QHz{`6nK~e|)}}jX$riX5-KI-`V){{5%_f9^bR^Xa2MCC*Rrl)6dMtF~9rA{Uh=G z2jTblxPG6_$NU~2@Bg#;nBU{${4$%5`8`PgJwE)?Y<=8+t>>Sg;Nlfp1@6ICfho2M z+=s0KlWY~Z7h46U*(z{9whG*lt%5OaHSbnr#`Hv)o+#74H~joxVNCn}(rt~?%lWVU zf0k)nVVTAimT6pJnMM_TC&JlZ+W!AeJzm51X$AS!PJI5=cy@mH6CnFEqw(zg@MqD!U(xLN*L-yS_51wr z=VN9XG@hLw_C$R@q}lPU`S|!=oe%a~%o1vRb$;0I^!se06@2m7tQAI~g*%}2-g`uwop>H8JU^4ENv|LT0O-|71q z&GOfLoIm4({Yu|YXvSajG5^*1U_aCM6Po3(`8fa8`Cz}(_Y<1sulYFt-{yn;P2W#w zmapdHd{^g#{Z8MnXqLa`-?Zn6L&yJs8o+s@8eU1Me2z{Q9 z^d4$D;f-ALswue6ZiSyXTih`D#AScXdA4|J>aUyHWm{ zkMsX5AM9uD?*6YRAI-=4{4Sq|+j;&qKaFF5m7fpxUk~EXG@hLw_B#*a&osU|KkRQF z#E)q_J3s7q9>kw%JUc(^cOJx_X*@eW>~|i-pK1KF{IGv{5Wl7I?EJ8Qc@V#)@zwcZ zfAb)IOyjxvo!m|nywr)BJXMV8S7OTS*NOTni7E4ACu$UbqvA3=vH1P{*1i^1_*`Nh z){m*;NT!IXKaGc{ML7;~w^^g>;qDt!7! z9h-T0Fh6#2_bA5c zYYm@%B_7O=UEDp2aertH-yfBDF#C0(Mo|^LJDOAa8Xn9`U8w6*#h6Parp!xSsOwY3 z*dKYAGW&I*Mo|@G`gNFY)F`ULr++ja%zkauD5_%Ypgc^O{o1HeRK=KnC8o@NZPbsc zV(gDROqu=Ks8LkKnEuZ&WnOBdu1^(Xa(S3ClebZmr;0KCN=%vk+Ne=f#n>N}m@@md zQKP7eu|M)KW%g^MMo|@G`gNG@)F`ULr++ja%zo|ED5_%Ypgc^O{o1KfRK=M7&oE_P zYNxJG6=QOFm@+T5Q`e`8G5tzRnf=8rx0e=Hu> ze#QNv3f~{c;$iJq+#jm&{qZwAte1*&QH9UtNIY)N^+o-miryXV86vfKSo;;HuZo_3 zOaE9rtWk{nLlwS1D)C_U>qh;UDtdRkzk5_-%KX^P-J=+vKeR^gkoNvki3jszH+PR> z+#g!Q_eUNc%#YpN9f)!ITEnORGd!5Ny1BatM$J#Dn>< zo4b23?hmcu`=btzJ2i@`=-Ic=gtd4uKX#`EO%-E*RAS2f*xlWu7`=O_V(gDfOqn0M zQ|G9Pu|M)KW%lb%{g^7o^nZpa^HO)}`cyF{mxn3yQg`b5R57Msi7B&RcWM+>G4@9u zrp$ibsZmtLn0_Uu%zoXeQB=j)A9a{Ms8LjfPrnuqX1^ZPD5_%Yk33A7+j>x6sERTD zpJB?Z(}S8kRgB41V#>VKgStLdjQvrGDYIV>Y7|v5_D3G3%ziznQB=j4ekG>Nem$sB zRK?gIm6$R=_MpyD6=Q$oVan{+gBnFujOl+r)AO6@`_G?$|M}P3v3Y*8Ikn1<{;0$Q+pm_sDt!9K;(_f~>kn1< z{;0$Q+pm_sDt!9K;(_f~>kn1<{`eUl*gCabRN-^^Y99N`v(rcFzgc0uRQz|S!uQ9K zc%0tO58Wt6{h^B99nC1#;$eMZoW3f0{w@7u@vwd@?hjS?{x}v7>&N2$P=)W0N<6F| zi_=$yPybjvtRIW}LlwS1eujrNS8*M9?XxO z+}(q52Wbu8L3MaE_l=FBDth+KDAwY^{8)2ntUpxIJEZkTB_7O=wb#q~LlwS1D)C@` z?CkDQjIJ)KRBZbJGh2f(y_jq5c#VxR-OT&TYz@YAGe_lY4aRh% zOgD26+U#FpeY%eD`pbk;#yqxVqjph`U0XOGqs_%o_1dUw2^Ve$}TpDXPXPiJQbt?leEP@Yf$dl84^{a7sKf)?ua>?leEO^Kz+S2)rwX53 zB_7y1we(ft(?1puY`{vMPFSwEwEcgZV=C zJFmt=YxEw;#e>*-mo^So3HGF^M;lcbEdp1H#Uu*dEEAe1{to`B?{Vu8Xhbnx3 zRN}$>7=Jd3DtdRke`?IawE1Fu?5o0Odo&)*2DWzx);K>8aw)b!jyR_`z+Gg zzoIpKE|qvNPsg7)ri$Jj?Oi<+4`#pq$&**LM$iABJ*(CdyU^#|{$_=>U-93e3ZMS5 zcv$-t_lGKce^laO?N^+>Dt!9K;$iJq+#jm&{c$WF)_%qPp$gw0Kf%L4gE`7Y6+M;q ziSKAUtf!0nLlwP4T7OjHVeMC(zAAkB$Kqj)V%#69@cmJV2Xk8&cL!qJA6morMf{$isvAF~6T&oW9oZ>HiE5X09&o-oQ9Ht>Kf) z!-IJ#zlUR-zSi*R*Wuy!=Zw-_d1ekC5vkNKUML2LB< z+xvbU9=rQJa+JO*diL$uKN=5azjo@!R55l?9;VEG?bIl$Vod*Mm@+T5yC)0AXMU~G zvukJmJUp0n+NsG?MbG~IeZLY@X0CSXwp20pM-Ha;`9rT~eT~{w>(Rhho*K33XQaWd zE%CSi8twV7NfKXyYP9F~mt3u{$qHX%YSiYNkp{j-)Tqt(Gc@q`yBf8eGt$7{&uY}> zn~?_oepRD3-;6ZyH>eu5`DUcycg}nDOd7{-DL)@(Pc)8fi{BM6I(}B?hy97)_bz&U znveTqbw1dy_CMskLGy9`tMkEr>Fl2A66LS?IRDl8V83*B&uoeE*LU^+YI=g3(MEPqz z&VOw_ekZiod^L{!+~@gV|K)cgi}KNYbo{N)5Br~sd+te;zvkooSLcKM(Z&6`Fv?%^ zasI3G!T!kaz82-L`8fa8`CxzMcUOz@*LU^*t^1G)+`D;GTe|0|C5BdGmqWm=< z=f651?1%g=Y*GH2kMsX5AM9`ZK50=tnve5Yn~&eu>os4EV?UOk5B6(**RH5PG#?%R z>+{3@$nSI(<*)fT|JC_mf8=*Ei}Kfeod4>4us`zqkVW}xKF)u2KG+}my}6?NH6Q1{ zIv?zh{GMo0{+f^T|12Nucl@4YQ9hcF^I4q__B(z@u_%Ad$N8_$2m2$xhgOuo=HvX= z=HqwCdd*kk*w5wXgZ-M{6D;Zv%}2-o`uwmz^1FgX`D;GTe|0|CANjqsqWm=<=f651 z?2r8JVp0B@kMn1Iu)p!UcSZa)AM;xZKJHIDQD zZa&uEMEPhO=aZd}^+!?u8pru(=VSd+l)uJt{@M9hzZB)Kah!j4KGrWq`D+~KpPi5O zOHuwB$NA^xb8~*~HGhp;KUa|t_HQ@h=QRG^{ILJIx#zz{{i*rr{JlOu?0;_V`EODF znve5eoe%a)w?7)k`DW*X{nE|tzYrb&nveTqbw1cH-Q4|iQU02b^Ix40_DeT+|6G*6 z=HvWV=Y##y&D}p2<*)fT|JC_mzjSl=&qeubKF%NWxf4I8aqP$P^TB@SPW+h0v-89L z>`wff#R?eogecz8b|)?PW<8O;}7EJG>-jTem>YQJ&2#vcy@l+FFlB#(|C4%*e^YZ zpVN4De%LQPh@aDVc7E6|J&2#v_;>Te{^vpbnZ~p8!~W+%{F%nH^TU4WLHwM?v-89L z?LqvL#&h#Kz48rx0pN9uF zOD$Vf_-rfjz+S1PuL_@jB_7yXwe(ft(?1puY_(c{{BIRk_Zg~@9oJBWXZo8wtka7B z4psQG!?Ac+=N0#dDtvz&iAOuL_j?+n{!m5lj`mJii-+}var&z0`M2~};bF~HoSZ6r za+P>ka}}qr3ZMS5cv$-t_lGKce;kX4^_8G4@9# zrp%9>-Q9!Hd0iD_e^g@14BFY*BUkaF-9A2N z&(~l~w~s5w`5KJr_VJE9UxP8-K91Y@8jR^ineLS7PMPi>pI&Ew=}wvMAJ@3^HCUhS zAMb?oHCUhS^w{4i(<^0qrA)7s>6J3QQl?khr&r4KO8fLmnO-T=zQgY<+rG!^yn-G3 zeV@wt8tmBbd)>{~V8?#nFKfOAJNEmYJF_+Vt|#*f_8!%Dj+n2(-lO`{=jUs%W4}Ma zdcFob_WM(I=WDR{sQ#qNcn!w9@5C~jk9)Z9%}(0F!!_$=R_bU!=(H6I`Uzs(0<_ptYHjej>ke1+7X)IK}@G#?*-zsrYR-)j8% ztG~Fv^Yg)<2>X-jXRlxL(eb@LKm7T#KdF9}zvkooSLcImPJdGUEPu_%`TsT_?1%c3 z=x6zAKF)V_KG=WtC(+OH*LU^;O=})?!<*)fTf5r#g<5~8!uLld9@t8?^i|>0 zKNb&cty+Jm!uLld9@uHM^i|>0KN63YKXRh>$?CCHRz>fg_FvU_Fkjf8y*}>`t#KRiJIDJ+4 z^pC}Z`LX__`T13j*6q9)t>M$J#Dm$d3%w^#6}>y&uRilI zW%ldhe$yPE9kfQzzg;{03=ig|F7EfpadKM2Czpo@vrZTHYvVY5t>M$J#Dm$d=KuRI z%HsY|h3}6#Jp4YbQTnRr*|%%DT0EHj^1JlL{h>8_hqV5v#Dm$djruWF^zL{+f8=4x z+?L;eJ3c#Tjh=ryJ5=Jq?AJz(qAGfKyq_I@hAHz>8+CoE7?aDxlzFL*nk!X|=~rUP z?AJz(qAJGz$itM`uZ#{Q_obaziUj6M^p!lz%02eV&0^<%0S z`=b(5X1{i76jd?y$5$|AUTUZ2N)=-+m6$RwwNuxpim^W`F=h5^r$$i~V}Imf%Iw!p zjiM^X^eZuC_G_m`Q59o<hQQx zbES%&efvGo(ReUFcB2MO6=MfgV#@s3&D}j1y}zhp?2kN5nIF5kdlcjJwMNgsy}wlA z!Ti|G-J=-yht}}@QHclhV>fq?V%#5E!}rH3Jed8uxjPW!Y_*2Z_Gfr7FLiVG2FA&0 z4WC>k9?V?b+}(q5e`pQgAC-78KX!9>561nWHGF?$;c=%%Q58MeW)zRcgW0b;HHxYj zJE#&riwBBpJB?p)SbFMRgB5yValx2otivVjOkZm%FNZB z+CWu|{ZWZ2^J91F991#)M;@lke%+~2RK=KnC8o@N-KkMj#n>NNm_DdcRE5v>Xgrwx zdQhXNim`*ff+@334{GvMG3HWiSeM_D3bA%ziznQB=j)A9gOmufsz(R-vC4{X2Mt5tkn1<{;0$Q z+pm_sDt!9K;(_f~>kn1<{#cR6eRw|m`==!Pm&O&=eyQR=&Y!N$!+NRsFI9y_d1{wh3}4{CeEvCj>v@Y&|!!CYT^ z4lhez6+Zn+JeVJAPwis;p$gw0d3Z2Cc5?Ry#_#)D!>3<|NBbTSAN#84**BwjG#<>4 zHHXGJNEN+@S_kFf!TeZzH7tEq`1C9BV1DfE?oo`cE>zLGRpPI+rTvwuHpS7OTS*O?kcRgC>ni7B&RXKEBx zG4@9urp$hwsZmtLn0_6m7itt$;nP1F4`#nE)Q_oR?4Yk;%DmKtx;|Bmxm04xywrud zK2?nUk%uX>Ul;1fR57Msi7B&R7itt$G4@9urp$g_s8LkKn0_Uu%zj;{QB=j)AC;Ig z`*op4Q59o<a0W*{_Wn zMOBRHe+5%!oi=LnR59jKi7E3^8+CoE82h6R)14YcRrvI4@nH6Ar$$i~V}Dd)%Iw!p zjiM^X{>aJn5j+`vcfL>+N8@4bSDd~o`qAHh<9jR~)_%qPp$gw0-_OH7f9N$6jrKhL zy3a;6SlMgS*H@%bn|?+b_S*6_Uya&)Gt#i%HoxYpQJZf@8u`U(e4PwfSbGVZX6`%~zu~-_Ovn-@v|d)~My2k%s*S^)+9O+I%z8@cY2MCaiI6 z+Vb;Z_C(|T7k1I{k)02=D<}88arF8%ANR-Ve6W2vk#CMQo}C}IGbi#*sK&GN!}jLn zeoGRa|1}?<|5xXO?T+6eFUnu@asG@Cwl98~m!HGm4!!f8jXyu%&c>ggzh>jl>+{+8^ZG3w?|Ved z#-Hzxv+?KoVK)BkpV|16|7`r}e`e#DUw^vmY(D1KpZ^%o@6X+vjbncOIb^f>m|uTV z(QH2E*Pm1}n~(di%|iX%e^Vc?-+yI18^`?muP$fvF~9yxrP+MUZ~u4}%xpg9w-bK* z$5RX9^{*el-I$GIe%FuhCuj39zw5{M8?*VC-<9yYemreuwm$B^E8%w|{B9q=3y=T( z8{v2R`2KG;AD{njAKxF$=Hv6Sy_DKF)u2KG?7H9qVWLYd+3@Z9e?_HS8ZW zKRX}nPx_AY@$s+m)%oGi|9$8BS-zT&&hMY+hy6?6IewOp=Hq;RlF#Mk{u-ZOG;aNn z#_jVK+J9f%_oo&4SbrA1K8^R|yCNU!hoaY~ah!j4KGqLK`D+~KpPi5OLs9-3$N6XH zWBpK+zs7O?x%v3}vtRSqxbZWXnl>NIe%5bAf4|0Y{@M9hKNRJ! zah!j4KG?tc-!Db|q4~H!R_BBLTHi^1_Wq{%IRDl8V1ML)e;6JAnve5eoe%a$eXsP{ z@vr$f|JC_mf7DXPuTSHj${rA@4p() z&JX(||NM;T{Gj>h{J%aw?2r0R-m~Lh^Kt&G^TB?|KmR5={xu)xzd9f6hj#b-(*LU^*tx)T4U@z3(Ze#Sq4JUad~A0L0K^TB?|KVLq|U-NPP ztMkEr=t}NC(|C4%*bn*rA)@17^YQV&HXpyg$7{YC$NnupAMDTk{w`5}Xg)gr*XM`* zkl(*2%3t$w{;TuBe#r076y>k^IDf_m`*q4^vHmRj`!(K=@9*Ga{Y+z}a?EJ7ldi>EiI{)V9gZ$Lf5rKYF@%LgN^d31L4{Ycf4^{a7sKf*N zrIx-beEP@Yf&EkK4^{a7I2I4=r&@og!uLld9@tK`^i|>0Uxf$uN-a56_~a__z*ecH zuL__3v3OuB*7`#gzCY^lXz3zndV2Fks<7!FjR*6EtwUG`slsO@_iD#re(#FY85 z6E%ve82cj+Q|8A`)F`TAOurIS=EqLdD5_%Yk2*}x)F`ULr(cT)vtMUw6jd?y$Imcj zuJ24;pDM=W@-Ssy>P%gqD#r9HF=giJOl_bl#{Q_pl=-nUb&jeS`y&riX1~tVDE_Y% zyZbFrBiFuJvww#w*5P68SDcF~`qAGy`B*%xAB+1#6}~?z@v!zQPG1#1{WW-8oa>8{ zQ$^3MU7^(CVZBtGzAAeDE&XHhu=XqN4^{a7sKmqCuQ+{G`1Fs(!`iR7KUCrS<5)bb z{fhfT6}~?z@n9zJLS3IKdUw2k_Nc^^`LPQ%XsQ_d<13glFLiNu560(ptf{$iiczzEBlC+4i1&G#<>4ZPcKtV(g$wOqn0s+&zlXyN4>q{>a0W z`LWI2qZp^JHG2N-{iPBQ=EpX7k7C>(TEq889v;koZSD@lIDM_*)BhPB%u8+5^{Jxg z_Wrpc4^w8HHfr)zF{WRMDYIW2^<%0S`=b(5X1_LS6jd?yM;4|#HHxb6*&dAtvtK(k zimDhps1j3VzjkUARWbHQ9;VEG?bMH{Vod*Mm@+T5Q`e`8F}XZUnU~tB>r=&;ekG>N ze(lsKs$%SqJWQGW+Nn`g#h892rp$ir)F`TA?2k%Jnf=DVAQi&<^QdjEwR5A8PC8o@NU8zx2#n>Ntm@@lyrAAQ| zWBQetGW&Ini7B&RS85bhG4{vjnck@D zQ-!B~G#<=L-KgtR#n?f4m@@lyqegMfifi!fbpMyC;-B!a_A4f)ihlIBJs~Ucux=|( zUll(6WAU)|EA9_f`2IK+4{N{T{!oSQk4ikO{fg69g-?GK9@b06$*IC8SBZzUPI3CG z@aZ3k$K4sls6SNEyQ4j+q!thBw&L_v(erQVAB%@IigACa!uQ9qcrZV9rv^f{_zE7(OWobQfpIQc!{<_o2Qyc9 zclTi2A6morM;;!`e%;-@fpPj;!>3<~2lHchcW+?aA6morM;#syY7|w`vu~gHYVlxx z>_H8hD#re(#FY85hr35HdiPMp*dLXcGW+$QMo|@Ge|!Z~=A|CgT&ZHrr4m!-r5@Dv zsbcJpJWQGWdQhXNiZT64Oqu<9P@|}du|Fy?Wq#~Iouewo{>a0W*{=sRimDjXufp{F z<`e((=ih(+_5Z&cZ{JMXSK9tt6`n{n9@u`hSF4KN0W0yqUaI}2s_@AjiwE{ntv^)Z z`=b&MY`ETNp$gw0 zm3UzL)zVjmPk#*_r?+IV>r+L~t+~%yJebKlQP-!6u|Fy?Wq#~LjiM^X{;0&1`LPo< zimDjw{KPShx>V(gDfOqoGDQRk?Nu|K|&Y1`%a9NhoWp49vP zsc~NMv>Wq^=O^GdYyPi1-*4v?&vWv;;(1igE1tQ`D;U%Bhe4aK z!I)ks(+g#K`MBnv{T-K&tG;;!V|w{`Zl9UEo3QKlPZx>2Uv z$JN&SFJ*nYeVlRUYp_1uDASEH-6_+ZGTkZDoig1i)1CAwK8LaM7dpG)^AxZKJHIDPo&d2(pD1VLP{B!eZ_g7iN^x6Tcu=i89-6Cocvwkg3UlqLrTKdQ0 zf&E0KNb({yjp*#!uQ9Kc(nYHGi|@wRE6!2pW?yHmH#zuWCK;v zb89ZR77u2w`jgw*-I{TKXpP<>tvmAYV1CU1Rz6N&Yxwjl@nC+eKe=swcF-EWKPvHH z2F*V!BR+p<4c{MmcrZWKpUXBsJ7^7`ekC5vkNGFz#AgSs;rnA19?X9Erx?ZAY7L+5 zDm<9E@=u_Ov(*|t+d4e_^Tnd{RnfC=#;6t#W)%JNSmXZC8ofhWe^lbZ?AMw4F;(>L zct3ySVan{6e|ltmcF-C<|8{n$#Dm$dGrdPq6}>y&&kmKCGW&I=cQLAB?2n&e%FNZ7 z-e0JSF}XZUnU^}#y9ZS zJeZfdP}ir5o=UswtHpzPDZl$)eB5e{-XX0&^6+48>q32@Dth+sXNO8mnf>zndd6o5 ztvAsN@eEdt}3hT#I;rFnu&%@fU_|>YyANxn*;df(>`a>1HJKD8FEgsf> z#p$b}=iky_g@^T0adN8g$yMTEty7%7Dt!9K;$e+q+#jm&{c$WF)_%qPp$gw0m3UbD z6{oKXpZ>9USo;?F^HL2lHe5+qdHV$+dC%s_^Mo z;=%mb?(R{H`$KE^{>a0F*{|K*PZy`JHGKM&crZV z!uQ8l@L*nQr>;*GJ(YK>P>Ct?Qag2hsu=qt3)3q#imLG09*qaHUsq}rRWWu@9;VD~ zU8((2#h892rp$g_sZmtL*dLXcGW&IDt!8D z@OU`a7bT~Po?CksK`kEEI>qU$qUYbzKNb&bzvBK-h3}7J@v!zQ?hjS?{;0%**{=sR zimK?{@qTqti7E4A4{Fdvi`MYDRN}$R)x+IA825+P@cmJR$N9}C{>S`Y>@|H=^yJ%rRpWvESbMdq z=pAr89@vjH9;)#DaV#F#kG1|#h3}6_Jh1(0>8rx0e=Hu@ezpEkh3}7_;eowW%S9DF zmt*n3UaIwnDtv!b;(_f~OJ5Z}{bTXK_N(=WDtvz&iO1^DYIWE>I+pdrvEccnYlVq*Qbgxxk^l#xoUgCv+F`t z^bTp)g?V@|KX#%Go(^o~$zFj-4!-JWtcAjF{s-macvdzPTd8zhlSo*5)=~v>x%+;CN zKvneact7*!Van{+nHoh^jOkZm%Iw#f`Y~0E{gH<$vtMUw6jd>%Ux_KRUuS9*RWbHQ zC8o@Nov9yF#n>NT!IXKaGj)Bc7;~w^^g>I$o}J!4Ra)n$il5?P-BwIp75(UM zeR?b&)_%qPp$gw0$Kqk_SKJ?}@cmJVhqYgE`l|5hAB%^zUvYn^!uLld9@c)v>8rx0 zzX}iQrQ+mN;ghSx!&;{}eO37MkHy2JeZf- z+`WNuE?UFqQi%sMSDU+gFzyen;rpW!59Y@%-0-xn}CK33<4?TO#lE_!{M zkNabFKG?4Ko$aFhH6Q2C_+U5U_os{aYd+?`Iv;FS{C;au{+f^TU!4!OHhu@XD1Xhz z`LE6gTOGf{T$I1&F)hkp^Kt&a%?Dc_zl&Uyujb=?*XHAQJ$ubJ*Z3`X zDz)`r8n?c;{kPv4E#hPSkjB4{-}UWY*@*Ac&&%Y^B=l5Tw&Bk&6^w)e|N&~PWask zzdPY~C;XZ}#Yb4Hz&+9&-190oPPtX!^L(qoN7`3a;P;F6uc)G5Wgd?Qe!puxRN?!h z5)b@t+|pNtPybjv@YQVV4^{a7_!%DfD!ApM3ZKidc(7|+_Bp9_kk;@WREY=wgrf?d zejOgnakP63*ymeS^zQik_F2Cc59ThI1#3LCM(>bnJeav+7PRru8oodB@L;}>IqsIe z*6`_9;=%kF`;Mda$8p!VzuZ$Z^7y}2SaTJxp$dOg9*c)HS8;!+!uLld9@dY=>8rx0 ze=Hu>e#QNv3f~{c;$i(*+#jm&{ZWU9zw0MTUll$3<_nL;!`i^OKUC2>r1i(Kcv$-t z_lGKcfBXy&>!spcRN-?u77y#`;{H&D?~h76m>;{ly9eX`&>Fr!D)C@`?C$O!jQc}t z`2NVlgZZ)h+xI;Ew@`8Vs_^Mo;=%mb-Q9s0_lMT-{ZWYr^J91SJFU1sw1)4GEIc0W z4#X&1RrF+=QCx=yGglAlwp1}@n};d$QV)0MUwmY1jh=ryvMcdme(d4y4UGFkYxw@C z#Dn>;rpW!4{X0$`l|5hABzXJU#&k>;rrufcwp<) za#4lPkn1<{;0#F@3P*WUmY1mRrKuNcco$uwiYqw3;RCq z^A6G)y@%SqW_frpKh}4-pQo=ieEOAmFh6#pMo|^LJKo=4@-Sug>qLE_D#rAGhAA^w zZEq*^i^KLVriz|jH6F}dwOtQbf2hLuM;;!`kG1Elvh-Eq)33yX`LXs?Ce|OS@cmJV z2lHd?ms+epRN?z03yM9@bpN{h^Q^lBm zC8o@eUEJM+@%xL`=pEADUn=one(d7zFO2&`Yxw@i!-M&;i@O6cPG4*I^egdTe(d7z zQH=XTYxw@C#Dn>diKpI9*qaHUmG=wsu(*c4^w8pHfj`AF{WRMDYIW2^<%0S`=b(5X1_LS6jd?y zM;@lker?n!s$xw4XP7cCwNclniZQu7Oqq4ssL4~sn0_Uu%zkauD5_%Yk33A7{o1He zRK=Kn9i}@qimLGGAB_jIUpqC5su(*c4^w8pc4`z=F{WRMDYIWYHHxYj`{OH^GV8Qc zlc$O?mr6{Tm)fc8Q^nXHIhfk#553+$qEVY_JsSARQ=>Nhj5OG_Wq#?u7HvKhe z;A=yT+5|Jwz}J`>wfSbGfv*uYYV*xV1Al9*QJe2)XyET>HEKC$q=CO*)u_!kBMtlw zszzc*75Q|366d4wr;Dq}r`wnK z^=TaEzdE08U*dcU^-@vAdYX`D;GTe|0|C z|JZ%Z;`}uq=a2c=eXk@Ht%e`r2B{?_M*{g2(}E6!i@asI!}2m2kn zPgk6;=Hq-<=Y#!@-G?jAU-NPPtMkEr$L_=x=dbxV|JC_m|6}*_iu2ceod4>4u>Y|; zdd2x`KF5r2(i{@M9hKNIDzah!j4KGvT_`D+~KpPdi(XIJ<9vZy~aANR-Ve6Sz7 zy62lk`D;GT|9AP^h(FUf_GkI|VE=O?{!HW9`C&hF`=fDm{{B24{Q2kw%JUc(^#~#G5X*@eW?1vu2uW5XB ze%Sv!h(FVKc7E9ZJcvKj_;>Tee&#{^md01-hyBch_$`g+=68DYXV?&_!auX;cs#Hn zYCKfYd!!l3RfSLgSUj*_YW-2Q;{5V7xAE1g;y=#M#XPK`QbjFd);`7As=~i} z{49^#+wu8&S86+tJ-yPr;%Oe{70=JU^NQ!Er&&e&OWyAfomV`sKIawBcjS4+^F3-_ z@jOe-E1t>CD;U$$hwYlL!I+*tKC#c%I8&zQk1P858jR`r<9&a=24i~uu>12h7}GOl zdj4=&^M8f)>4h@AP^OoUE9u$aaiL5vAMdyGHCUfs=&^sHOfQt_h4yLRyMFds`tIfP z3f8B6hw1qmtWWzcwevMtpZ1+D=WDQIf1^zMer2OhH-?M+EKjnE|!I)m@v45q<{*|6juk_fz(qq3rlWq2D`%@+673}Jw z|1y2P20Lr_Uw6*d=)Zqd#oxDguyuH_8oocif(QF_(tj~I&qZtaTq^Nk*Zln#mGl148oodB@L-<``tK>{>1z$2 zekC64(|rHE<-9+%hVPF&Jox8*RrqX=#H0V#adzyhqIXBLJxAlgzDexA7M*vH*62Od zIw%hhW&`_gN$2Tn4WItc@L*o5{|a=ToYwHk<>A4sQ~wRxX$}SYxw@i!-M&;{`=Q? z`dY)MUxi1zj~d^du8N*~`>&tlfvr>fJ5) z&%fnzEFRX6#r>fQ-yfBDSU(o0uL__3v3OWN7WaoLe1BBpVf|Q~zAAkBtMIVqDo#!n zKDkOfte1+@SA|diSUjvBi~B5)bCb{C*a3e`pQgA9;8%Kj!x;iPP5_KK)8Om>)a4dlcjT z&>Fr!>hSQp5Jl;$qG#WXVl5ube)&D9;{MPYy+c}mRN}$xm*0Ub?hmcu`{OHkFze*^ zeT#F^8a|gwJeZgAyZ*)fp*4JeRN}$x*TwxFIqnaw;rk;G4`#poex7mqTEnMbi3hV^ zemB>+KeUGLk32k>{qj5Y#_4MfpME7C%zpWOn&bY^8ood3@bG(ZN9n7gXWxwCPw`-0 z%I}RHC#N-fb}hL|JeZf-=-q>==-u&tWanYZ?APX=Ul^Yqv_{XrogFIiVD@XHcMqzf zcgOqLp%PPOzcy+VRWbHQ9;VEGZS)>RRgCFZV#@5-=ALjEUtMU8-XZPkVig|DZEf!9 zgmJc7!)Ln+59XyddiS6zdb00VeRY`b^!LcB@afm$!R*&g{g^7o{;0&1*{_`%MOBRb zQHd$@V>>lysu=qt4^w8pc4`z=F{WRMDYIWYHHxYj`{VnW;wKbo)FzUV2EIPksLgi; z8ke_SH2weV6{JS%(Xdy5ulZ`!9t|03*lWDkd^KwG%}B#uqrK*W?%EwsLl8LXxML2UsKSiO(7!f6uTS%F{;TuB?&ajZ`;GF~e4PL4e6X82xo>}?{52ovzd9f6Zcgso z-6(&}$N8_$2fLk<`^89J16)1g(zRm$N7Gi4|X#r_p6O4AI-=4tj-5p zp_BV%N0h(jz>9ls}BbbM<*&i}J~uz&Hpwnh19KF;U2`C$Lz zcU_C})qI@q>U^-@@%yet`D;GTe|0|C@A!SyqWm=<=f5@|zYo}Jz8c4VEk7UZ$NWBE zQGaMYI{ts3AND(b=d&nZ&Byt!&IkJ)zr$LTzvkoo86WJY{0?Rjf6d4ISLcKMi{GIv z%3t$w{;TuBe#h@o7Ui$`IRDl8VE^OyAdB+Xe4PL4e6auVyO2fsYd+5ZxA|bd<988@ z^3{Bt@7jF)u2--5Y8?Bs{Cu$g@_TDV{h|5j`2T%=*zfqg!lHaNALsj7KG?tb-K(N} zG#}@)Iv?zR{BB)Q{+f^TU!4#3KYll^D1Xhz`TsT_?05WrTT#B6kMmuf5B58L|EMT` z&Byt#&d2(lZFmOo-?zKNHQw{B$jADh==EtF=f5@|zmwE!z8bgw>^JyWKNbD^8b`;U z-x(|;KkH|rzhC1x|JC_ezZ2!Fahz{Tee&$a6md01-hyBZ)_$!TP=ZF2z zo%l12XXl6g&z<-)jjzrR`<*-SV;axS5Br}x@n;&(&F?|{nZ~g{%g+bjG>MLyR5 zM6XZdIRDl8SickHt8tufc0ShsMEPqR=bxRA^*>Sm8prwP=5u=UXVwtCc7Q7UHTTc) zux2LCMHM}pmdmktShExNhbnx3RN`U1QJlUieEP@YVZB}4AFA;EaV#F#+qHL7Rrvm> z!~!~;96mcA-{`m6B3HmW733ZGmZ9xYwuDo<~IL=`su zqw!#VtaS+MAXWGds>Fl&v6H*oF0u-$=-u)6?P$uxgZZ(OyO%FcUu*RITl$rFFh6#3 z_X5WKp*4JeRN}$>*ohiNRrKz7fA`44l=-m}HHxYj)BhQ!%v_zQ>r=&;Tpp&(T%D-v zQ^lBmC8o@eov2Y%#n>Npn4YOoRE1B!77u2>&eSNXV(gDfOqo$UQ=_Pgu|M)KW%lb# z{g^7o^eZua+OPH$%l{0&Y;FGI{9%md70=Je^NQzZv3bSwdVOB;ykeVGTt2RY<`vKL z`n=+KWX~&}>CY<|(+g#K`7kx}e}yrz*54KR*w5|J>(h8Ye(Uk+cgMv2t#Ru|Uh~h-$9}$#UZ2L% z@!#*JnjJsC&CmLcC|`}^e7~EI^)FFA8pru$=VSd)l)uJt{@M9h{}bh}ah(6^e5~Jz z^3^!bH#;BeccT0?j`PpX2m7_NyB{v<56#E@u{s~@&(7{{$0&cz$NB#*AAcYEYknHX z{_OktVE=M)cM3=OX+Aps*5`-)&BfhYALXz4IRDl8U_W$mznqBj*LY=IN#OzVE^NPeHZ1g`8fa8`Cvcfe_I*lulYFt)%jpQbaB5(jPlofod0k0!G6d8 z?m5a=^KrhP<%9jph4?Lv=jP|18Sr}iX&n2n_4#1`<(~)<<*)hZ{JTCs?05Y0KBD|J zALqY1AMAHF;?Fdmogel;{#iZI@vr&#_+On5_CK3@YEYEF=HvW-n-BIon|tO{l&|LF zd{^g#{f>W1T9m)$a*L zQ@5kzU-R+t&-h^f;-6_A@z;FJe|0|CzxXHCNBL_$&VO}2*#G$b2%`KoALqY1AMAhp zZWB@dnve5en~&csc`myNsX&fE@H}`zG75Q1e6a9S} z$N7FYAM0PDd^C>p$<7D+A-`XG)E}CU`{TFyU_W+qzpsq))qI@q>U^;Oxw+q8M)_+# z&VO}2*#F$z^UI?AH6Q1{Iv?zZZtnM;QU02b^Ix40_Cq)K{In>4&ByuwE}#1!?1wb| z+kCLUx)Xn+@zwcZKht*YMCT8UXXk_c&)q%0?DhRshyBlk_%n@X=ZF2z zgZMLze>XquXCB0FX?%5l*#A6;Kht<_ey2Boh7FM_{<^2e9FGS!M2&|kdXH4&f&Ec? zwW{#xABzX}ORYat;rruQJg|Ri{hzf>`%zY0@kuFmf6!T8A58a>^1WLM(B%+=Z5Js9_g*6{sNi3c-iXLt8t z+#g!Q_eUNc%#WSj-Gg!ZTEnMbi3jszXLpZc+#g!Q_eUNc%#WSjJ&JMqTEnMbi3jsz zXLpZc+#g!Q_s7rhVCL%V?jDSj(;7ax|Hs}LEjO+sNwl9QVm_rKMj|PZ|Nmnvtgj3d zRLJZZyJb`{V;;6+QNXoM7Afk8BBJnEsOwWjO}4ncv+-bVYoWeS6@3TAVan{+Lj9O3 z`t&m~W%g^KMo|@ge`I3H?AJn#qAL3Sh{KfGuZ0>#RrKj+V#@5-LXDy-`u_M1rp!w% z)b**N&m|L6=A{PM;xZiZ7tLns-jOn57U(zMOE1J&&GqaI$=+n={l-aM98bwv~{Sk*Lb6YF*g{tV&e-BgUrB>?tRM96Fhbgm8D>Zql=+n={ zl-aM98bwv~{gH_&vtKJUimK@QBMwt$zgB7#Rne!Phv`O*qAG0qXXC-_*G7$^D*6tJ z!<5;tjT%K&^yz;GQ)ZnuYVuUk=aPvj^HLjieX8jDBNJ0*zcy+VRnhlH9Hz{EZPX~v zS+P3LPPc!lD*l8=YrlMAs;Ec*<#Db&7mwC{`Td~^+aH;DwD!wSUllg}Gx4|?qv-XA zDr$F>Up>EzM{Aw@TvSn$DY=}BN9(2h{!oSOk8|;8{g~e$s<8c$iAQU{{Pa~}(?1uF z)_(c@p$gj{nRv8D(NA9$HvMz)V1DdI4Vo%y|9pIE%*2%Wv75O^(LcjzjoKmQ)9ZKe zVCL#(?jH1W(Hb_FJUs5y^{Jv}U(VXOcrZV9rv^Md#IxCk2p-3 z{kofb6#ewIM$Nyxdt~Cl{Mg;xqv-dC*0BANi3jszcXN-T-yd4T_D38Z%#Yp8J&Jz% z-?>KFpQ*C^_*Xe2vrpNoXsH!q?DMZG@)FyrF;Im~|7<+i=ii+=1y%GNl!+<({JT@9 zpo+df;xJ{Oe|P!`SrvWynV7QAzdLmbs_6UUJD9T1ojd(3uZljGOibA)^__m&S4H0+ zahS3@S@wrD`1h}WJzPtxKT+=C5e& zm;Y*2Vb2cd;?deKzduxA`y&&N)_(cvtHP##E*`D@^7}&-wm;6rqqSdtf2hLtM?4f?&%nSWgIJod*G&-BL? zjOpdm!j0A_pK(6!a~xMNrq|EUgyS_B({k4``#TuZ>*qIC! z{D@fHZ+u+AnATm1M{CrbTE`Xa*sr@+j@Mwve%(oLyaqn@@i~mW26W!Re>*Zz-bA$Nf?7 zY#+To%}2+_?ELE8?S8%*$L}Wb`QY<==?c`}8jsEge*&)e>W|J3nvaiCw{!~%#$sgsf`8fZd=7T>M*1PUU`D#AScXmGb^J%@Sew4rFEV$zvkooXXk_cS-mfQl)vWV{O9IV{5v*Gs;GBClz+XC2R1w9 z?@&d}=6pP`*(p3!Vf*7;Jg`|R{h!~1X1>{1|(x zM>!g_hV73$JlGRkiVt8$Q5Cg2%2i(^9?U3SAFl_$d#IvMe@0^0m#1izK5hR}zoNBY zs<6+d5|6971JUQv`Y~1HBG%eKKU-DQcZYJuorOp1rTpYnVUx?mqqR_c|{<(Ox_RH@NRoMPG6A$~mVy{0`QM;q~!dyI8% zf5hRz?3dji(NAA%*z_~;VD`)Ij_LP@*0BANi3hV^c5hU_KeUGJk2pM-{j&Ss`sr&8 zn|>x9%zoKjkNy788n!>;@L=|9rAAQ|HTw@|@E)ejOWB>q{o__^)a;5g$iu_#BJZWI zikf{nZgcTq_G_blOci~9WMazf*Y^00UH!effBsNK?T~W*h{J=~uZ{j5Srs+=k9Utu zOqu=K=sk+6==&oRQ)a(5ddHnA`u>=ODRWyJy#rAdeYUeOWnOAC&+GHA`m{z(w_Nqb z;laGrMqQsOYW5#jeVLdt`?XO&ri#8l@-V%b=NEeK4XUu|=ivW?gPZfRonV2$jb)z;=6@7nX zV#@5-jruWF^!*WsDYIWUV-y$X+3Bk2({GtZC)V08|Fx*1=3jR8%ERMse4&@VDr)xS z+k~_6XziEZAF8MwQu<>S9<7)1lT(FFE)$Q|OZn-m!lr*N9*PR+gRn+eIunL)&GCy{w22B-xe|(+k zPF zKfZ$p^HMu?eX6Lb6xWxF2lG-pb$zPn`y&d|gBnFu*lf?ngW0cx8bwv~9TbNtb6W@X zg{tV&&%~73uY>wARrLLli7B&R2Q`YS==&oMQ)a&oY7|w`r~e+N%u5~A^{JvyE)G*> zoepa9RMDrOi77LR2Q`YS==&oRQ)a&oY7|w`_eTt-*N0F1PqU-J>$g0rXp{Z@@F!;@ zhV573p^Dlg*?3_4RbH(sZ2ITof$dl64^`Oycn=S3ok}jMu(_Oz2li5>KU87+<6Jzj z{VM&T3fmua1Q@<_Mtk?I*mRn+W@ zQ9K(D<_j;>D5|3GpzmPH%+-auK2`L&WMaz9)rGn~RrLK4hbi-87itv$+luw&$>`<1 zvi&<$F%OT{kNLT%q8|OFlh4JY^<#d2sKWL~CLXOH^V3&_P5)dxT0iFZhbnA;Wa81< zFF$=%*!1V%QA}=ieO_{^sJRu_my1Vho&5AwQS&e9pNmIpzx@7Ch3$`X@o4Rr-yf>5 z{gH_WGkI6)`czT7Z13pI+WsM(im{#-nmA6uwF zQ$^n&nV2#^wmgmq{EdVv`u@m7jQO#}+@t7SU8th(k2p-3{aUC|R7IbDCZ^1OEz~Hg zqVJFIV9Ko1LcNqK`dl(GWnOBbu1^(xe`I3H?AJn#qAL3Sh{KfGuZ0>#RrKlSVY*VI zs0y3@*?2HNwo>P)ioS#5FlF{@rAAQ|efpW0GW)esqo|6$KfZ%0^HM8yeX8hl$;6a- zsg=4uRrLK4hbgmPD>aI$=+n={l-aM98bwv~{gH_&vtKJUimK@QBMwt$zgB7#Rne!P zhv`O*qAG0qk$5n3wNV?Wiaz~Wm@+T5QP-!6KHE%8nU~tA>r+MFA90v6`?XP{sER)Q zOiY>m+Ne=fMc*GWnBu1#X|zo>9}Rr;YJa4@Ht2Byfv{!PktTfslWpmPKzu$dLP@`>v5oxsF&%WlX(Kg?RG}`Z1 zU-Q*yn{PxK?Kh~e`D(PyHzEzY58P|Q8gJcFMn0`Q@m`UFhkKos*@z{K@A1cqX$FEQ0vH4*CV|R1&&i|T^^Z#i+*zefg z*t~o-ALlzeAMAJR?qXj4nve6Joe%auc1JcZf6d4F&&~(?AG@!cm;W5|kH_;J{`2@P zUwc1M`S){YveEc+C#LcE$LH7a_{Zm)@%YE}?|A&<{eL|E@%}L$|2V&l$3OaSJpPg2 zc>Kc;jmDqPogI&3e$VG{j^|^3&*uS-=VN})Cx(sZV}8#k294)qe$S_DjOIU|OEDhD z{rCKB`*=R?zvr)C$MbRjZU1~fGoFw8Z~MpZj^^L~d9KTN9QWVtAAd2PkNfZT&+p5} z^Kt*({`r1#JRkSp?Vs;I#`AIi-3h<@KTl2>t$!!{?*I6K@qFBW_kVt$J)V#I?@s#f zPWatP|Lug|PWbJF-%j}Lr2lrpZzuh?6Mj44w-bIP*K++d%J(4r%Kf!?g;Igf0i^<; zMN0)f50nbr$)y6H3shmR-eU2<=b`diR8jLi9}oOKUU;a&_Q$z+;OpShA2U|mUOsX6 ze`)lJ_WId>Evm4`?U{I#Zm-v`UVo^fcE|6>m3S^5?I#OAeO1)_OZw;H(SEM<`$HAB zKhDLYwF-WJsKWL~CLXOZ^3zv^P5)dxT3_h*hbnA;Wa82KLO*>~*z{-N(V8niIaS!? z&c&lOd47MW!uCfd9?XwDf7AByov7a*TEq579v;tMY>m@bMa{k##auj?AA9~{4E2ZB zs2x)JBNGqi$DY5)L;ayOY=30p!Ti|s7kj8bw1(}EI6Rmid;VSzrLQ$?`tRYv%+>Rk zcqlooVUvr)gPE)6@9KQi%Pe(d=>KGYvt!}doU9?X8( zUqO0CQ57}&52uuesr`+sm%b`&`e)<8{MbSbnkxDZio=xIuf_a2&Od)>jhg@E@ms;~ z;K8iZVt$k8=b|-iE}3{RFSVFor274#HEe%m;=%0KVt$Y8_lMT7{Sk);vtNt(J+hy^ z*0AYk;=%0KVt$Y8_lMT7{gH_WvtNt(J+j{)TEq5793ISmE#|o{e)?L&rk{t0ed?Q+ zzA9?=#V5au2eVEqHF>J&lgq@Ec`5rmM*qmx8nr{pk)4SL^J6P@j;g5L@p0yl!<5-C z`?OX6?4UJj{^jhDi3hV^D>aI$sNL~#c8J52*)RJnW&iA;HERCl?2w5EvtKJUimIsH z@o{#@#FW`D`z&?;{Gl~!hm`Zjckp0dYNf7E6*ZNQ<2DadyF-C@RI0+JpNj{xUv`HI zzdy7_?U2jkGg2lV%zkaukEx<|M|t;%#DlplyZ?-TcF-C%|B`+t9?X7i)Q{z@xI52I zx34yTMQgwOSE~wpcF4q|wO@Yvs<7$L!lU(4esZd?$z|fvS|>k!RoL{;#iO-fet)RK z_Q#oc*gZSF{!m5jj$#CI@o4RrpS~(;{w4i$@o0^r-yf>5{gH`BYrp*TRbkUV7mwB` z`u(8_+aK@Y!MxPX+#Bd8r!{PHnRqaBbu;(E`Te0aY=30p!Ti|G+&$>`ht{zD5r+r! zV>ffBo1ebcu<2*w!Ti|G+@t9Cht{zDk%!0K?85A&uZo&|F^ai(Fh6#u22B-xf5c(R z?AP7gf#{zdv_{RpoE_f7gPE(lxfjk)PHWiYGVx&M>Td2H^!r0=*#5}GgZZ&Lb&jg2 z-SKf<7>6mdUw3L0Rne!Pi7B&RcWM+>(f3Cjrp$ibsZmr#pMEB$%zoXeQB+0WA9FC> zsSQ+xO)e4-=B0M(`c%=UpNT0mS37lEs_6S84pU~oc4`z=(Wjq@DYIWYHHxa}`y&%m zX1{i76jjmpM;xZie(lsKs-jOn6H{itc4`z=(f7x9FlAn9r>;*GeJ+`pGB34L*QbiU zKcX-#JD&gh*S{VK|L5^P?;ZhF*lf?ngW0cx8bwv~9h8YFvtI`_imK@QBMwt$zYb~? zRne!Pi7B&R2Q`YS==&oRQ)a&oY7|w`_s4fIWnSu_u1^(xE}57zFLhAYr;5Hm;xJ|Q z>!3za6@B`dm@@lyP@|}dzCU6xz5c&PL`G2+ZL+@~cBGis?UCiBset&2U z+aGawFh5py1Fzqk`su5}rk{xi^J8UiIMyGku>BE-2eV)0In6A6RoL`1@nC-JV(wA& z-#xU3?T<`6m>;{Cdldct&>FTszRsiE?S#+Ts;JD1>pL3{=B0`wVI8E3+C!y-;_zVh ztGpVPzA9|`nRqb!b)`m86}3A)-d{2?W%lbzjiM_0{)oer*{>@#imK?-&%~73uPZf* zs_6S84pU~ouGA>1qEG)lOqrLuQrD-7KDjtdnRU8Slc$P4{X9$;Y7|vr(?1&zX1^Bd z$5hdGP#mVrel64}s-jOn6H{it7HSk#(f3Ctrp$gV)F`T=?~gc4nf+R*QB*~r{&z5C z)@h+8PZfPGnV2#!wNTfmioQQGF=h5^p+->^eSgGZ%Iw!djiM_0^z$%XsZmsgP5*2> znEhI*QB+0WL2;Ne`?XS|sER)QOiY>mTB%V~Mc*Ia!IW92m6|+N^tohW%DmJ{U7srY z{)oer*{_uvMOF0azn|&hJQ>~Q^1oKJ_RC*G6*d2I7yY?-wD!yI4^`Oy$i$!ti$RAF;D7mwCU`Td~^+aH;D zwD!wSUllg}bMa{Hm){?%u>El!9_@3GUVB5MwJ&~?Pfv5Q!q=x7ZS##tgI(v=rxd*& z-J08`KPL@*ovP6`!LQK3SA-gEIY*>{ujn+|<{Obl`yKD=JDo<`d?V7p-{NYt%{L+q z{4K0T+k7L^z~8fKw9Pjn4Z9cI>pQT8R&Ubb`_*)UXSc5 z;N`FRIRDxCVE<$HLGbd|e4PLL_>_Cq+WQsDzuSEZG(IDr>R@#D%U|Qwuf^n3{g?muYaAWl?M?_W`BlH;|NR=r`A6qd{g0o&#&Q19`BeYo z=dW>`e{??8|M>ZT*LYd|^78q=KHYpY{=ENVH2(bjIU0XnfBWP0Nv)&t=k?EM{CWN# zjX%#1qw#0|jK-h*N8?X_GaASIw$GgcNAoei+vn4*{Q0-fC!LPQF~8gAZZo6#nBVPl z*Nf47%g3BQBzI|#pn@H+^(qnO$vhxSKRw%DlYt;O+@nG*Bcl!RKirO8& zA6Hh9c(5x2_DP_;TCGv@e;*Ha#dd!rgRf6jQFHq^ZsQPR*V^n8cYD6d5oHQn>^U#OufyM`)q@o0UapRFqF*&!2;){pt=tHP##CLZ>VGp|2XQM;q~!dyIBU+AZ=ikg2( z|6Dv;`{nnCDr|qehevCj{9IIFb2%4})=T;Qp$gj{=i<@YFTX!jVf!N!kJf(q>8rw~ ze=Z)(2HM~8_#LD*YzJlH!Tgy09hcu9TEq5793IS%*1z#}{tP_I?t1OrgRjY{ zqNY~<6^jQpSLL;+qUL)(9@tzJ9;&eYaV{R%pq2hmh3$__Jg^@t>8rw~e=Z)_kCpyV zh3$__Jg^@t>8rw~e=Z)_ewF@Eh3$`7cwjG8l2e6EE)x&zrAqp$u<4(PM|r+jeO86% z3sq6OqxiyHJeV)MP@|}dzCSWCWq#~JjiM_0{>a3X`LPQ%imK@QBMwvM$1c<;s-jOn z6I15LF4QQhqVJFIV9Lx@d8RP?RG^BQO!-uhi3c-R<(X})KU87+BMuK{zsj%8S^BE5 z>1X1>{8;&o9qSKO*#5}FqZnnJzA9?=#VF?D!R%MLR$~33irOKiKQi%P_N%;J)*q^{ z{gH_WvtL(g6jf2X>iSgCCl`k)vrY>&dEZ~LygWO-*uwTNRmHn_wD!xVu8Ml}mp;wJqqSdt`l_($ zpNmIpzx@7Ch3$`X@o4Rr-yf>5{gH`BYrp*TRbkUV7mwC{`Td~^+aK@Xu^N--<)Vt3 zO1XFAY&=>o<@bjwYKN5mI2VuBe);{O3fmuYO>`M-`RLDKekbWri#9U;xJ|QYcqEs zdhZRY=+n={l-aM18bwv~{gH_&vtJuEimK@QBMwt$zc%W}RMDsZ_nEfOA9{U9*Jzta zL>l<&Q=@IZ5oxgN%ldSn*P~l=+w|w8fv*oW+9nv02EM-2Xq#_D8u$uMqiwzsY2fd4 zHQMGIkp})wR-b~W1O`xP4aJ5r6doFme(JH5Sr*3>w*NAdYEd!ljVV(iX< z-tjX#KkQHJ&UW7G(|p_?Kg|c*6}vN?m#^mId}rr_?Tg);&dXo(asIRO!FI;(J?G`G z`8faC`Cxlv_jL2}*L<8mulbn&?0m3&vHQ$<`D;GT|EKw2>tpwc^YYbv zobTLx?7n8N`Dz^dv-o_l-?96edHtdJ==h(XAND(Tr#CNu&ByuwG#~7D>^^K>zLDmy z?vtZyK4%V=i^MJj4H6Q0YJ0I+S z7W2GcFMrL)`OnS=`=7-;SJ=y6^Kt$^%?JCP#XJ|-%UAPpzH{@jduP4ot8whl;`70N z%8U(Lt)&dvw> z9lNiVm%rxY{QoW=yVKKaJ{rgV>*x7k|77>2^77Subo|ZF5BnXvGnJRW=HvW-nh*9j zc4sLsU(Lt)&dvw>8@qFqm%rxY{AcHb{f^x`%FAE#asEHe2m70i++U{g==`w1*~tB6 z8jsEo`<;#4U#9V|^22^*Blmx4JT||Z*&F`#`bp#1f5qp6{nyRx{OAM9^#|bugUuir#KkQ#_#9wJVIzQ}xZp5GE8sA=?|7%}gyz#s7W3PX|##=v@kx%Ql zyw|7k`uQj$pVt3)uTSGR|JnJp{>IB!<2c{wd|H3w<*#v^e{?>r|MBwIIL`m8d|LnF z@z*%!ADvI@f4uxPj`N?LPwRKQd^L{qjn1d_V_yCm$N9(RvlD-&aqQ3L=Y##%Ztfp@ zJ^nQwogel)yScy2%U|=+`G0sKWL~CLY)umGo6%(?1sv?3GG?sKWNgxp-hN zRr*5}wm&lQz*efHuL_&~xp-h}Rr*5}wm;6r16!}sAF8nZ@g5%7MwMJtVRJbXkCH#S zoA2^4N~&o4BNq?m3rqg2KU87+BNGqi$1c<;s-kws@5j-Uiw84k7wQ~U(f3Cjrp%9B zs8Li!pMEB$%#U5DQB+0WAO9WGoB5`?tX1BD+BLpjQGPMe{*}-FO7&x-ifTwk745F(lBYqWx6(3uw%d7^T1!@PW$vu`}9ux^iGfc zJ3XJ?>9K#O=hHhm_OFlEiqHI|0;gXp@DWuiaQdYJA5o?F;7>H7p+k{Bo+_$Ih#4y@@ln)O+OP4Zdp`e(?1gr z_U%gXiOj;OqV`X@x`@Ps`9k*HT6wivqvroU9?V>^?>x(2sx@qKad1z#} zekLBwD6+d5N`Gh#+aGawv^Mbiat~U`RuwkebMa{Hm){?%u>El^9<2@Z`$HABKQi%X z?U$dvDs1}a;?epszduxA`{Nxv>^;3+E~==h6i;_H9<8VI`$HAALrQ;S;?cS-KYdl$ z^v}hkwO@XJsKWNgxp=hp%kK|W*#5}GgZVN0J1xIIw1(}EEIiu#174HYXifdMxtAge zD|{8K(Kg?|M}u9B)?bys_Lb(g8O=!pUrlPXO)w%2d^M=iHs6Re@YS3~+k7L^z~2CC zw9Pjn4g3wRM%#QN(!k%*YP8KaA`Sc(V~2+RtC}asEHe2V0l+iPV0+nve6Hoe#D$ z?bDI{{52ovKRX|6Z7$|1Gv4*L=HvW-nh&-%7xN4lFJH~a`OeMIQy&8jsBf`yIRQhIjp^`8fZd=7ar>-8IF_SMzbcv-81z$L@*a z<*)fTf5r#<6}#h*$6xa?|JnIqzhn24^77Ywod4W>>~3JM`Dz^dv-$a8zh(C}^YYhx zbbQax5Bo2>cbS*J=HvWl=Y##1-M!4qU-NPPKg|dGExTivm#^mId}rr_{f*tj%*(%> zzr5W4Z|7^g|9ynr1I**o`WKDo5uppT=?i(fPD~$ID;iIRCl% z*j=Yy^VN9k$1?J1{g?OpG>(pMyN_8!ey!i}{(g<){AcIW`Wr7_jpKZOnosLzy!aALlzeAMD3g^ZQ6If6d4F&&~(?vDN&3(#v1-asEHe2m77X{65ml zSMzbcv-81zXEndi^zzqyod4W>>~2u6`Dz^dv-o_lAG5nbdHtdJ==lG6e%SA9=J%Oi zzM7Bo{VE^qXEyWuNiQGG$NBs;AM9^7^ZQ6IU(Lt)&dvw>9lL{+m%rxY{AcHb{mw@G znZ{@5hyBe){Fuh0^TU2;BmPX|(fMJ&vk`x$@wxfk%-)5s*Jm2Xe(dk_!T#xHo-gL* zr}^mm`sev!zj7n~O5@S_VSjTYeoW)h`C-3vBmPX|(fMJ&bNi)n{Qf;VAMAH-#E)q_ zIzQ}xZp5EyJUTz@e{RH|X?%8m*zeqkAJh2X<##83OXJvY&Cdt>tvm5!8jsEo`=2}U zXBv;r5Br}x@n;&Jogel)cjCu19-SZdJ9py8G#;HF_CI&x&omyLAND_Y;?FexRespN z+=;)^cyxZ)&)kXM()ir`cH+l0j{R7CKG^^4#Gifd`1`{&nwolon3JiZ#Q z_a8*$)A}9n@7FlaH#(oz|9JUp9OoaMPwRiY{56jA|0zj*vLj`>ID)A|=Le~sh( zXXn%U9WP&v<9ws@Y5k6uzs7O?vH2XvpS|X<@z$SZp=KeA-f6d4F&&~(?pTpc==H;*XIRBsJ zb9wkNY=Bf@@98-o4{XQ^4^`A2IUf&fhzbu?*#3AA4{UBqE~>D(oQnrGJEcEVVf!N! z5A2mn`l_($pNj|fPNhFoVf*7;Jg~Pa{hq?EHD*6t}#FQDuD>aI$==&oMQ)a)e)F`T= zPd^h=X1}h~D5|3Gk4#LN{kl@4sEWQn;xJ|Q>q?EHD*E)_!<2ccD|LNyR%|a%$S&XS zwy#zdS7Y*g9<8}j#o36p_RCLS74^Jb&M8qkkE`y&ny z=EqiZZ=j#P*0AYk;=%mbYVIEN`$KEk{>a3G`LUHcM^)7BD9$kw4`#nsY7|w`r=N)_ zvtKJUimK@Q;~h*lY6DeabIHYnd8v)MK2`Mn5r-)=R~xl~s_4_t#FW{ujruWF^!<^E zDYIW2HHxa}`y&ohX1_LS6jjlupNT26UmG=ws_6S86H{gsH)<4B(f7x9FlAn9qpnXC zeJ+`pGB34J*QbiUKcXvW?gPZfRonV2&B zb)!a66@7nXV#@5-jT%K&^!*Wq>75!yRoHCL#)H|fJ2i@`=sPGAQ|8C+)H$l6?~gc4 znfS3J*j zP^QP{`|aqza(td~#}$m}LHqRh zw1MOQ3hUG3(@c!lV10Ugeme2jD0|%f=hwe~{p(RTuE2d-*1&yQDlpShf%~*n;65!C zm}#lNeOf9o(^7%^wCsY%m|jSqmNgjD^1NuAT-~F6lx^LmdtAYo*1dekYcQsDU(wMT zg*$$=b@##X8jNY(qinne>(jbV(RdBUw9I6$mNBh+4UGPd`aJq^1v~Z^+NTTc(}f=U z3qAH1a_qCeg8dEbFW~=uoM?Tjp`S&4s$IW%XU6&rv{AmAkMo_K5B~gEpV&3ZU-NPPv-82er#{1Ml)vWV{C}Dcw#xMxWTSjF zALlzapZe@BKVOYwKNg=4_Fwf`W~2Vle02PCe%PbJ0I*<>eIqT`D;GT z|EKw2e^a0KHOg1>alW(j!TzQ`?`xF5=HvWl=Y#!DeV*4Sf6d4F|1=-$Z|d{7M)_(! z&Ubb`*x%IWevR_ie4PL6e6ZiC&-EJRulYFtzssjSi^|VOXWlZ`D#8o z{^sY0{Z4&$)+m3?$NB#>AM9`Hv#&<^YCg_)c0Sne)Ms0b^4ENv|LlCQ->FZx8s)F~ zIRBsKgZ)i?2G%HF&Byu9&IkLQ`V_2D{+f^TpPdi(JM}47qx>}==g;_HzfzwfHR7-N znE%{->XVcFd^L{!*Zh32->T1n8s)F~==h$WU+Zt~FHgUz&v`2OYrK8xQ~7s%KCR#J z^3`}fz9aH!{f+ncYaHhrolom;y!(hMP zA3x0p`>)+RMbyhz^Krhj^TGaSH_wRm^4ENv|LlCQ|JltGfW7=RALq~bVE{slbao+K#`S|#o zoe%aac1J)jf6d4F&&~(?ox|);=H;*XIRBsKgZ+)&t<%d_^Krhj^TB@SF#Cpj`D;GT ze|A3D@7SGoz5F#F=l`>O%AUR00I91AKi^eSgGZ%KX@c z8bwv~>A#05GglYt`fSDi@)YQDo!tIcR51^a)=T-hsG=U1rIXLZ<7#}N*B`2=-BFCd z*?6?}%kK|W)D9{Ak%>oZ6#ev7VbebskJf(q{hZ1U=+n=`bfHF3 z6*m2|@nC*zp$1JAeFw#1%KX@3?osrvK2_1DpNT2+V~e>*(eDqfQ9GpEvH2Z5n3r12 zy@7r%TEpg&i3c-Ri@AHy?+>kE`y&nyX1^A5Z=j#P*0AYk;=%mbV(uRF`$KEk{>a3G z*{_8fMOD=9C`K_74`#m>Y7|w`r=N%EN{yl_Z2D*8!R*&cjiM_04*CwJ%uB7*^{JxI zB@1qVJD5Oqu;!sZmr#pZ+_TZq)Uu!se2T2eVEaHF>J&`y&%mX1_LS z6jjmpM<%Aser?n!s-o|YI82%S+Ne=fMW22qrp$hA)F`T=?~hDOnf=5{gH`B>$d##RbkVgg-7f9{Nz+&lRFm=X0Gnk zZK1z#} zekLBwkKN5Zihh4+4ci}ic#Dn><-P}Fs_lMT7{gH_WvtK(kimIsH@o`-khbgmPJN09# z=+n={l-aMH8bwv~{gH_&^J6=8j;iSU<2#r#FSS$Gr;0w8C`=D(@>F57JsS_^whrnG zRnd1)CZ^1O9n>hQqVJD5Oqu;Us2@{BpMEB$%zhozD5|3Gk4#LN{W_>oR7Kw(ahNju zbx@oR7Kw(F_>N-KJh=l{{8D; zkA$y}_kh=X1XR%``};xZY{anrDm+wCd*pmPu>C4LRAKug6Ax^^O8Tm>>7R=SwqK<` z&R9`9qFhm29u%I}VC9zw?P&RTwu*YaFnYDBs69~9KNpYs{y6FnRoMP`50CoJHOfU5 zHkWhpsPE*X{!oSOk4!x3_gJI!RbkUV7mxZ)*Qh^KVf!N!kNR!dD1BAf^v}hkexEk# z4^`OyI2VulecGr$RAKug507FAu^&@K&A#};d3Z2$RqPhaRuwhfl5HFw%uAJ5!_rrU zO+OP4=Etthw}<}wzA9>We4P0+F=c-2+I)LB>JP0^JEWX%vTI9K*z_~;V1De{{OVzJcF-EOKfZ$p^HSI5*9N0p zw1&+k508bqK2_B0%O}3G@nH6Ap?*vieFw#1%Iw!djiM_0^fNJK_G_U=Q5AiEWMazf z*Fyc6D*FD2!<5;tg&IXw^yz0}%Iw!djpBb(QEKnbuYHzJb2YAbei9#7JUX<;dF?Q+c)oj#E1u_%amBO8#ud-x#uZPuHLhSx*H1GsT4SS3x6e-}<24x5 z?eiLDyar>seV*z3HJ*3e_@k^ZKD?_x7xx4HyKx`j9>DqI?D4Twf4}Fy;`;lo(Kt^0 zLh`j)kRNxd!1@7Zgfs-f|xR=jY!Ondf>CQq-Yt&B_*?8b{cX_p{u<7UF zaU-7x%9R(s_EAOcjq#C^z^Ko8} z!<2o}y3x;Ks_4_t#FTx`zCEt`u`yFc-yfNXG0SqJ9!3>?f5c(R3|jeCkewY=QS&cX zP!+X1KCUg}FlF}ZMtz|w`t;wy^iEBlDr_!i5{c$cHt^M-*Llw3^-ovByQhqL~u(_Oz z2Qzs)b$zO+{qym;Ar4dKwsvzboPYk%8a4m&sUQ;%=Ert(_n_Y&TEq5793IS%?dI-5 zKYguX)6c`>phi&@HT!a9a5f&yj~&#YsiNHUu)R(Gx1=4>@ar^`u(9bY=30p!R*&TjiM@QcYJ(qh{KfG zuY>wARrKj+V#@5-L5-p+`u>Q+l-aL?8bwv~>1SbD_L;}`D5|2(zUkn1f{`d|a%v_acEwWrxVRMPYgLx^t zH@yF@t~G4>nRqZiR(@y0&JL=u{gH=9G0Hf7Rn+W@5y-`Z*{^a<&-z0ZwL?mOWa7c> zS9!gxKiZ1p<;mz}1y$G%io>I|Uw*c#u-Rtf(b_LReO1`>-@~J|PJS+`u(_OzM{Aw@ z{!oSOk8|;8?U&yls<8c$iAQU{{Pa~}(?1uF)_(c@p$gj{XX3FKqv-XADr$EWqnL|F zYrp*TRZ;UV>7R=Sb6X3wfvTwe^Kt(84yMdYE#^))|H#%FHJNf`XX3%k)na~+?DvP( zu>BE-2lHc#x%1CYUu)R(Gx1=4Y%%u+`u(9bY=30p!Ti`_?ossnLu=Unh{J>VvBmt_ z*iT<;*z_~;V18^d_bB@Pp*3uOMB%YgU#NJ& z)6c||*{_xQF;(>ak%=j@Un@0=s_6S84pU~oR%#Sg(Wjq@DYIWIHHxa}`y&%mX1`Wy z6jjmpM;xZiey!9fs-jQ-JxrOGTB++(MW0+0rWKs+k_eUJ2%zkauD5|1QKNC}Czcy+VRnhlH9Hz{EZPX~LqE9~y)AlJxulJ8=w9WnR z(ZE-t8f{aENP}HT)+YtM9)p_OravbQe66U_Ho=HA@U@;s+k7L^z*ln`ZS##t1Ao7( z(Kg?RH1PMc8g289NCSTZtI;;!zefXqo2t<^g@`olj&HA@L^X~L(ENOuJJC2YF?LTp z@A#OVAGRlUk2~-6y>I^gaYsyhJ}v)l|2~cXFMO(d@%d@|dHm<(Q{9aJ`ZSL7pPf&2 zGk(4r$N5I*Q{9c9zs7O?(fL%j)=JeHxF= z2m7IG^E(Rv{Xz3_{)`XyGuP(HCq948$NXpKgZ<34d9sP0zvkooXXk_c(6xECiJ!mb z7;pWH_utoeeSgiz=ho~}e}6oUyMI2n##_IY zkx%Q#yw|63bo}2Q$IRU0t>5wT)i};CI-l0>c=>A_=O3L<>wmobHIDO-&ZqT1Uj7=# z`OnU$^*>&|8pruY=hONhFMo~W{Qowe)_-~VXdLGgoe%bBH}iZmuRk;&_s7rjDc?z= zzfa@Y`C$K3oGR`QjmPGL{m}iF#&N#U`CvbEH~R;?zQ1dHc7E9Z+|B*~UcQ=-kN?^E zVE=PB`vZ9SYd+5Zt9-D(xtsgPynHkt=QBGW>~HSo{xL6q&ByuwG#~7L?&kh6FJH~a z`OeM<`<*-SXBv;qZzq0DANDgl z@n0IBogeluJMmi@kIoPKot^kIjYsE){mxGOnZ~2@!~SO{eof=i`C&h_6ThbMx%nN$ zpJ^QXv-o_l|2c?1(|B}#*bg1VuW9_N{IH)nh~Lt9bbi?X9K@e#JUTz@hYsS`G#;HF z_Cp8pYZ{Nv5Bs5m_%)5s&JX*agZMLzN9TwA&q4f|#$)rlJp39qNHbQHU8(Lb&w49= z>C<+ME1sW+#}&^{Y~zaOHT}5adDS6P~Bl`_44nwQaEdZkRSpP$~w zYp_1OeqI5N*I<2m{d|`ht+7z13uU@crVC}dP^JrIy3jtYyV{R=Fs60q?9m!^@8EF- zJNE1Ttm8GJ20Qla)2qj8us+@Bv0tCzI{L5Fr&x|F7}Fa$_RCovcXFw~)Jp~Kr~DkTBCMIEFSEW)`fl+Q$@}G3YIl5`KfcbixJ~qZ zcKKda6_xw>crcS!&Qq*|RADdi`{ioxa3G*+6#B zRp}3{Vf!Nv4`#pE{d6ULtzpy8#Dm$uEA@q{sNGRM6Gq~}>=(OJw!B)cQS*Nv59aBv z)a0q6=Js*i#$n2=6T3UT^r_aU`RC%netA$n?=hpOirO9J?2wBGvtR6&DTRmDs2viE z2eV)7S4ZX5Y7LuyCLYXwvEQ7P{?Hn>KipUeMR(b_M64OQ6mGx2Ecm!G~W zZ2Irv(V9Fz7gg9?&c&nkbbf!R!uH3xc(nG*?+;bj{>a3mwSj*6s<7#wiHCjehSwje zsNGR~;n{e!Hqh@6Rn!hC{gH`BYrp*TRbkUV7mwC{`Td~^+aK@Y!Mv1x&Xu2>*09NC z;=#;Sd3II(<$>QHs<8c$i3c-i_8E76e`pQcA8~jvKen2C1O4>1hD|>c59Y`0(<}Y{ z&>FTs;_zU8Y&CZv`sr&8n|>Z1_NlX8`l_he7o&JK9?Xx~rxN=eq%~>}l@9t29?V>A z=H5U*7p-A)$;5-1EBhpHzdy8w?T@)uT{?Hn>KVtA` ze{uAht43?4zs;|+a)9K#!q<8l zZ8=Azfv?px+U6UP2LAR|qiwzsY2fc?HQMGIkp}*LRikab5ozFWP&L}-8v^wF^KpNCl@InGc6U23AI-=4{4^hIW$f;B zUcQ=-^PQa!wl;QuIxm0C$NA6B2U{Jx|D2b<=HvWl=Yy?}-GR=_U-NPPv-81L$nG%b z<*)fT|JnIqYh-tj^YYhxod4W>>|S-R`Dz^dx4+K^`y0ELoR^>GqvLaae%RlXC*kAQ zr}4S@VExaDjHIDO-&ZqT5Uj7=#`TuP`t-tZ|(Kya0HXpl>*lYe8Z~a(CKCM6VUZ2L% z@o)E?n~`7Z$GpE!<2c{wd|H3z<*#v^e{??BpDpJ3CtiPOKJJg%`Cz}cm?tKC`D;GT ze|A3DA1%K$j`NMq2m7PNJQLYF{xu)>$5;7azq9<(IOZRn5B5ikc`C7Yd}==KkGc8S zeYsxq)j0NV@%doCX7}at`a|>4@&EJuus>SO{cT>pnve6Hoe%a$tGWNp%U|vv=g{^_#}AUyIKN`?H(b z1K#To%}3YwU+0JY&5hijrt#?fu)n#H`_nWYogel?H}d;XjYsE){m_m4K2+n;`C)%_ zBmPa}(fMJ2bR+&v`MP2|LAqw~Z5>>&P4~Y<`!Af5V1J z74|o?*?3@oR9>wrY6qN;2lh*ahbnA;Wa5GCQb}JGHvL(6U~g2CQ-w_~6Ax^qO8Tm> z>7R=SwpOJ-RAKw$Ts*MVD*d4f+aH;DV5e2mSA|XgTs*MzD*d4f+aG7*QSwLkBwijy zNfm8>%)^7ZzLFiwRuwkeI6RoSx=`1rikkiJ$FUNL2Qya}>iSgCr=N)_^J5ok6jjmp zM<%Aspk1hQR7Kw(ahNhccA-Y`Cn_#4PsA?o+3jml#rN=N{g}^G74_&ZU6_eS>&N`` zRbkVgg-2_y{Nz+&lgq>7YCN5nzA9?=<@5g8c(iWI?+;bf4k`U{E*`B>^!q~1&Oee|dk&#Dn><#oVLl_lMT7{qY?< zn3r12y@7r%TEpg&i3jsi3w3>}sNM1Lxgir%X1^9{6jjmpM;xZiel66GsiIFm6H{it z7HSk#(f3CbrYkjys<7FfjR&(|D>aI$=sPGAQ)a(bY7|w`_s4fIWnOBf=1LWPE}57z zFSSzFr;5Hm;xJ|QYo$g}6@B`dm@@mdQlqGfzCSWCW%g^OMo|@gf5c(R?AJ<-qAL3I zGcjfMYo$g}6@7n1VY*SH7_nk|d>ZT_K2 zy#5$hJl}!F70HTql&T*`NuO5#}!XMHm+byZ=ZH!yar=>`}_FLJ*71pQsPiHV*gZ1hC^OMDR4c4dk&+Cuz8mv!u%59~S3Wq(JcY;g7=3i>L-UkJEAfX<7Wp|*#5}GgP-|TVbebs5B9## zuMAXC`{(!Ls_{E`{K?f8yAIMCHkVvH*yoo&xf<6RwL{7$oH#t#XVX9Vq@^`%`k8pJ zPtkQ>jsN|VxYnrsQ{ML@@nBx6?yE8G53N!2FX_kO!JJavHDjE<*0AYk;=$}!-M?Yn zA6moqMXkCy4{6YR?Qc9x3Pe))f?Dr&kVxmkF$Udm5S6*jp{JX-7Ir>_c| z{<(Ox_RH@NRoMPG7mwC{`Td~^+aGy&)O{q%w>)0@s;JqQPkd+N(b_=2KU7gWr1ZzR zc(nG*?+;bj{)oe)bz6S6s<7F{;lZp^-4kPcWuP@|`f+$Lb5(cV7^kl_Z2FmaFh5rJ z)fo4O*0B8%hX?axb=Qn>`dY)LpNR+aV|8DRaertH+aH;DFh5rJ)fo4O*0B8%g-6{- zVw9~aYO=*BM&iNTR^1b0oW9nm`Iq!(;laFA-Opm2t=6#FX5zuzR^3-)+#g!Q_D3cj z%zo8a3G*{^cd!OkD5u>BE-2eV%r z{r#;fYW5#jpIMl;&p~>9U(jfq``@F1uS7N4rVx<^yVk_-y&A3g&q)$rD{8dn_nUkY znUfX1*3)R4Z$ujSYEGkVz7c8Q?{_uY<{Oa){(e@YZN3p{;BR0x+U6UP2L7H_qiw!l zp<#D@d-XjU$BrjHA7)Q9j%4`C)#3 z*dHzCsUTkdnve6Joe%a$i}`h;m%rxY{AcHb{gK_P&C6f&asG@C_A_?3G>^aLWB#-A z!T!eXhUVq3`8faC`Cxx!_e1mY*LH^4ENv|LlCQAF_LgdHHKT&VP13*bmvg!Myx6ALl}_A_=@ zDldP{$NA6B2m2wrPnVa!=HvWl=Y#!_-G|G|U-NPPv-81z$nLY{<*)fT|JnIqKeUnG ze`-8BKkSD#^7~VbN9TwA&_;fLs`2RjupipU?@u-UHGa2W*#Bre6QAYf`O3G)6PD}s zqsIH^Pv_^;`XMiWjpO4ZI-k}LdHHJ`=O3L<>xaDjHIDO-&ZqT5Uj7=#`A6r|`XeuY zjpO`h=hONjFJF!0eE&9|*57#fXdLGgolom;y!gDdH6SMm{eh(`85*{?0(8$s*0LkHXhjg zlvk??oBp|YVDnV^Llw3^&cy?psnQ>+u>FyV2li4WeO1`>&&30KtI{8;u>El^9@uM@ z{%9-KmnTcBqIOUDS1cZ_)$+4dMa{Ql`yL*xZSr$bh0WzmJW3zdU*mfHp^Dla<(zyr z9<49*`$HAALrQ;S;?epsKYdl$^v}hk^<#d2sKWNgxp=gG%un6mG} zuJqe7RrLLli7ER|?rMH@;J?3UjoKmQ{Ur*Ig?>k=ikfVBZ#Wwd_Kn*@zmro%-$8Mh zGGDk*qo|5L{r50sUTUGPPZfP~ahNjev`{aliaz~JOqu;!s8Li!-yfNnGGDk*qo|6$ zKjJWD_G_U=Q5AjqnV2&BwNRs|ioQQGF=h5^p?*vieSf@z=}K*&Dr_#fcrY)uQrD-7 zzCYqHWnOBfu1^(x`k9zA`?XS|sEWQn;xJ|QtK4~nf9KK)F@nEhI*QB+0WADNgk z`?XS|sEWQn;xJ|QYo$g}6@B{O$@KQPc6;4V{qlHEe|o8L#nViTDz;CnFs^uhN*Y%@ zucXHn&ugi1#q<4kT=6{Pjw_zW+_>VI%eaCu-9G);XpI|Xdi(sWK3;<{Ei*r^>Beg? zrnk@c{qY)%>Fx9EFkXW(y-}uj%Jfc|-akJhkN(m-WqSX-k{++Y`t<(!ZaQ9r_351+ z`*+H;?npoSJL;b9;|kWNbzkW58mv$2-nHX3SfAGYFUM=JKCOG`jn=5Ukc}(Y`Lyoj zG+u)p`*pXO@fxg8>y8!UHCUh4r{0g(!0%Dl$C3YhR*%0%slZH21@6;Qfti*H+^3}i zGc6UkPfG=6S}Jg#mI}tSKF!BxTJELA#7YGwRw^*DQh|w;3QSBD?X~B}UC^@-!<}4` zQ$Tu!0%$EKU87+;~hNe_v)i-2UXNm$~*Gec;Kt?!b26cL$dK; zpBw6(2;=jI*0BANi3j`CSnos__lMT7{Sk);GXnKagmL;>!=|5!2lGMoPK0rPXbsyR znRqa_RqsR?_lMT7{Sk);^M&!>0cp9?V?*$=wWE!zLGp2lG-ZHF>J2*?%~t zJWT)OE+qUN@a6G6qAF^KWaGhn;YN+3Dr$F>^G75e%zkb3UIkV3>1Sff?AP}ArV!sN zsfxZo;t*r@Yom7|siIFm6H{itHhK@5D*FET4yMdHZS>ARRrI-JV#>VKM(-X}Mc*Hp zm@@md(Yps#(f3Cjrp$iv-)X6$Pd^XSKlu$F^MzW&_D3Wh%oqO2FEF)6&HwVa7SF_k z*{>TlimIsHQG9YP9?X7~y9=;UR7Kw(-$9IdsT*~Ds_1ix$<*8H$Ue_N6=&no+AlwS zRn()uyl0<_M{B?Q{!oSOk8|;8?U&yls<8c$iAQU{{Pa~}(?1gr`vfYlKU7h>qZol) zJX-tZr>}~de@TB99;{Fdldct&>FTsGVx%3%s$82?+>kE`y&ny=Ev+ay8ZOE zhE4zLJnVDNJ?g5c%!|o88xLl#>~rz`4$>O6he`)!;=%mbZtfoR`$KEk{)oea`7yiW zg`d9Gu<2*w!Ti{6?ossnLu=Un$i##BF}vH1-yd4T_D38Z%zo|ko;+35>_0x8WMazf zm)*z8KRalR+9Bn$$9M2x)@e7tHuiJT8a9_qJeZfVd&l|xp*3uO<>u>C5pRu#1a&c_4W zufjtWwm;(Vz;3H#s|uTK93I$9m26dEvpp9NY_3XwsKWL~CLY*+mGo6%(?1svY`;o> zsKWNgxp-hdR{BE~wm&lQ!1k-8uL_&~nRr|t`PXOKdqz0R9@-D{pZ4cXN z|5yIfb`4eJ;?bHbKU-DQBcdD)nRv8r%THewHvMz)X#JSqAF8nZaV{RMAM^V|6}CSz z@o4>+pS~(=`sd=&`Z2#hRAKw$Ts&Go=J$sxY=69mM{BP9TvTCmITMfKdaLX6`a>19 zJBsVe#e>5oi2m>(;zm-UA#Y=6Yz!Ti|O++XOwduR=tekLBwk6q0@ zihh4+4ci}?crZV9HTNj`{h>8%f5hRz{Mgmpqv)rvHEjCt;la$+)!aSkC#N-Ra&dSt zFLgEd2Kwo14V!)@9?Xwj&E123e`pQcA5nNL)EBCvCR=>r*?2JfwNO8%ioSy~F=h5^ zp+->^eSgGZ%Iw!djiM_0^fNJK_G_U=Q5AiEd>i7E3^3w3>}==&oM zQ|7i7>I+rTr=N)_vtJ7}imK@QBNJ0*zZPl~RnhlH6s9XRimI^Lo{a~yUn@0=s^~i? z6H{itR%#Sg(f7x9FlAn9rLIpEeJ+`pGB34K*QbiUKjJWD_G_g^Q5AjqnV2&BwNj&~ zioQSMFlF{@rAAQ|efpW0GW)esqo|6$KQb|8_G_g^Q5AiEL}9v7qo@j-?L0h~m)fZ7 zQ$?R`9Hz`VZPetcqE9~)Q)a(5Y7|w`_eUJ2%x!Jd7pkI9KNC}Czcy+VRnhlH7N+#>_c3ijib@8&}gq>UrB1TJ%0ZljrLmcH3f~fDMX~vUJbtH ztI;;!h&0-(xz~I(+U6UPM*IElYrYz7^NmQO{Ra0nUyZi;Mx@bx1N)k`*vnt@asIRO!Pe$tz5({~*LBS&VP13*!o<|uSUH5 zH6Q0cJ0EO?F6LJuUjCYo^Pim$wni88s}C=K&BytFjgQ?s?UldAu^)@i2m2kncbeB9 znvagp`T1dgWOtME^4ENv|LlCQKeGGDdHHKT&VP13*dN*b;=KGdALlWN?C0Y1!G6u|%;xon=A+|(ety^=*`3$C{52ovKRX}nkL=!SUjCYo z^Pim$_D6PaH7|e7$NA6B2m2$thnttb=HvXo$_M)$yN8;WkLKfiewq*VH+GjaFJH~a z`OeM<`ysmvnwP)kWN?BC+^!T!wdW9IdT=A+|( zety^w*?r2q{52ovKRX}nhwOf6UjCYo^Pim$_Ct2RGcSM5$N7Ji5B4{9M=~!T&Byu7 z&IkJ;yW^ObzvkooXXk_ck==95%YUZ%_m}4t+rMAq?enP0zwMr39-r1PX*?gl)*pHK zYP_D`^YO9!WWByVjkkU-BcIl8vkiN*pJ=Jj+w8=r^ci6!~W;?OXKML8=nvMOE>}ZX;6X&>s^=aMhaJ&ZV)4F5Ycn#L4b=Rfw8mv$2&M@OOSfAG26Gm&) z=jV?r*s))qVLo1i9sBh;$m2CwpVnu&j@Mv)TAv5$uW=`5k2^Vc{QUI*?*E;fbAEmt zchXMIh#HU151)H?at)#J==|`zz)r3ZH6EQGzHZvd^}ojdHa~oYwUg^7jYsE)Ka()u zqw(1MxUa+JMDwHb!H$OeTFpmhaejW-79GTTYCJkW?3eiWEt-#y|JnIqzjP2kr}60g zuwUZemufyf{uv+acMjsmG#;HF_B;H31I@?B-|T#_KjQb3XgTuz*emE$9XGWcctxl z#I7i>raE!&wWy+=8-73R+1YrszR>RvRn!hC{qY_it-11ZQH9OrTs&HH<@bjwY=30p z(fTnzeO1`>&&8wlV}5_A!uH3xc(i`Z?+;bj{>a3m^<#ees<7#wi%09n{Qgjd?T>Tu zXnmpIAF8nZ@eUsLDO_GIs;H?H*LOA^%v@cm+fqf}L2;NeKW3l6=bt~cM$NyRKQi%P ze(Y-Q9`yS|YuNsX!-M%T`)o}=eXU{B&%}fIv8%a9(eDqfVf!N!59Y`0b9Mdx&>FTs z;_zU8>}u{&^wZZGHvRYTVCKp`%i2#)YuM!C@L*o*YVHm6)7Kg{{X9JEGw8kaRZ+7q zM)7PsnEkSQ6!;yaHEIu)4vNEr*{_BAF;&#;Kh7VSm@@licOUW34qBsjNI5%X;=%mb zVtyCx_lMT7{Sk);vtM>!AwPYsVbgyP59Xy7^Lu1JIjv!ni^GF?DZ7`KpT5?x>1X1> z?AKy`kL>q{*0B8%hX=D?c9%XseXU{B&%J31l8GtvQY*cCP!)ZDWMazf*Gi3|D*FD2 z!<5;tmEJw5iaz~JOqu;!sZmr#-yd<9GW)gCdlXgCr=N%EMvbB>Z2Gx)Ft@c)U#N<{ zKiGn<(pN>zzFd!;jYn&){Qgiy?U2$RnRvAJ%THewHvMz)XziEZAF8nZk%>oZzx?!7 zVbebs4`!}z)NQGv_Rq)FXC|i1kKL$2Q$^n&-@%lbtDCud&_DBQjhamPRFH`WGgmir z_n_Y&TEq5793ISm-OSyCe)?L&rk{t$of<_|)a=VO-Pw3BKX#`EO%;6y#bL_)*xlTt z=)HTWqE9~)Q|8C+<{m}AKeR^ekn;W#hX?axcXN-TpT5?x>A!~u^HO)}`czSK`?xNQ z!<1R4J2iQ#=+n={l-aL4^<%2&`y&%mX20&#D5|3Gk2p-3{kl`5sER)QJWO|L6jfo< z&&7ket)2QpRrLLli7B&RJ2i@`==r+MFADNgk`?XV} zsEWQn;xJ|QYo|t06@B`dm@@mdQ=_PgzCYqHWo~PyzEBl?`k9zA`?XV}sEWQn@-RK9 zQB;LZ|6M$ompZ8HQ$?R#CZ^0w9n|%yqVJD5Oqu;Us8Li!pMEB$%zhozD5|3Gk4#LN z{W_>oR7Kw(ahNjubx@El^95{gH>q#rQ%meO1)#i!VGIkJcCZ{h^B5A*Dag z#e?~=i@8V9?;x#VJ17nh=EpAP9z{QWtzpy8#Dn>kE`{O%!FfUd1bFJSa z`?;vX=8}mAGgoDg2i6~|u>FyV2lHd)-V@dzs<8bLhX?ax7jti*|L&nRZ2FmaFh6!N z_bB@Pp*3uOMB!2HRKjO|Rn%mQQ9K(D=EsUdV;!W5+C!y-GVx&ctGr&;AF8nZ@f|#v zm%38dr;3`&$C*D9Q|6_v)b**N?~gc4nfq>p0 zD*E&@F=h7aN{yl_`u@nol-aK^eSgGZ%Iw!djiM_0^fNJK_G_U=Q5AiEWMazv z*g~D7D*FD2!<5;tg&IXw^y$BcDf3bbb$zPnlZ(Q1rLIpEHruoDVD@XJMo|@g2W4W) z{MbsJqbmCTh{KfGuaz1_RrKj+V#@5-N{yl_`u>Q+l-aM98bwv~>1Sff?AJ<-qAL3S z_ztGbI<3^?siMy%6Vuj99nQ1USL6CraW)>U{qoaSMLj>1U*Y88u^FT2rLT&befd?| z*?6?}%kK|W)D9{AaV{RM{qp-m6}CSz@o4RrpS~(=`f+%)=E~1j6*k*AJX$a1XR8XE z?Rj{#Pbhlr4UN{m_)R`N&B+R1pK7$tHzEyoeOaFl^m=q_Zkzs`H1HLqM%x4<(!f`d z8g289NCRI=fm8J#*wM9JL!4H&+PoLU9mgkd9P3NaevIt2fG=&H=dWj=HvWl z=Y!pi-TThVU-NPPU*&_{i`@gy%SZEZK0nO|yBE8MotLlX<9ui5gRPIKhIyI@n?Rcam=qiTX{4e^Q%u^9nHu5>hl>#^D)2r+=3{>KccT9M`a8kVIOex~KC5XoAM@KjpXM@}kB{H&^QjV} z`S|$VK7U2+&%b@%TR$4d$M5a)NoJ$@`1rkjKI>>SANSww^Jyrf`MCdXpHF2N&By(B zC;aZ8zf<+szY~6U(tmft?@s#fPWatP|J@0{JL$hd1-<|6gx^m1?S$V>`0a$>PWY8y zD&r%dRN!++slZ18W{8jAuZ-ezr$*bmha%FzovYC{--tBuc}Jsdz7c8QcMXlU`Ti6Q zeEqM{HlsOd;7=GDZ4;c62L24K(Kf+|H1KD5jkftlq*3qE_brRYnIVWi&Mbz;k!7pD zau^*yv-87trT)rc^!hX(_s8sfuzjh&av0^W`8fZd=7a4^{T0I~U(Lt)ew7clC-qkh zqkJ?U=QBGWY-Z}O97g$TKF4jjd%s!v_tpGLEFT~HE9uwQr}5UGW#rTPFYonfyk5Wk4L+@Z z@z&Qk<{zC;>vz2THIDO-&ZqTbUj7=#`A6r|`Y|tmjpO`h=hONfFJF!0e53Pe{g0Qw z#&Q19`LzDW%U|O-|LAA`5B58o`F*9A zzvkooXXk_ckKHBF%U|E*Ba==h$WAND_Xms&4> z&ByuA&IkLQn|VH(m%rxY{AcHb{g2&c+RI<_asG@C_AfVbf0)Lj^TYnd?$YiZf0~bv zzuEa<|8pbvk7;~%e%SBah(FVKbbi?H+{pcB8jsEI{tNpdjc4bB{n(xOHI2{C5Br@v zx&KV#f14lnFL&a%G#;HF_Ahtx`%8__&JX*ayYXl1%kzab-tvpcr}aDD->>oN$1?J1 z{g3zhG>-F+&ZqT5Uj7=#`OnU$^*>&|8prv@=2LdfL$6Qc+4;2o=k@sCjX%?Pzdy*= z`Luq<(z8pruZ=hONhFMo~W{G;>1erP9tP2;ok!+vZxzpwO;f6d3o z|LlCQ|Jlv`XI}oAkMp0M5B5L1xj)UzU-NPPv-81zXgBw#dHHKT&L8tRh~LsU_FM7! zV83+`zoqf${IDN7%>84p=U8ytVf*7f zJg_$^xv0YCl8FblN+o?&*!0iE16!@qAF8nZaV{R%dX@fAh3$_#JW9IAiC!MQNEL1R zXXC+qVd)UoL8`DFl!*uPV;5=^RZ+X+_v2`a#Dn><3pI+W=+l1>Q)aF%)b**NPc9Bq z=A|ywE#@9Yzdy8w z?TaI$==&oMQ)a(bY7|w`r=N%E zMvbB>Z2D*8!R*&YjiM_04vNE+*{_WnMOF0aXJX3i*G7$^D*FET4yMdHZPetcqR%B0 zQ|6^M>iSgC_eUJ2%zkauD5|1QKNC}Czcy+VRnhlHCZ^1OZPX~LqVJD5Oqu=Ks8Li! zpMD;uH)<4BVbebw4`#n^)F`T=@1XBs%DmK#x;|C(xx``0tkaE}JXQ4RXJX3i*NqxQ zRrLLli7B&RH)<4B(f3Cjrp$ibs8Li!pMEB$%zoXdQJk~l<~$kQ{-vt;6CSPo@`09!X5-O*`t_4jMNO}CawZ<_r(ZvPRoL{;#iRZ7 z>-UE$Y=4}KNBim5?+;bj{>a3m{q*anuL_&~xp=fj!S4@M*#3AA5B9nAPCvP-qUQGT z`8E^N@n`+=s>^2}Rn+{?#$z{k4|(TxRn+b%$4f3A%=PWm2CAa(k4#LNAKR%xQ$^n& zahNhcwwrsD{C5wnQS&eF9+`MBKen5Dl>GkC8n!>;@L=|9H+LZU>1z#}{(E>ZbG4hh zhy3KUhD|OL4`!}*bN7(nA6moqM;so^e(lsKs-kB9;S4e{WxjByMo|@gf8=3$P@|{{ zn|>}H%zhozD5|3Gk4#LN{W_>oR7Kw(?_tW!)j{2sD*EK&FlAoqpsr69efpW0GIMoM z8>ouDKjJWD_UoWVQ5AjqnV2&Bbx@ZtAbGP^JrI zx=^MIWxCKlT`1Fq_US^IF0@bEed2wl?atVv3U=(by9JNdV8?#DW9VoNcI>zN8;;gs z$9}uV*=P-R?6-RZ`D?U$;fyNSdsMq)#%K+8?6*(v_twDYFxD67{D=Di|J}F`@VScR zALq#B$F?fktHbhM$&TFbsQ8mJDn72RkM|c<)a+vMU}wdZUZbd@W?w$h<>JBK*Z<^d zN^8^(DgE&sJn$7s`LC$LQa=|Dd`(*VLlw3^&cy?NDk=S;3fmu%0Hs6Re@HeO$ zZS##tgZ=JT=fmuY#*vG;kngJbIQAFpH}x8i&JSCc3;DKFoE)=jYS-e4Niu z^TB?_?z!dVtNA$J+4*3Z1qMS1<9`RMrnd4Aa6*u9>-d^I2EJ3AljckFIYUjCYo^ZzOz z>|gBeQ(iurkMsFyKG@&b-J`sGH6Q0YJ0I+KHnV5Fm%rxY{AcHb{my2dPv+&X`8fZd z=7assX7*6`^3{Bt@9ccA-`ULb$GrSCALl5wT*Er5UI-l0>c=>A_=RZ3i?7!~j{xUCr&ByuA&IkLSyScy2%U|ZazElV;aYPEIuFX$9Cd}G(I~&?00r^f7$E#UE|UD zVgIw6`^&uiH6Ojd&(9D0pWWPl=H;*XIRBsKgZ<8K?l1H5)qI@q?0m4_*@-{X_}}J- z{mV}Lmd0o2hyBV<{FTO|^TU2;C;m+1vH2aupJ^QXv-$a8zjF{jrt#?fu>U!TKht=0 ze%OB<#Gh$=c7E939K?@le0F}=-yFn`Y5b@8VLx*azoqfn`C-3v5I?5z==`w%Ify^g zcyxZ){~W}hX?$*emxmw221ph5i4*7JfelgNp^Dlg=i`A5QsJQr+aH;DV1HE7SA|V~ z79Q9PmE=@mlgq>dd!v%RDs1}a;(@(X=?_)d{x}y8?6pdNsKWL~CLY*omGo6%(?1sv zY`sc_coRGy1R>&N{5P=)P}OgvgY=BKX;oBp|Yw0_L*4^`OyI2VuBkNN$f3fmu< zc(i`ZPhS-_{Y*Ss`{k#v3Y-2MJg&y%dC94w=2jfa*?6>G%I^FTs z;_zU8>}u{&^wZZGHvL(6Ft>Fz_ZRxvY7Lw1EIgRGx|+KO{cN>{%{CJc=C-cp?m@pl zw1(}EC_ENw6jf1^EuZ(##)J8>g&H(f^c|FmDYIV-HHxa}`y&ohX1^Bd$5hd$pNT26 zUkf#gs_6UUJD4)-v`~|$iawW2OqrKjsOwWj-yfNnGPku*U#N<{KjJWD_G_U=Q5Ajq znV2&BwNRs|ioQRhFkPupRE5pGn<(pN>zzWg5fY&=@~<@bjw zYKN5m$i$VY59O z59Y`2)S#)N@1RUfnL)doyBNKz3sv;}5r--BV|R0pqMyFjsQF(WcU@%S!Ti|W+@t9C zht{zD@f|#vxw@OX2mM^MhRr1t4`#0J=I%kiKeUGJk2pM-AG@1-1O4>1hD|>c4`#pa z)F`T=c1JNrxp*-9b*DyA6@7n1VY*YJs0y3y*?2JfwNs<0ioSy~F=h5^r$+I=sW|@s zy|?9A{(X5|!8|?8xZ?Rqd|dJTOgOH1ekvGOJg*$b70>IjamDl9V^nc`p0&pn&mJ3B zJd+z&Fs8?+4;rt*m>!>>O~-36rpMaZj=x5!z)VX8W?CvR z(^7%^v{YcGr2_Y9slZH21@6;Q!I)kiHJIszGA;X3vo#pg3uRh*I-QRjt1j37}NSB@X;Fe$=Blw)~EF;yyG=kpVnt} zj@Gc}Ag@2lUW)bD_bb@nVb4MS8tizn=OBL#cD$6UDfU`aQLjO-kM}TkG^nET`u%th zI~R{XdC%tW>Z+(c^k>&Wafq?2i*m%^bFwOGca$^C_wZoXALYNpa#2N1rtpfxgI&{I z=~bU9YW5#TWhSQVivDW6gLgHqioQQGF=e0Cuf{t0{h>8#hm`k@I6T;A^{cV8e)?L& zrk{xivv61All}hC8n!<&@nDYaNwiRrKj+ zVT$h$&}f@`L>l<&Q=@IZ5oxfiNBj&Tjn@38 zasFTBQ{9QrU*nj6bUxTa{U3X0yW}{ME7|%zX7ea%*7}y-|HW2uYjPBTK%CfVb(R3R zjqPsR(i0^*Tp{u>7_kFRrQ_B8%c;)1`&T?Z=-jyUw@zX|4;jq^PhP~wz$9g`@FyJ z?oZBl<{j7K{_F4a{=d6FIp3N0ON;xjzt8*s?*8QbXWlU_?!W#%@Bg3mXWl0)>YtA1 z{H(q|Isck>R*UnYzt6tkf8W2Hzsx&%#r@IW=l%K9{^a~?-ia&jul_#o@4Nex^PPDw zuDJjD`@H|}?oZBl=Do+_{_F4a{=d6FIsch=+lu?Izt8*s?*8QbXWm^b?!W#%@Bg3n zC+9o!u3T|{_4j#y-`$^_@65Z9#r@ac=l#$9nRl&<{MGTCZ`JoF=Tq~(R&hS`_u2RF z{r$`N&b)6`+<*Oj-v4*^C+9!&&Q)>$_4j%I-`$^_|I9me#r@ac=l%cF{^WdT-f1iD zul_#o@4Nex^PPD|ueksE`@H|}?oZBl<{i7@{_F4a{*ymBf0_5piv8E$=l;LDKg3^j zJnwI9f974DqVKnk=X|ZcKRF+pcfE@9p})_@hd=LM&UfZrtK$Ct=Ov zdD;O!?vMUH@6WsYlk=Oi*&iSpfA#ly|Npc$Ux%|@cY<&Oc{mJ>u1^AYZzq@}qf4KnP z((&s4<$UJ?{7lEI`cB$@$NC=AHLn$NyP>a(;CMzNO>U{mc2!75JHsSNAXHLs#HyI$qtsoDW@r zuj%-^`+ z3DVjaz1nezNX`U*T0<4+<{{kBx*-f~2qs>f{IUv7MRK7hQiy@kqzl{o7Q@58`7xGv_bvzG^)B zKf3=jeh|6Znb~@A=TyUXu8tqXrFLenUfg}vu-)(E2l26;nadaFLp5wZI{86-Y-i^B z#raSTn~yqv5Fgu_nTB!qRl|0_lOM##c1RSZc%KZt(qktj;x z6Z8sCiRA5(+(XRs%MJaqf>Uc`@>wrX23g7)so)Y~! zAW@XU=cA6N#I_E|3#IVg{~1q-OC6B)N#Q$J$5WzC2PAn?`0n@d^oT@J3fuip^MmNu z5s9J{K0$RnCHi$lq9}#$ekV_fejSl0O5yWS$5UckN92W4`0mf19-h`*A8(1*QOxu! zJ{Kt-{U5!37e8h$6?aYw+qq7D%v>t&z7)3mpXJ9)zv6sIVe`?+kC}eO-Iv04|C9VU z8KM~FLyAW_#=GX9=EqFG;(SQ)NXW=XCqHKT6?b0>+x^e-W2RqmKBTbu_!&QlI-QV9 zN%830@8A7So)Wn_A={F|=cALS#K%r%_Fz2ntHvWCH_X7*s*ebunt@8k#Z zv6Gpj80SMZY(6^qK?Ln&W--S3Pz{@pDt?@iC`$3@?6|Y|G(Udxv9VLkU-xrA2D2v4 z|Cy(jYkuEJ=bGR5Y`Nz5b$hP)eeITOe*ePfn%|>*uKE2<&or0+e8+MP`+QmO`SPDR zVfnwsK41QGN14}QpD+Kp_RQ#)zG8)J91tj_mp$hn5|{JlDBUWf9`Bls2b&ZGAgv(6*; z6?6ViC{9mTgZ^KU!hSFQ89)3l^7FqU#e5g{b^o^5v8c9V_8K5M7b)ic`>WILj@jSK z=xn91`S=+>?6qLj7b$FCI{9I*KBMkSVY~lXe%L#_C?8VTe01`|GLoqKQrPZy^21V@ zsQXgb?thjamV8F}kizDplOM#C{L_UfAF5&VQN@qnM0@7w&)t>gz5F5iHu@#a_p_Qf z&!6lM(Wv2^GFB`5%lV_u=Kg7z0E7IiI=;{xVwBd?0c{aNG zL!526B2Au+ivAEk8)qy{-uHL&hnUwm8)@>Mey%^m7vgNvJmxz`T&u4?%(&X9b>ko6t!@@i1(olY0q79KS#$8qn=9hxG#`D_8Ri& z_+jjis@h zW)^pH^E2aYs7`jh`Z^DpeVrBnX{c1c&0Rzjh;TA7kH*Lc{cj`!<_BBz%!+x{8aRrIoo-GXG%lac$Lr0 zzRnAbQ5x!3MW2}so);LSG?a~sJ~L-KFYruhC>s@hX3lnA;F;1;HY)neob9~8Go_(y zRP>oS+j)U!N<-P`>NB&r^8)jfhVt_opDzoHQJTCLef?qfby;AH(olXX`poR>vcMRn zp=?z2nK|2KfoDoX*{J9yKl#N&U%g{U#gS$tD-;5 z$8K)UWSkAv$+J<>A7*hkH)k@=hU(lV{_T{UH`N z@*_>2pI7-qTx;|~n!FdE>(B6o7@9OWgYD}Nv&!89&yyKl#Pl$GmG0T@Jwka8x?(K7PnjAnbJ@;Ugb0MvE2e=l!p3M z(Pw5~y9ItI4P~RN&&=y~3(Qj*%1=F?2kj=FDNWw@zWy+0+b{4;X(&GxeP+(KU*MV2 zP&O+1%$#k%z%!+xY`mM#%+U4=tWp~4`%n7J>}$Wk7^R_}R`i+K*M5O9N<-PG=reP+ z{Q}RFhO%LOzCNw1Kd!LfO=CG*{F$Zso`d&U{#b?Ue(bT-_hy^g5pR|K0uJ>(2cA^!K&>p=(PW&-+{5AG&_j@x1@< z?hjo{>UiGY>i!V7*73am@9qyVejU&I`%n8r^I3H~@6WsYLvvDfJnwIHf5ube{0yb| zGAq{f@`L$~6m$Rm&R5SwxtD_YnBVOw@b?}V`=8{8-zVrfA5zTe_`1J4VEJin$1LlM&P9s3|9;=7 z+KyQ+6`hL|w)>yuhb320KHg6;7}fI~&b)ummf~?IzNL8F6K*LU_YGT$$F=2_;&J^E zE9SMrw-k?2drR?1@|NP!+bzX|ZEY#Y)5G+x?^X@+bY917s|I;GuMZU0m{-WzQjn+f zN)KB#$kX}F`K=n1)9<%v$CJ&i8kE!Hv_e>1<1}31kSNaqC|pPfzIS89hBuZ$8JL<2=3px}_jb&(phbTQ$hjGkSVPPtVgDhFhP5zWW#S z^n#vV(9_HGW@-FMFX-uIdRuL)27UK0=;;MLyO`$NBwyLl_6Xi#m-)mNl>#@)B$MU-P+@;CJmU%zf z?fg{q(6Y)n8`9+2_(^{(AB+1XP2R7r{#ZU1XG5Ai8(saeoGs3VG*<~?V(#}?Jevr*3**>}07hs?+3y<)ehTUeRY}asCaNc-&B(eB7w$53{&= zKiTbZLv`|ORP={goPR4W9ye4c&qhUmn6u6M$!?Dus*`7p{F|`xxS=|EHr~x2 z=3`@xfbUhXx5or&^1i>DKg_=TTkG-nU3K!l*Yn4(MG*B}nw&ZG^@lm+ychb`?}ap! zpNc*+XY*^6#AA!RlZb@FU<^@kbSX@ONrL-(E)eP+()SB#9u z7S+kemU{m9bwH!OOOuZYef?q1=2wZ0^P@W1xKYzX=8%4U;5ZwqlV_u%Kg`+AZcWQL z8>*9M<5m7J`||5_$Nf^Byk8alVfJ-)YgWhEP@Oy*75!n(=GW$rv!Ob9HY)nVoXzjb z5NAVm@@#bVhdGg4&U=nr$Yv)i{K&W7sb*{J7_--9RWyEHk^?CTG6NWVi< zoFCQ6#*No`$n4ASmlgNxpQtltG0%H?j{hFJF3tazG}fV4`ZKeyEuW?N{XP9Oe`e0M zb?(yS+34!e%-OcGAx)l*uKvuNZ7UnnuPhs@b-3-ckRp|Pc+&&=6w3p`UA%0@+>nX}y%c&0Rz zjaT{1?CZ9`7^R_pRrHzJ*KL6@N<-PG=reP++XBy&hO*JsXXb3T1)eDl<)@<0%-L=W zJX0FVMm3-JcbZ8&Q<|LDb@qoi}&K(n!I0K{UP=> zvLQ{LjjsL>XB*j&CeKD!e~7b zlV{`S{28Bv7@9O0Ti)L(TUQU6AMO?yqcoJCias+R+bu9gX($^NeP$N7Ti}_}P&O+1 z%q(u~@66XE(qz|=H9ce&w_D(u($Kik)o12)y9MSc4dthz&&=Y+s^0v&BTfFh^D2Ls zkL?y1intAp8;g98Gu|Lv$e@{QjpFx-BF+4hVX&%4tpXHC`Z1K5E zlZ_i=^yTkYMUCZbaW=NRwxyt3Q@Q#@Uc2&qh~&EN6?eAx)l*pY+Fa zt+-#(oy<$i&AN<-PG=ksBKXG)Xzy{|va z*$xZ5P8!NjMW30)9o+oP=$cj<%0@+>nZ+I4{LDBTs*~OCyv{@BV+S{9GVYh^7^5`QuX;X@9pC94RcZ3R_w|Q4+i8JkN<;an=reP+(*n(tA9{|g<9UCp z`$Nx)b$sss{%I|F>(BrHar^A|`R{c+_y67f8E+-#XCTGA_rTZv$#5sfET4J)e*2vp zrT8qzEZ>T{FU34Q_}wgPJ7(!lbS_fZ?thjamJUVvkizDplOL8HMctRecE6J!mK;Uh zm%?`cUHq_2DC(RPwsW2QAR^@V9*pv#8a5ww{2(6XcUFwLuNt=def;qIB0hItin;e+ z_jdt^23ArK+wyz=Mfp&TIU&6qBi6Tf@5V&=Pz{@pI(`t_+Pk-3qVB7P?S36Uh+OU6 z`z=xTRl|1wm43{X{eCCUy;xDuFS*|}B>GoW!}g_)AN0HA_XUZ%uNt=d@8Spj>iB&t zqTZ^8?d`kxLBA<}pOC1xs$qLu#}9hKy$?we(bze2+{=bi7#FYHr8c}am!}hk0A4Hw}?io?{Rl|0_lOIH`{0{5}>@_f^Ao zzm6ZorTnfKQTJ8DcK;{*@VhcR_eF}iD_{4Om5I|;QV@mnyHZ5?P>neuy&NNQ<#(ot z@}U|wA9eg7a^?4)h`O&Dw)=JbATH&1mx#Kr8n*kd_v7%iMxXD?Kc%qbD*9KXu-)(E zhb320_ocAiujt2k3u_mQFb^)ZrFgK5Eyd&hHddUcJFP9nr{`(6*sU7m=>6Ty`raA^z=Ht4ZHO@D5uwHU#P7bl+)|9pY>J^`tD!R(;IqvLr-t$ z=?y)-VNP%8=?!ywLr-s*(;Ip^R+@dVtGIVVLu2aD(5N~zGzJU}C3a|N92go(?a^}!@Oii3^Smb1_IZ)dGiQyf%q(t8 zK}nt&$5stW@q9<78iS$Nag0Wvc^}2C-l~SZ6RP6}{jQvFM3iFg{rK*8@|3PAPWWpm zh0n(;Jf-Wn6JF^_;rmj@Q@(PPV(#tUJ9$dv>Wma!3ZIWxcuGv^jMV8} z70bj#(}hor@H<`=8~9WqnaTq_FwuQOQqj3cG56ok{_O6UC0EheN@4TS$q&n=qV7v!yZ8Mck+Ws-UZo~6mvSp9bYF;iEa5ezM}C%HRgm=a*W88f15Ar zzG~R+_wmEOsrlS}DdygP-DgP?4XmUf*5}{Tjq;%yb3$I@7%?UPc68Ji)v$f3;|DP% z|K@wtebunt@8k!ut*e`p7v)1WY(DDvLFCG>X%Tf_HEj3m_(A0A>gM%D-B%6U{Z4)m zx$>*kMEOt+n~yqv5U0Dkw|t}StA_1`E{tGe5i)a$KUtEukH2hx)ihLU-!4O ziNaM<5JB@RyG8j>jX5Ee93w8}SM7_suNt=do%|qj<=1SC@}U|wA9eg7F6GzbjJmHH zw)>s@AadnbV~z5m8a5ww{2+4WSK5ubuNt=db^IVM*hWh>>5rI_isR z*uHe~gNTt|xjf2;YS?^K@nfunPV7pWfB*W||E(E6){lNpe`kM) z)%xuUe|JhJ^07ES(&YK+ z>W^h{aWyWxnc3H2 zfiX%${i^6Qv#-MfW0Z!nQPF4SY=;G&DGg<#p3lbxo+(Y<_rCrxXFD$NOlc@TU43R2 zH&%(Ic~;U;ekyv%ob9;4Go_(yRP>oS+i`(sN<-OrmCww+jth)Y8tPX?pP79f7Z{^7 zl#Pl$GiN(4@Jwka8x?(K&URejnbJ@;D*DWv?YO`*rJ-!p^ZB&EGo{J<{@MO8i#sha zPiZJ)@8&Zzw9^8sl!p5LlRh*1IxR3pX{e_aeP;G`T40RQP&O+1%$)7Cz%!+xY*h4_ zIooN0XG%lasOU3uw$lR7l!mfV(P!ptrv;uV4Q1n>@%b36&+mKjziTXKi|a`9{Vw^R z_UG&vWAu5Xd3;Yl%OA_N;&YcK`!1gyU;Qi(Egy@|U79>UUH!3~EzX8Cc{aNGV>w%# z4QcXhboIw_wm2Kos@hW)^pG^E2aY zs7`iGQqx0baThl~GtP$UM1l!mfV(P!pt z*9D#_4P~RE&&=7b3p`UA%0^e8nZ;cfn5Q(9pNc*+i@Po`PiZI{^?bf9@Jwm)zW=O0 z%)V|5j8PiuX+@uzeccuqqcoI_ias+#yDhLvX($^NeP+&fTi}_}P&O+1%$)7Ez%!+x zY*h4_IooZ4XG%lasOU3uw%Y>Fl!mg=)o12xw*{Ul4drLWXXaYB1%4N7tx-MjZh z;_*jy^6{slKm7c0@7@!Mv!Ob9HY)nV&mZ^h9gsL1s*`7p_6xjD8oDNVjn9V# z#wbnRi@yFa8$2v9MrkNN6@6yTc39w<(oi-k`plf|u)s5=p=?z2nOWSyy#o^6J4i#> zsOU3uw!;F?l!mg=)o12xhXtM~4dthz&&=5l3p`UA%EqgFX7+VhV2sjGzbg97?CY?= z7^R_X)bshcz%!-E``*_d=4{6Wo+%CGr=riy*^Uc5QyR)fMW30o9T#|}G?b05J~N9u zE-+7NC_fLM$8)8K8y_crxUG5cjcv{2K6hL5xVPHYJg%{a<~*(X^7}ofaUPHNfVMS{ z-`s7@W9;45Jide58tZfXnIDWXu0!X<=kxt;OI)AMgU*3Izs<aK0hno`d8>1KR-9xszIL4e0Zw{ zc{+2cxW;^kzNH{f=R1|H8kE!die#$>efN*}-9JuTe(PT$PmdE1jBD_(>}g^Hag8x1 zQ_6;hJQ*5F+R*Tr_}9XyD9!Kd%I%&~x<)VFO+&wR<1xPjHY4U9Rq(5|JJh~-K-mk9y(DnPshBSFLy86TSDJx`0n*83Oraydtx?8x1 zm4>p>)n{fGE5uhC%1=d~nOW@?xRx}Ojfy@qLtA;uBMoJvqR-6Y=Jh+bn4UD0jo0|h zPf`b!V8$p--mjYeFdyUR>?1#_ld+4M{xFN1*FfDG=cS=>qoU8u;^uWyx3i%-`M6Qh zALf}nt7`nFs7{`ZuKqBK<2iRDKdO`Gr=ma1+2(apw|{q3C(p*K{9*RRb6>}IS#|P$ zRrH71*SvP=_IFuz@@!P}huIg;cOT=1>g3s|=MTTdFlN#)&y*(T5;gr{4mq!Zy7ikP z4P~RE&&=6I9%w$cG?b059x{vLci+Zulj>yGBsKkE7B{bxy8XMOI(ar;p{Cca;>s*d(s7{`ZivBQXGwNKP){=id_bwX0dT(@I z(mck5KktuaU-9RW=KJ^kv;48#FFto^@@#yvKbFPC`H?2iPgj2|XN$8TO`eUe{#ecy zXG5Ai8(saeoGs3VGzq`jIpmj%qq`ry~;R0s*{Z^eLZAecXsn3phS4DrAkDc9o$T%CS zlV_u%Kg{CJZq8(!4b{oBQPCe}ac4IlGR}tTTz{P<|@<%$)7Az%!+xY`n^6W?z>D#wZQ-tD?`$zAg)lQ5wodMW30oT^4wz zG?a~sJ~L;#EbvTeC>s@hX3ln5;F;1;HY)neob9r}Go_(y)bshez%!-E``*_d=4{sm zo+%CG=T$y4*Saq7LusgAU43TubzNYL(olXX`plf|y1+A~p=?z2nK|2afoDoX*{J9< zbGGXO&ykqT9+X7>hhVoO$Ci^oGm_gX|~6W@!k1ke=LiO^CL~3pRWE`&K74wnmij_ z{jr=a&W1F3Hh$6{VqfETP@247UHu_`II z#NtLaq{*|<)1Pt9#OtJaJj;&mtv=fy=5@OTrY8+$>?eI@hPHEaFXQip>SVtu@8==& zv7MVU8TVav^1fH}hxypf&6$j|p*ndsD*D4LZnwZQrJ-wpias-o+b!@+X($^NeP$N7 zTi}_}P&O+1%q(uVz%!+xY;^URdEIV-c}he1VV?(GCdMdD?(=8+!|ZFnz!;^Wj8*iR z8RLF|RZ2tIsOU3uw*3Onl!mfV(P!pt`vsmU4P~RE&&=8O3p`UA%0@+>nX~N|c&0Rz zjfy@qXWK9EOlc?^ukxAM*M5O9N<;ms=<^EKk|ukWynX?@hc&0RzjaT{1 z?CY?=7^R_pRrHzJ*I|J%N<-PG=reP+!vfEghO$x7XJ(a$1zsl&WuvFh#|54#O`eUu z{xD}dF7QlgC_n#<&$p+w_s6Uz`)~d48q3+@I?{YUNBi^sSoRfv9%=G^b@j)xuQ(gh z`oJ!;_mc8RuDbvfqoE9x{tNxjB<@HdH6i zMn!*^#hu)o$v7LTlV_u%Kg{AzZq8(!4b{oBQOzH_meq65b$njytDiq~eXQeo|KHso zz6Z$9Pk;aS{Gsbe9nbx(?hjon>UiG&clU>`_jEk(Z*_m@Ikt}H{eO3V=vlOm=ly+m zf9QF#j_3WY?hidP*73am@9xi_b@>@c@nzna=;a6V87b!e`<*MFiRVu#h&=iI2BS}^ z8n(A}{2=b*cW#WjuNt=do%|p!k-S6ZFkt@HaVU!Qmu=%Lt2XQIC zYhl!V)v(>~k-LK;ZaVfw1VAOrpu-*R|KZq&$ zeF&q@sfO)b9Y2UE`JMEl?yH9Feic9bPI%9~m16Gf*L_6?Vtu_7MDqMzfl-1~W6n?| z$7XUhay_5N_;0%#pcK9Qn7LHkTPfymgx&wJzhg7GiqBRGn~zR@%v>t&z7)3m@8ZYI zl;X}wVLR8!kC`dO-Iv04zmp#`mx{YDh3)=l`7x8LI3H5jeDv|d?jsjXDh{=5WCx5b;pPX9?e?V@!6_|%|{(Si1i(()vibGpK0-NTJv~I@wi9c zQatX(wiJ)+^)1EYnr=(+_*IV;^BxXcipN;ErFe9IOYv}hOYvYzTMF{@^ou+_O*_AD z{VU|@Y1#!ku5q4zO}7-}>3JH1wrY^4XUyq&TA_LCUm;J==;?XdQ+?}Sp`2dO)62BG zMf|T^(9;Wk_b=$_1wFlBPA}-`1wFlBPOs?c6+OM8r&sj!ik@E4(<^#KG`3-GaLE&Ne$hzj8$X!xBLAxd>wUOxYm;9_fCRa*ETi%;p=B6 z7vp=OI@vg1(;vQfI4|5=NkijCSD*Qwnu+EZTT~|>TPpg)_rlDwM>bR^&qhUm_=jT=atS}jA@?P}xhi4Fs zReYJ(Nt557*7S#&C(kb#`B9y0Z0YL{^Gu$7H1eZ5d44MT!@Q2?osDd$PM(d5{xFN< z8HXbqs*`7yc&_QlhU(^D&*9M<5m7JALF-lN551j?^i{Cn2+)M*&`dOlV_u%Kg{Cz z&HRy#`gL}}yPW>Kq?zA$9euaFF7`*7?{VX^{IM)9K6h#IY;^U5pH5 zC(4F251uK1>@|sBpDFgoGEZs#q=%M|#l4Uw`z`P*j`i`-^0D~5q{*|<)gQ~^;%rEh zXQQh>mc_-{kS5Q@C;MZ0W}F{s^89r5hk2%7S2fO$>g4&U=nwNczoKrO4b{oB@hX3q zq51WV<9?}5-mi}S?C&!#?cB@fY)CV&+w)oe5MvzKkY;<_=P^7ssZOmnmj)h{b8oJTi~M7&^2T|p9c}AF+rNV?|uDY7B`45=SQ0C zH|2F6G9TM7a7bzB``*=OW@!5bRw)hTr=riy$My>xQX0xeMW2~f?iZM+G?a~sJ~NBk zFECGOC>vdUW?r{n;G)t{ek%IREN;KRJf)#*RP>oy+A$;OtW_Okw4KvC zdQScPq3c>5&-?%G{_wSFet!D<+WyeBu8!yZt?mz9&+2&I|G(=GT@UJb?*F^{L(j2w zJnwIHf9P4Yj_3V*e$vYi<~vf%{r5Y1 zJ`>YQ3Zh?rkILw5Rm0}vXZ#>;<9CpZI;R@8b9MY6YUB5RjJmHHw)=JbAZFxuON_d& z8n*kL{2=D!cb$y#p&B+Hb^IXWs@AYSEneT?#< z8a5wQ{O~&$KKE9NxwBvQw+D!h{*;0!oZnS2>aA+b-L2#pF(to;W7K`su-*Uv_2Xck z0*qST^?yoXxm5J8NMU>XS$NR`J8{?DyPTDdx_8-B*pUoUXQGmeWP&BE{T) zztdxF$1InM&P58_{m=4)*w(?Vp%W!YHEe?F_(A0A;8w|ry003x`aA+n-q!JhxYWU| zo*i{xHEj2*_~Cc7d+x0ib7#Nq_cz4)dMSwY`91BT1gXZHp-PSs+wwd1Mcr2o+x<>{ z5V`U@`$hRs4V#ZTeh|6xd-p}%R}I_!I(`tB^1J*+-B%6U{a5%w#K`Zk7xhIoY+pM0 zLDb3bvKQq;HEcfW_(5FC@1qxWUo~v^JNZH6%I~EYs-`*)v(>K;|Gze6VAz#V($I8=I`Vwk*gEV>yyIgqmHLUu1+}fPYU1t zI-U}jI^oPeDSY?)czQ;*C57#NZ9i;sk5B83o!w|4#ZNePao@sc*QK!E!cX(V689({ zQp^dt{OaU~<;PL?rLf)a}?fz%^VL5h` z4=HRuI{9HKb<}++Z1;c056h3EzDQyF@>zZmb-Ey@lVZ-#*Zm1+6;H271EsLN{WL#_ zZC#OmN#PSz$5Uck*ZZz9|Nix_dj|fxuVgXy>9yzjb${M3#q3EXKZtEz-P)W{_f^Ao zzmp%twytjV&L|(MVe?VP4`N$aw>D?gebunte}x~!l&)^RY19|huzl&|2T`Z1o1q)! zLp5wZ>i9uy>*{9cM%`Bp+xCKYkh|kElfOel4i61^JT&C;(6G-#^>_*qpZm`Ic5P|c z=bcIURvq?vx8U<`!ROtA&$|VmcMCr67ku6?_`Em26S0T;1)ujgTI}xs66blp;PZaL z=lz1u`vsrv{*SRgc9*~{4d>bJueMc(^K5rw+N#6jhTZpNs}7GFc9)5`j$K)QOT*){ zUA26x4v)`vedDbsB2epY7U>TXlGRwriHfb?nMkTN=)@T{UQ{4(HjfVzO0- z@_fP3=YnI;1xKC>jyrZnQgk+UUW*j+!(N-)Sv+w*Xrxq)x}MU=Yv;AZ`B06y|CJo0 zYZp5cDDJ*$*zUi=54w)AGjQU*sD|xJCqL+3!Oqc%^Pw6xA9ehoyOYuHoSR88_kKL> z?c^8{06P;X9vxI;PDmxkh@sh;Kymj~!*;)pA4Ki!yq388s$sj|#}7NNCF;HubMMEK zYkCG*NkJsf&hv@$p&D~SUgH=MG&{d0?u%;JzI5_~n9|A&9M!P-sN)BbtCiVRs$sid z#}DFCH+&W?#oYUGP1ng&B3CzLTT=LZ)bW%!-3@1%Na4F*$5Y}`H=IEvh3|eRPl;UJ zaMr36J|BPI(=o4|sFF1K6U@&35MdkVF3oUZ%w&Fk+o-cYM774bOOt1#t3O1vhAYzK z+4y9Ch>87nj(?X`C(l?#e~6fkGnOXrdslymmJL^=$+OYbA7W|46>0Kp{G>lbzs4t( zChu2Qe~5eySER|a(bJ!C&U9b!zi2K`E6I%YKJ33G%}l7@(I3ky<9y{H`T&HdH6iMn!*^#rfT8;%ul+o{ftB zFpKlM6vf$4oje=${P8l;CAPX^P@U>ek%IIoXzhR8fQaw@@!P}hdJB9y#pR+Lv`|O zRP={Ao8KKc&W7sb*?2d9n4ulqyX0}-RVVNJPx`~`%kR(~_f&QAp4Rin@46oKU7DOR z_VtH3uPhs@cI3p`UA8e6*h%q;Hc*1e3!7S+kemWuu`XFD$NOlfFr zspvCvwxe6qG9EWnCm%Onw7?jpp=?z2nK|2OfoJ|xnrpD8lmEA* znb*DA-M`7Ur~kV@mb1lmr1@qJpXHC`Z1K5ElV_u=KbEt_*^nmBMo)jvj%P;Mkmhln z`C0y0&K94$G}*XucD(nW_0V#y_}`Ky?^joUEZ2&&Ax)l*Pxi-hwm3i1oy<=M^8jK>z$$;Xz8{xFL>yZM=MHdH6i#!vdg4DIaZ zRmMG4oxG>-<JL)qx+GxNHOn=={b zM|HC6jhY@Zi@Uh_nQ=B$C(lMjf0)Hx-2BWq8>*9MqoO~|*)9t_QyRJ^d6m!1zAg)l zQ5x!3MW2~{T^1OlG?a~sJ~KnREU-#xC>!;BzAo@gY4X1J^@lmzb%AF}L;0!bGjq1< z0?(9&veDIN=8)F~o+%CGr=riy*{%ybQyR*~t9)kmbzNYL(onxD`poR>y1*Evp=?z2 znK|2afoDoX*{J9hhWb^}XJ%iw1;!{1Wuv0c%-L=WJX0FVMn#{Qv)vYW zrZkj|ias-EyDjicX($^NeP+&fTi}_}P&O+1%$)7Ez%!+xY`ntf{hcuWW%kl~eqTnK zd9Sh0@`u>h$c8lA?^1obKg7Oq{;i$)gQ~g;%rEh zXQQV-^Rb9HnZ@nh{LJWgM;gjcMW30o?H72aG?a~3`ONHVzrYx!p?+2Lnc3HVfiX%$*{J9< zbGH2g&yoS+i`(sN<-P`>N9h;;{wl=hVoO$t!erJ;UR^qJY$ae*;P^PP>cyYIZN{P^$j z2FvVo70t}qwm!2ozu)ivEPqahXU69)O+F^{^=Ia6TiK8%8#hjd_jdAd=4@N%B~6}< zPxfc#Y+Lz}CeKere`bcZ)pu#~zQ3D4GyB@=sWf>{JNh%PFBRoN#~F;a%L)V`=p7;0N{h{kj9nbq)-5v-PZ>i*C(cOB3BU)`TU1oJbL!p_0zJ8P{|Y~d>DV0=`sAEZ>5+!JKnYe`_(wz-$y?M@6kRu%$DMD zufC;t+%;|~9`_AfipRC(mf~^!v88zY0>z4XPlYYT<9oZMc=UElL7vX*Rd3ZGPv^C3 zw`!25^E#GWHOSL>4Y|0+yo%bEf;^p9OWLYIIh|Kd*{VS~omXtwszEtDPAgW%HRktN zw-l7q)AY<@s|MxtG_6&%RfBSRn$|7ZszEtDP4D_|)u5c7r)!wF#(8=}bW1@wJx?ot zZPlQho~KoSwrWsL&(rE7TQw-BXUypZJ-wi(7tHAeJ-uK~$8X>F^ZnS53+D8Ko?bAg z7xeUso?g+@D|&iGPp|0d6+P{BF7%zdVuC6uXiUE1w?T^e4(RJXHq`NyejBbh(n;aF zU&m9rmbxzdimArj|95e0(2D#zNQ${{U-zWfag6Q>Z+PV>h3|eHPwC$DhIa*0`0jV| zlxWWl?+K;w`KaS5QKuW;?@Qsk-^o+rV>hHdQuut-@s!xs4cV3yzWa4NB`$SCawUcD z{=0Ze)aiyKPYU1Lckz@M+YLFL6u!4rJRR@f5}A@FXPuw!53#M`k2J%Dc+Nm)e~5gI zbC)L1Mpu7`dJR{k$+OYbA7Wy|6>0Kpe6l~p%zit^*LA9sXY5t}5ak-5LYll6UHu^j zHe8V=&qh~&h@lNvq{*|<)gNMT!xd@rY<#Xi!xy?fl;-zNid$T(uRqK)=amb${ZXB4 z{Hf_7^SXH@$n9*XPM(d5{xGkbSApElhU(*=Cviav!Ob9HY)nVyl!53ayuKUlV_u%Kg{dqbt$*Ap*ndsy86RRZ(g@@ zJ3p$E=ck@O^ZJWheU~O@o_+mcRynWFxSb!>`5rgUPb(=7GHCtz-!+zx#dV~~d(qV& z%g5quNRwydll`&0F3yiMd49V3V_96B4QcXhboIxwxHucq5t`OalfR=`_SSX}O%It>9v7IWG&KHH^qE*9!8x{Rw7I$1=p3=~`(bMOXTZc0mH>An4(bpelm8XTdpwdu&Ugb0MvC{&F zl!p3M(P!pkr-iwf(oi{enb(~bxTrKVwp8?)dEIG&i%LV;c#Y5J1r8}q-iyBeFdsWF za7bw=KNWpu7I$7?p3+b@D*DVU?!3S}rJ-ze^_f}Rd4YLKL;0!bGqbq!0`ruHvQg1z zW^v~Q<|z$jqpQ!%GtUcLR2s_9|G&?dU{8UwV~o;#O)iaH)+|5#EPpH?i_cw}@8=hv zTk839U0|Nl|8qcch_gyvk>0XjeBs zGwzq_WY-BbJ!FP#lC@WtA7*ja1?DLY-CtDnnOWR*fq6ZGnqQlV{^+{b4?KTi}q= zP){rR%zW&&z#*lfY*h4_S>nZ?}}n5Q(9jaT{1eC)QsA*G>yRrHzp*lmGBN<-P`==1(gA^$S#Ek8fo zl4f3y`m_8Y7B{jX&GvK8&i)XK8|N-fo{g^l5Q`hxkS5Q@C;LOZZsbRrJU?CiAr?2X zAx)l*pY(_L*yxuudB3{)LwsyxLz+ArUHu^zH?kp3o{dlThj`t{k2HCHdipcYnV6n5 z84uszsb5zQnP=`6n5Q(9pNc*+uiGs!PiZI{U43Szw_D(%(olY0lSnR!Opkmhk;`RDzyd@TMv(q!M|ac9Yy@2as3EzXZLd49V3 zWBFK|4QcXhboGZ><$i%@N<-HY6@6x&xp#9fKg{&@ZZ2q?AJxh8Q_&yh zb$d4#G|qN|WC^^!0~X z++l&~NkjSR>NE4YgPWfj{q9IZ`KjnL^SXnZdl_d#b+T)cnjSKXJ1j6yX=vQ2=rgmp z!vgb^hO*JsXJ&DS1?DLY<>ysCGaoxFa7byWUlo03K6Y5(kkU{#D*DVU?y$f-rJ-!p z^ZB^IJf+F|{@MO8uRAVqQE4b+6@6wFcU)ke(oi-k`pm5IxWGK6p=?AxGtW3KaHH30 z`2P5~z#*ieEL8NF@5PS`%tIQ=Mn#|bUi`SgJfxv)RP>qe#g7ZjLmJ9PPoGZ$-HSNDgnlk@Y}-`Dnsu7!0x@9*FBhpsn& z_W12-U2gmD>-c;>KK}df`eUybpZ(SG`TJMTAN!p9`Sa^|-rwr}*k{?#{nzol|JD7m z&#RyNuj6_DtNUZ0Nk8{r$MgQbyFcSC@B9p;u-D9==7%Lj&m(}}15b*dami9v_ZRehqN8MKq+xAd<%Tw`8aWJ^Igo!1%IszEuO-j}dY-Pvw`x#M&(m*qT;qbCUeMFa^yb&r zzd|{^Of!( z@!T=)^U%=9C`~@P41Z{xljd_hq|ta}Lz?l#e|wDT>JMGpjBH4gXX7XR;cI~T?Z@pr z|G7H5fSmZxEX_)9WBou%Wmf8)Qq`(v-6pZl-l^Yvdpf9&=D^ZDs`-v4*^ z$6kLv_gBaB{#N(LUSmG@U&r(QSNDgm|8zX>|GWERx$X1!TgUVM{%L(tpZR^hK}DZCEQMuez5HPQCB@wT`F+o=?@K4g zi2uy*6>j;V8a6?7{2)5CbI-@4Uk}x=-S6ZF(WCi2%dOEtHEcfW_(AMwe$R5N`>J8P z{|Y~d`OI%XZuLbqY+pM0K}>0W19B@Ls$ug{#}6V>^Ba&`-B%6U{W^XSkDA|a-0Hq+ z*zWi7!@sNfd_O0}-21Ql`vo+Eu9AYt)!x0666HfR=7jWejL6mAy>AocLp5wZ>i9wA zYL7Hfin;gW*W(qQ5-}R@B<4>krSN^}el^i2-wRi7EN59#sVY^?) z58_gL_ttyVebunt@8k!OtG!$CAj*eo*nHISgUHq1tz{8)Uo~v^`}pBk8GG)&6m##t z?ss!U11l+r+7-?trXMin;gWyWh!EB3FJj-e`1CjX5Ee93ygdKpH5;-1{*))bW(KlwUb?}V`=8{8-#P3# zA5zTe__{y6wR7@nJ7zgubS_fN{r9`*b$85?tLSW{u=(iZhb4JY_ocAi@8pN&Qc?G% zu-*SGKP<_M@*#!I$Itjd6wdEF9(7JNZ0G9uK}_l7W|&3YR}I_!PJR&EI=MG=qkO1_ z%|{(Sh;5zR46~^Fs$sid#g8+RD=FsAe%)6xA=cMRL9FlW-q3v>9i;FHs^ck0^x;?MP7j<6>+xoskAgF{fkP6V~yRxYQY0pA^3PojfISbw(N}h0jM7PcO)} zq_Dm16h0qyJSB2E7CwId_L-UO62N_G*AlP{W_i! zm%1YBlfrkulcz+ku1Eu=@cF3YDRHSQvOXz%_g~>D5u+Uc`T=!z6h3g7)c zp5BlKN@2U-%MapGH)MTM_;0 z#fB@=EAZH=<5&jy4?a7m4@>3DxaC5?G`ws zG}Nz(J~KnxEpSL_C>s@hW?r{jV4l)YHoE%EOmDZqMWvzqRP>oy+|Iol9X%hEhO$x7 zXXbUg1?DLYWuv0c%Yf+34#J^RfK`hm?l$ zQ_*K;ar*`4DGg<#qR-6Y_6y8Y8p=jjpPAR~7r3Z2l%I+|GmG0VFi&YH8x?(K7Pntu zp3+b@Ugb0MvHb#vl!p3M(P!pk`vndu4P~RN&&=!g3tUth%1=F?4-3pwn!N9Q{b3e& zSYV#gP<|@<%q;G(z&xd)Y;^URdEH@wi%LWJspzw1amS}Me8&u6%Vc7Wy*H0F_I@zd z*!zN5W3T-p&Cy+JNn_Wy`B{JLZ*JTRX};e%`YeC!Z*F|<(&X9rWPj{$Zk!)!^89r5 zhp%mp?s;yUAJxh8Q_&y3radlP_e%4)CyKv26@BJ=nWKB28=t%CN7LFlY8bH=SOw2-=>-#GOrt}uFvbd#o3T1&qhUmn8lqIn5Q)KyHn9;W^tzl<|z$j z<0pM)hIU$DmC{g8EBefQ?6klkrJ-z8^qE=QX@Pl4L)ob4GxNHWdxs^yzfhh0{-UQp z=LIe*O+Ie)^@n-gd4Y>cL;0!bGqcL`0`rt6$_8JDoENV5K3l`T*XM=nB59(0e!rhE zR{pK$^JU?hN1D9vKkEpj z8(tQk&q_ntsOU34H@qx7pOuEPQPF39{&-n<&MOUNqpQ#SjPkPZELa-KPeq@Z4PF-5 zpfr??SNY6*?6Sbnq@jM*^ZB~KA*IRt{@MO8ue&aAQE4b+6@6x2cU|D3(oi-k`phiu zy1+c8p=?z2*|NA(u*TrkF;8i}pNEhCckF8U$sSr>7iUA7@42Rb-XF`*;?E;Z-mk9y zSUwhKLz+ArUH!3qEY5~Bc{aNGV_96B4QcXhe6Bw?$3>(3Nb|V&{49Sgi;K@)nrv*j zIVRl4L(Agg^O7ddMpu6(zfO?&TnfTdEVAM`o67sFuiRJ`8>{xd>$I|d1%Pzp<$oLSn$2} z)Yf_Jrr(Qg4f{NHr{RB#ecny;Dz`rm`@CE5dC*+`%F?IL=*~ab3Ip{p#uujm;w)(&X8w=nwx^UKf5(rTNX&x5tfl^O>)It_#;l(oo+k z`pnn8*M)0iX($^Nedha}>-|cBud$`cuO%w_vvQv+P2Ts<^=F=!v2`6KP5ztG*B^Rb zx4Tm|X|l1UuRqK@Zwp*h8X8+(yv@eAB@Xu>3i;F*xG~Z*wXZd4UTzu}*JnmijF z{TVZR?Yyt&Y)CUdOZxNvSjHHC9%;6}%OlTS{jq#3&W1F3Ha^)O%j@F&NR#KMt3Q^- z#o3T1&qh~&h{cWHTxs%bboGaL=E#OLc{V=TA7XkVKhos+c{hKEvyGlgllQcuKg7^R z-=)d>-qW9P&cxZIc{~%3?!Wr_!@SO~^AY=_I@#FL*F$D{J2yWw&X4Nk`Kjm+^E$uw zPn-?a$+J<>ALeyC_fC484b{oBQPCgfb$+d{I2)>yXX91=Fhkoda7bzB9;Bkr%*Vzm zN_>ARP5xc(>JPKHv3d>XN18l875!meH{KlOY)F%5qnFP7HIKLiqoFCQ6es^km$SlsU!yRWsb@FVy${*%qeogeaU#gS$tD-;5$My?z zFQuXDgo-{hi}QOR#N&qQD*D4LZoj}h zrJ-@7p3i=dqi9T!ChvP+f0)Jj{jcKus805q^0OW?KRhhVy_AN=go-{hAM^Xv#ou?; z$-nOv{b3e&SeSb$4UHQWeP$Nt_oa--4b{oVjjsMMuRAQv1(k-zmWn zdH#_0Euk29t^ z+1T<=d3gHu<^DHjP}yGm?;6YE;yTiN_x-c{u`Dh=cWLr$boIxwxHucq5t`OalfR=`_rQUJ^*9@b`2&?!UqhVm5x4$EYu=Vf)g_4`M!k$H*ujs$ug{#}6V- ze&5Kb`>J8P-^mXmQhr~^C?Bd}^HIkS;#Gd<$Ef?NVY^?&55F_vb8n@XJNtEiJAmkD zF9oqazjtGlAk~;NRLL>oQhsN_sQap6yZ;J5h#2{u5u?7ShV4ryKZq&$ofxBhsD{l) z9Y2U%`F#|l?yH9FejPuEOZnXtqwcGQ?S3aeh+O%d5TkskhRsJEKZr~D{Sc$>tA_1< zCqIZ>`TY)~e5i)aM-@N(o_)`~m16Gf*L^(*qJghb5JB_1b?}V`=8~9C09{Cq_Fwur7 zQTJ8DcE6J!#I}yVq_Exp89#_R9e+t-`_jn|VoJwfQrPZy@`K3L@s|{~`=8{8-^cFx zicN|+9bfk=T%v)M6h!j;K6Oz(RAWv^CC7+M`JL9H?yH9FekVVO7wqdhVA|<{2*fF_mzwKq8hd@o%|rCbV3Rz#hi|D&0oh;B3CD5eNy=Dck-0j z)(L5#6h0qyJSDbuLK-NA?|v0e&q%JMu)X~>KZxX=e@QVXq?aE=uFg1*O^P`kU-!F) zS9nUq=!|pnr0{*|L}cE_ocAks8935lB*~mQp^dt zIyze0G0UZ*bCJS!|FitCb?}V`EHR4uB8BZsCqIY>T^)ss@}U|wAD#Rl`gL`4@}hjGhRsJ6KW<0^rI*8K#mc7P>;H~)^^myL za7CIt8(sY&$~Rn*CeOxC`a>LQd{Sxhes%SS7}Rh@nmij_{UORVT#+Wv#wYtjByBh+ zO`e~w{t!j`?F!$2sZO4sivAE|8)qy{-uJHl5P=)6NRwxyr$6JI>GwjKoM-;5Kg`E= z3ye`3>S;xvnUC!j7^5_ljfy@qi`y;mOlc?^6@6wFw_D(u(oi-k`phhDx4<){p=@;Z znOWR!foDoX`KjnLbG9AMwH$Xcs*|ycn*K10+b!_SSu@_#JwDAx+TZVp9&G2+G>3`* zY@NF_zsKIs^XI`pw$ELfG4{$IKhJZ2rwI>Evh9yFd49V3^WY@g*^nmBMpu6xoMby2 z(&X9b>d%9dY-dB7JR4p8c`%UeY)F%5qpLp;Mzoy`Y4U9Rq(2Y-v)wOg@_u#ohk4y$ zf$2#@T&teX#|54#P2Ts<_J?`qahhMZ_1h#3Wvrsl%;Js<%u^c5Mn#{Q#T}>lb=%{H z>SWinH9ce&cbw+eZD&Ju@@%}yALe7nY0lerzf>phS4DrAj~%D^Y}?sToje;A{b4>f zRz&)K-)cJ>(&X8w=nu2F<20XbI~%H#XQQG&%-N0$JX0FFudL_uX@O@-llT3z{b9~_ zTHu+|P{u0y%$)7Cz%!+xY*?R9!8-`v!&qb4pfvNGiL`MJM3p7*!9KlWMibN_Wb@Bh2| zW1sgv_gBaB{=U0EgV^O~AjSNQ3Ot_MQ_|?49_14*{hRsJO zKZyU#t6gv9Lp5wZUf~CEnR%t@t-h#+?Mod$hziYXNpE#uHEj1g`9V}^UMqSlAF5&V zQO6HrPV;KVTisU;+xxAlA2cZ^Ar}4pR68y~0ysN@I_PoLWoa`%=d-B1U5+dFs9tbN_oeM&xSm z*3OAWZPl>(sN)BbtMT3!jSf=S?$_~yxYXXQwG(~!Rl|0_lOIH`_HMnMC?Bd}^HIkS zB3FB4TT;xuA4H&&r$qAn&VSM9pc->RUg4PEPw?4wDQ3^V?)SgM=_)CR7#)zpN#XNR z$5Y}`e%HWgbWn}C|GgX|l6OEFD8-zP@#|5?Q{qwwWPMWj?sxK($khR9pcFnIbvz|< zbwC;@h3|eHPl-z%ko8I7yZ;JLi5MM_DM{h`(#caIXnr5Q=#Eb{=7iL7%K; z&VJqRZ;18vQV_ZFJLyFUQjIx7l^i3I=l9Bsy003x`*r*vF6DQ7J3prGd2_vz#tE7b)ic`(5|CJ7&pMbhc91 ze01`I$d%vUEy{;#*nGUg4`OU5HzzOZi)z@u)bWFu(#g%Zi@L8Gw)>s@AhvaKbMm5m zsD{l)9Y2U%o!p$fsQap6yWhzVVp}ISH!#YFYS?_#@q^gb$*sm0bze1X_pA7EMsg*^ z+}W@DbrP|@UJ7D;XZIfP^XMRjPtYqoC8l(CtMNsBQH{AXl^i2tbjBHGQp~*{<9a7g ziCmqL21?=cQO8pvS7)SwQuyw7@|4Kc8EK#tJ|A^FC31B}8YqSDejQJVOP!JRN#VQS z$x|X%XQY8r_`0jV|l*rWuX`mE7A9Xw>E_FfHCx!2RCr^o7U62M!;q&ndPl+jAkkd)w z`%=eKB1RXaa8mg0SMl_UtWOHt+fVa@$ki2TpcFnqbvz|5bw$=Eh3|eRPl;Szkp@cP z^HIlBB3DBu6u$ef@RW$r6)Bt)zAv3TC1P|%3MYlnM;%XzOI?xm zN#VQS$x|X%SEPYnad}#!TMC~b>-wK^?B;0T^XHJlcCMEnmPYgJ`t0g*&)t>g-@pEKXFPx1pNZV= zPsQd=kN^I3e~1PSf27It^OOD%jT)a+n!I0K{UKI0T#+WvMpu7`mkn2>$+OYbA7W+0 z6>0Kpe6l}8+lF(}S!L3G?a~sJ~Knx zEpSL_C>uR}-Y;-bY4U9J^@my9et~&PL;0!bGqbq;0`ruHvQg1zW^wxk<|z$jqpQ!% z>-Gy=R2s_9t9)iYwqM|o(onxD`pkT6zrZ1-p=?z2nOWR^fq647nO$c zQ_*MUb^8S_Dh*|$p3jE`<|$3y_rCrxi#seZPiZJW6@6wFcUWMa(oi;Df~cfSAUp!9^G8fI6tbB=jT=aFhe`KxtDRjR44COMSqx~9o^i^I2)>yXQQ4! zrv>IIO@4jY*B|DYrv;`b4dth+&&>2rZhmI;yCV(dr=riy>rQSiXq*kz$*xIiddR%) z znZ=zKn5Q(9jjld3uRAYrQE4bY^?bf8aMAvnF=JxAQ{`a>#tHVCu7JR-f%p>bnqD9=Mfpa%1&NMu3Jl4zIuJhSr!pgWIP4*kNHm-73RVTle zsOb-n^J~Aks*`^QyZXb|v}@O6s*~sERsQhx*lyt-L>l@nsOU4_SFYU?sZRb~uILZn ze+>#t_ovd(xKYtV=16M{M0N6UqpLs6WOhp&Qg!nD)bnSJd9H9#X|in8^qINe8V^^U zJR9%k53|a(XB?`N_x&gRVLrBBc*ZJCet*%|ALe6g&ns0Y9}_D2!z^yUz&xd)v8AHV z%;MJOC#X(7ZdCM#S=@esc}hd$MpvJi*R9Q2Qk{Hkspt>0xcvh2l!nHZ*Z90PCy*JV z>g4_UU;NoUy$>?(a&0gES&ijm@xLX__Za?J{#b?&n!I0K{jq#3 z&W1F3HhTJVTwrL@Ja}gG-RbKO^UR}L^C9*}b+WOguZPU^j&41WI6tbB=cl4S%&(F_zO614yQyFzmHRj&Ek7Go2{2r1~ zZ&kzgwv!)3o&0{3Q9e||=A(`u#GL%Dlu`Fp!*;)pA4Ht|o{~}bRl|0_lOIH^{N9sM zK2*czqmCcMtNhN9QTJ8DcE67weqY1q?n^QE{_B1(PyF=HDE7fB@0LqRQO6HUjH1p- zF@G=pewN)Gvz#tETPbWlI{9JARn&bcZ1+3)VYyV)eJO1BKg$nGuA+QMVe`?+4@<71 z?n`02|5<)mauwx63Y(8QepoIQ^;Qbo+xPIp@5cAsIVtA8eLd}8*xfNAR|hvsE%HM( z<_uMGj9A~n%`l6)uNt=db^IW5b#QC!MBP^n+x<>{5ZgMqb#|hBsD{l)9Y2U|9o#B8 zQTJ8DcE6J!#I_D@1@R~!s$ug{#}8s#2ek-G7B2#FP$h?d_;9s$u)m$q(XE z2eRg`KaQD-xKe-w^GcV{kq@Z*g1K%9V1TX_q>bFRyF2?^m2^ImERXI%7<#$ zeAMxS$d%vuFY3N(*zVWygSeF6+b`J8P-^UNXTikQ^rI>sF zb${MXG_aC_NS@ybFUp5%%n7OF7;!1T*Im?o)v(>~EMS zQD0QU_N9&=M2!5dbW!(J!*;)uA4INBI44hvIUVDgzmBIwu1+{7PYU1tI-U}jI^oPe zDSY=kc}nE!gfsu7@cF3X=^4qD6t=gY<_D3yGrk8bg-_5cJSC=d#y51O@O`P{DG{SH zzM(6H?|vswiCmrW4P7aGKI(W%XGa62 z=;W9sS5a@Jn7{pJM@MTrX1P>!E>hU;zlR?e$LXFsC&k>iulsM9os(DFF-wf1bCF{1 z|HVyuhb320KBTbu=;VjxQc?G%u-*SGKP>qE0QZI=FWcI z$4X*-y%fayu1LS6@CmBpDY31qoB8+r+aQJSejQJVTwUGFzo`4FG55chW5l+uZsuQ< z57n^wsN)BbtE-#&7j<7XZ1-Q`2Qj6qo0AvyMKx?+I{86N>59}zia8zQp0JLmM6Rw# z1EuiYuj46kx+}6iDSY?)czQ#&C57#NFF%M&-H`Q3;qy_)Q{qxLWPMWj?sxK(NZt); zpcFnIuke(J(G4k_6uvKYJSAduLkcH_?|vswiCo=~21?=cQO8r_Qa2=5QuyxI@szmK z4OyQQzWbd#C31B`8YqR&M-@+Zch*NU*`)dRuYcW{*YII?zq_@){`$ZF|E?YqxBBe~ z`=dH}eqQAdk*3ivY4Tol^@k|a$c8j|Ha^)OqG2OH(&YK+>JPE9kqv3`Y;^U9IN8XC zG>cmz;~_J&{Q_r`hJKqW`pm3y z@8)O5-wV~r$Cg+5!+dP-=1j)@Qk}eC75!m8ws&(T<7}u-o{ftBFpJx}Ig@cVR430y zMSqyZ?cJQoI2)>yXQQG&%;NTL&Sabo)ycC_&!58r&y*&=XZ&n`m{lGYn5Q(9v5G!3 zt2`|5I%y~yukxAM*I|J%N<;ms=rgmg!vbTJhO$x7XXb2&1)eDlWuv0c%-IeLJX0FV zMn#{QvmF+ArZkj|ias-EJ1p=_X($^NeP+&fSm2q`P&VGn=i>salqTs@hX3ln8;F;1;HY)neob9;4Go_(yRP>oS+i`(sN<-PG=reP+ z;{wl=hO$x7XXb3j1)eF*?`({9&!RmSjuZFW);!q7mgY3^gl)~^o@iV1xHjI_Jg$+p zHILuQZOvoM+}1q4JKLH^R<|_|Hn^=}pU(?EpQroxt$*u0-N$Wf*yr~6y_txIl@c2CMO1xc%$BlWH)a^Pv zZp`~BZr9;)W8Rx>yAF-dW3__E8m)1ip&_4#hJFW!hI}3x8aIZ9d>$GaH-?6M9vT`q zhK79}-hQt)82da{qNF-wH9f8~&!^q`x8`}3+ZyWE_&n4vX{hh7^N_w5qZiVQ_c*pQ z-_;))4@Wkn$+OYbANm~}*^nmB#!vb~*CeA~(&YW>>d(qGq%?UpdipcZ|Jl0!k%ss) z-+$HgknZt!_d7jlvT>uYKg4!MHl)e3@yY%$N1EqZZT~i@PM)!f{xCnB=UHuMLv`|O zRP={g+&s@}I~%H#XX91=Fdv)eK5h3)b@F~y^oRM_Jojlk8>*9MqoO~|;@0MUsZO4a zivBQ*J1#somxj1jJ)hU+a5Aq`oje;g{b5#lTHu+|P&T^y%)IWjz&xd){JhF%W?!fK zQ*oM$B@OkfqKC}BP7CuGrJ-z8^qJY$X<^Q!G?a~sJ~L-KEzFsehO$x7XXb3Dg*lVb zP&O+1%$)7CFh5fo%0@+>nX{c1c&0Rzjh;TQy-&@|Q+4wEtog(2Ywg{3)ybY)_4Sb1 z*V?)Vs*~rZqCd>p&I>$K8XD&-`pledZJiU<$;XX~{xD}dFYruhXxymiGjq1Jb&XUf zA2%xc!<_BBz%!+xaigNo%-Pn~F;ks<+<28g%)VCEl#_=w%#4QcXh{G>mYeZ~EfChu2Qe=Pfovms5MjjsM!&K74wnmijl{qg&8 zMA?w$!7Am?gT#H^Ih^0CCH9ATo$64=DtgGQ((mIF=SOw2-=>-#GK=&3H^tddoje<_ z@`w4D-%Bg*m+IvGs^|~%F~5geoDJ2=3{>Eyf_=GlV_u%Kg{C%o{4cbR430y zMSqyZ`MomZY^YA2jf(y-i}QP=#@SGvJR3dz@q6P&*^nmZQGNYk&URave<%&*XT@jc zetv)I_`9q+**M?VLuOw$_YQcRAJxh8Q_&yhY<|!BI2)>yXQQG&%-L@49q>3Cs*`7< zqCd>pZf;G>I2)>yXQQG&%-L@49q>3Cs*`7pZf;G>I2)>yXQQG&%-L>kP0KhN zs*`8q75?mh{dND}ybr>2FQoZge~4?1Y)G^HJ^gflh*b`Mq{;Ks)gR()BOB7>+34yI zakh~SY4U7z^@ljy$c8j|HoE#loNZ)7nmij7{UL@n`Yui0_jmJ$*w^T(G zQyR)fMW30)?G|{ZG?a~3`OJK5x4;;sp?+2LnfcgmfiX%$*{J9CYh9^Y2BJ4QU?N67pwW({g{O zQIrnlqT={XZyn}?zq4_rJ;;f^qD!^ae-$_L)ob4 zGjqt}0?(9&vQg1z=4{6Wo+%AwqoU8u*^Uc5QyR*~t9)kmbzESK(onxD`poR>xWE{t zp=?z2nHkz~fmKRF*{J9zy$ruC(CJYRpSx<7Qy zs^fY8tNX*(rTO{m@88=Wy0+BuynogGp=(tg&-?%G{?PTNj_3XTr~RR4*gBr~=iU9G z=g{wU{QR_*y#0JSKChoU{+s-<&zhh8)A9NHUC$r;y!iR^>v-PZ>i+oM5T6qug&i|{ z`C<7^)O{)D{*SlD^AVw!!t$>uA5z$Sbn?T}p{V;(*zW&~AC}rgeUZZUrIR0)=|tU^ z!gl|&{IEAzH!{(!oA4Kx}et1#$Rl|0_jvvIO{H}pf z_f^Aozmp$CuKdn{Q9e||=A(`uM6UeafKm5V!*;)uA4IPF-hWX(RKw=uXZ#@Qb`2&?sxKo$d%u1FUp5%*nHISgUFTNPcQ1eYS`}A@q@UO-!U)hzG~R+zl$G4 zo&4^4QEyel_V!);AY$Zq$BTNa8n(A}{2=P&_rHs}uNt=do%|qj<@dmg@}U|wA65MD z`?x*#R*Jc^U-x%ghz9mj5Xtkq*hL9ajX6V=93yh&_o<7zuNt=db^IVM<#(csy5G0P zS&eu$}AVhow$Y_ocAi|13W&xr*{3h0RANKPp34%%<1^LuXSQ+U~R`Nr;E--in;%1w>L*^$1InM z&P58_{de)hGPbC5QrOOQ@`I?;*{#MGx=TC8a5ww{2;b)5qVw=_I%*mWhNI%BUR`pl!F^c@@;%Er*p zXC4a5#?a7MH#C%usu~)f$9YLJM)R>R=JQqgr~5-=-S9`6JU?Cip=*he4QcXh{G>lC zzunU0{p#rtUuTXhExxXk=3oDJC9!oaQPUs3R_A+=kssB`#+I7?@I9K{ts=h0mWIZS ziaztb`3iH8hO$x7XJ#^Xr;Dv|Lv`}sl&=0Tud_R0Y~@FF^88fvhk2&mCu1ucs*`8q zRsJv^v-?(T^-Fc~epU2``Iy}qV=Eh~lV_u%Kg{Cn&Kg_UP@Oy*_586rM8tiUCcm%j z>ko5CyMx45epDwLH)?vwoXzgYv6T(g$+J<>ALeX!H;%1rs7{`ZivBQXvwL-HWkYrH zY`n@J=2~`ljjevEPTsGs{xJKpJ9up6M|JZ2RP={Ao819qD;uhlXQQG&%-QVzAY0i` zoje;A{b9~#_XgR@hU(ko5Cy9dTrepDwLH(uup*ndsD*D6h>$LE$tJmC~Rw5a1!`gpKnt8RBcl5_{wzyx?e2)q8 zXU?;Iuj|UiGYclXCWM}F?Fj_3WY?vH&|{M>&X&-?%G{@CZe z&;8Z$yua`6k6-omxx-S-yzlG25)U!GUJ52SQp^b%oID>BDk+HH_|=}H@k2FiK3?Gm zaTmYBcGMTuuzl&|2XP(0x_Xok)v)=f;|Eb8zixiiebuntuj2k-S6ZF zF(S{x03WNMXC*$qyn{ejk%)bWjbOk1Brn{b!zgE5+Q|ulp_y zL<3)=Ag1JZ1&TVS8guV@IYvxr>?e}{s!K7a3&f^ zG{g4e9exl~@~8MkxoC#XrH&s&jQlx$QTm!;)9>U5kt=^zU(^rHu>Gjwhd)d1HCrjh zWPcv}Z_=8)N($n1{;asDADS^Xq?cnvuKbyMQ9m@p_M?s;#HIYHdQtkCVbkyA2azj( zvR>4W|8Bh*yK9-F%q;meJO1Eo%|q@cYfTXJojdZ`yqwxM<+js^__o7 zVbkyA2eGa5FDY#L`|^X>*4gaW7r%RGhHX$CKZtFe&F_HY^fkk#U&W6Lk}E03WPcv_ zNyPfzqaen1F=s$TuSzL=a-BRS>U1%C%f@s!Bb1zDdIKK)Lf65F~U4V1$7qmHM1f_+0vUdPV9ag-ySgA4IOMNCTzt{ix$9ak?wAJ}G?qojfISbw#!% zh3`ilPl?lAk@ZR8)9>Udk*h1REh&6I>Uc`z>WVZ_3ZMQvJSAduMG7Z{&!vv1M2xOT z;iT~Cck-0T)fH)=6uuu-JiQ_7lfq`ZH$RA6-H--K;Tu%PQzBP4q=8cS^y_#^T^4gvWvHWE>c)775O2>`0Bqq_SxMrORl14 zD~0XHXZ)~CDau6(n@cA@EHR4Gm%^ss$q&n=qV%P(>F>)AORl1RNMZZY$q&n=qV%P( z>F>)AORl1RNMZZY$q!4eqV%P(>G$#D@L+wG_PypW%}7K4d4Gt$t$9gvczAGle2)?5 zwP$~bMy>skCht#Ie~5^!-H;~lMpu7`m#y89Chta9e~6~7-H;~l#-9Bl+P3ybn!G<< z{UH{&c0-!H8(sY&4!3qgn!FpI^oPjVnwK0ur=riy>kbplQyS_iKh=;G)vx z*NwjZFsnRHFi&ZyKNWpu7I&Orp3+b^y86t#?l{3krJ?@3%V%b2#|c&`4dqqQXXaza z2@WX@b)%xs%*T!s98wzUMn#{Q#T_S@r!>@!u0AubJ5F#>X{bLHeP$MSoM4{PP&exN ze41dM(&V}K^@my9X@Yr5L;ZP|&&@` zias-oJ54Z8X{Z|&eP$MSnqZ#NJiBpx*;#-6MTGUahQ_kE_}?te?{!x4XWScb?Yw1i zu|Lw}{psqDWpQygq{+MSIe!+%A)~yc$?pOB`eXT6+zn~6*Ye^xZ66OUi;JI^GEoj^g&B^XbYI?}L?(Eii#@*1Iyc_TGhZ)-0t-Xx% z(wsc6ivBPkJ5O*(Y3LrHtIy2h&J)a28tP9)pP9v-Czz)+)QyThGmAS@!;ylSY=tA?%{tA_f# zYUsMLYN*evhJ7B-l-%-pWt5cHcy`|Q9QJuUOKW=$`#heTvpt7>9?$I9p2I$`X^@BG zKJ8n7YuvAUTf;t&`v7mxVV}o+mbT`Md;4r__}@J4qeCB}UZwx7G^wI4inWZcfyhR$i{#5jtKff;%oJ|_)Mn#{Qoh}o6RT}C> zMW30)EfZW_8tO(@pP6Tldm3!t(`rtBPx~%^n2(Kn8f@pKIeA_c{b4>f?pLtg4b92B zQPCe}apRr_+uhKdyc<3J8Gp0C)eUL#d&s{2FwY$KG}!Ks=498FnjSKX8}}>N?uO>% z-Kgjfv$*m1_}kskoV*)d{b61=?t8G^AI-`8^Dcjwp^f_A_ zUp=1ZTiu^=7lOC}QjF(N|2%%d{A6Z(aO_FYww|pNV?$QHo?kO6DToh^yN_)3Lo;kY z>i9u)=rH`QXe)iqu<3X5gXq$@r_feEG{g4e9exn?ISjw+*~&#TY%X>DAm%gf(6yDm zX4v#Q`9VzTFziOO)ep_E{ix#y5vg(Cy{+^$!=_)y58_paVfUh~^fkk#-^Y(}ugo}o zDaP!79(%434XmUfay9Ogy44TO7#q^dF(Oyv9=Tin&4=<8iZPY-x?aaq zB1Yqm(_61f%^36V!6?7_(nr z`<*-`a&;U|JK4HAXvWx(N{$h^T7O5IuVs;9%znK(RB>#5HRst%VYB@nKZvo7X9LAo zZ7F=Vbvz|vG@kmjmA+<-`B!p`xYP;Bl@w$4KM%h;c}gU2Jj-qC>Yy28Ln=8&T##8;a($@@|ejPuE(~al$ZKbanHvLY15V;!9?%V2zX4rnz@qE^arzD1FVa>38yj$khdDpcG>}*3X1>JSB2u1Mje@acE*l*rW;X`mFoA9Xw>a&<)-D1}eIj;F+> zuE_eN@acE*l*rW;X`mFoA9Xw>E_Fq6C52DFlcz+ku1Eu=@cnp)r^J-5$myi;xm5A= zh7?W;n{6*Yh)dm&^-1CT(aBRHS2v`AQuuz<@szmK4OyQQKK)Lf61ln|4V1$7qmHLU zu5L&JrSR$3@szmK4OyQQKK*xiO2p`f6iy1COD9i>7~PP4g-ySgA4IP1NCTzt{ix$9aj849J}G?qojfISbw?UlS8;sVE8IVq?h4DLqGv0` z`0Bqq_W7qAv&1O+D^l28_T`6VN>M+gu>I)dhb320`cl~RJNaR`RFu9HHvN71VaZk0 z4=HRv`uK5pus*xH+-v^Qj5{0c%OA_F;^!{S;Xy>#b2#?pkEL4ibC)LX#wY!;%l|hxy_9Z{Wais z-RSC%WoU6Xq{+LnXMZebi~A!@-k+}iSk4xALz=uBUH!3~E$)Uic{jTH!<=oIU~$qA z*Lsi7=LyCrO`b(xf0!Sh-I~ehy+9i3Peq@Z#hu-n$+#PulierO^pIKH*{z3+yP-LG zH!AwWEbi>qXU5&ooV*)d{b62rcIz|a{%B6#pNjr4i#xmZnQ=EXC-26){9!(Jc55c% zyfi1ztD-;5$IfoeWZVtS$-7a}A7)?Y3C1W5afy09UnY2_G9sljOPAm<&XQn^|Z*5|7>Z-&-h!K@w4ZaX8e4yr5W!tw>0DZ#+GJ$ z--$IhbDiJPj6K}ajJa=V*yo$!QCoA^=bQN~yfue?zL|UDtvT%TeZuE;`g0%Y_;20K zYiCQtKHn#Nz8fC3^|!dsck|hEYYzAMZtg{+IqRu-<6hib8uEFaLw#N~&B{~ zKCc?`dDT##R}J~RYN*fa>3Zz*y8a{Y^E!upUUyOAIqb7NPdx61Jy&{5!#>+{X1C_B z&ubd=-0fM1@!zs%-fd~vXM4WY)*SA$JvV1-4*P7++Sr=IKHL50<2iN@_AL$f+3vTz zHHZ6b_j--ytgk?Ny{{VbXML4Y4_6Jn-d7Fzvudb^d)H7mR)3`VYyDyTy4bfrbbVg? zBTe3)uKv({=GqNu@@{<6AG$|c^O7ddtE)eJ@5lGgYkxE+?@vX4X72f=$#d`N4}TV3 zi41=pl;-#MJMm|bn*Q)-eC8x;e>5k%w$${8*^WJ{ZtHcSIe9m_`or9h+39+1(VV$p!+dP!`wMC49W1dz z-Kgjfb2fWc-Bvd=C+|i@f0)JDv)Hz}p*eXs>iJ{OVvBQ^Ccn?@>ko6tWr9^oL;d+S zpP8X8k8eKnwU>v-Dl2KS_lwW^!(3~bV1v@oYq_G&%(a$@HIvd%H@f=FoNbv{Gbs)A zr=riy*_MellhRN(D*DWvZJAh~DGha_qR-6PmWj2O(oi=l`plfoo>jNSwKOOHeEJ@L z>{)Da7SiOe)4u*N`?6=%ZT07$n{#x#X8b&usQ))hGwv-i>yPD!v4_(9zJ~A1AIsU| z=Ppg&jjsM!&K7q=n!Fo(_Q!IzxIfb5{psqD%I7<+t_v zs^}rJN_$q_)^pdKygwEFVHRi4s@v*@=H%U|=nu0vdk)=JH#8^jMpu8B#o4p-w)&$v zd4JyJ5A!j5R^3)!nv>^M(I4hx_N==^=AAdsf|6H#8^j#wYz@KIYE^ zjIW29lV|#E{xJKxy5E4uxob|Idsly$eO=vez~laCPTrr2{xD~|y5E4u-O!x88x{Rw z&USUb0gt<(Ie9lK`oo;<>V5+rcSCdXZdCM#Ios8p-5Ga7bMkJ~^T(gt9_21g&NDyj z53|9W+h;P)RCBV|a!n7JecjwXlW{jRC+|i@f0&`&+@6+kH#8^jMpu8B#oZ>Dr!;gg zQPF4SY_|!XDGha_qR-6PZWBCH8tO(xpP94WCU~Ya)QyThGiSR^@Jwl_8}IU&+1G7? zF-k*u)${p2@%wIR^4$CS!yIzm#d179CE^m&P=6|V$ee9mCCS~8CSz7LJ!H;ypWvC& z&~>A$&&=8G6FgHI>Q6%Hz1RHn z+Ly+%ulTu3^ZT>IzWlMAEq?COKvGW+t!a<=%nOS665SYJDP z_Q$fyxIfb5{psqDWpQygq{+MSNq;Q+it~~t&#S9HmVL$DkS6a&SAQ(~in}3A-i@yQ zSe_YoLz=uBUHu_exqh~iChta9e~87c-H;~lMo)hZ6FgIz=l7M-dv0HUn8mHH8REUt zP=DU#A+xW8TQeE=S#z@Yf|?#O`#QKalW{jRC+|jAf0)G`+?vU_Kbn*Gr=ma1;tp=j zWZVtS$-7a}A7*juDVKZ?DNWvuivBQ*JGk|k@pVIU@@`c0hgsZVf@exYpFJ!3%q;FO z!84_yZoJ3ml`hl!yEJ(gef?qfb(~;~(olaY`pg{iIKeZep>9<4nK|2Wf@exY-RSBw zbGG9I&yqI*J*+=N<-bK=reP+ z(*)0yhPqMFXXb3D37#npb)%lo%LLDqCeOXEKg`*d37#np^{1=P%;J^_<|z&JXU1pd zTFV4Kl!mgfJ})nO@2{%{zfEJgR{U?4=J)UHF0>b1|7v&H^MllP~qKbEt_-H;~l zMpu6J{#ecycSD-I8(saeoGtE#GPcTnu z=-N`vXS-9j7k9&Rf^M^i%=1&2fzm6Zo zqx=brQTm!;(|?B_#EJarhEXn>VRPx@hd(dyHGL_@?0+76kPwBdq#$zT&r6K@p&4UC zdO1eq%Ac7S^+PjkKkE2FGjx2azj(4q=qOX4v%m z_~B36dre=8G5ep#t`S57D=CQN`O^lYerU$nkV=jbm-6QcM(JyYO}~>LM6UdKfl)s+ z!}jC-ew>H>mjC)&K9~PZVaZiALkgSiXZ*0lD9S|&o6ElZuuLiHhZMFSo&2!mDoS4p zn|>!hESHMXm%^sMFF!1~iuxgi?MEL!{7H1L=}R$Y|MS@4)3Uzqj#-iyJzFWphWN7! zYddDiRrFk>u<3us4@-=qT%@qM?8^_LPK(>AI%<$+*ap?{gV>foe=ka3Gi>^G{2+3* z{F1_EyDvY8Z7si~u>I)d2eGZ?mlQVrPJR%%T7F4k)8CUH{+zql`$8$kcKkffbRin} z9tANrf1+EIoMw#KRdS4&()saw^l|UOD19kx`knkBw&l;Pi~6A%wjXu;ATH%krHj(n z44Zx(KZr~DGv%W6HN&Rg$q!;%XQY8rjO|$O`RjN}34FB$khc`{z>8cQO8pvSC#Ct^z^b9ft{U=p)lh3! z4P9SX4P6aZ4Rv=t!IOO+&-vWSVmv={Tf;t&C+%&|VV}n{xwhx9&*S+%+jH3G@$`(X zIpY}%+ZyikxPSfj9PabD)AjZo?(?`e@Ae$-^SF!W)|~6a>xYkT5BdFl{WojQdd=JFSYLnm+H#wCKb7WRkM?B!spvDmck_M!dTr61yc-q$;d_bO z#Qn20blrHD&wT&PpTF1FvgYKk<*xqlJ^yXuK3p1ly;t;^KT|W8TdyselV4jZ`oo{8 znaHl)`0wXjUiOcEog>ZoP0*+Pu?#KFLYm*#ggyD=zhQ}AnC@kxJ(p{;pIljqgdAL3(cH>AnCv0s1u9s&{f zlO|iAx&HE>*>X({^SbqQMchvs>Q6-vnP>WaMdE9V=49_pH9cfrcbH(F($ICItIy2z z{9Z%xwMBFCYsYL>%F4S%+UOPU-4^MbMn`6MSqx~t-E>g=L>1_ZdCM# zdENReXYPhHc{jTH!%Xim!9}H^dy;xSuSA@#8`9*t_w|QaoZss;x?h!s`cu(oW|hZ@ zb)M2tH{Rtl^D)2Qa{OA>oa`R5uZPUXjuY!MrJ>h*MW30)`90X4#=SunGUl*3w#r{Z>_ve%TSUwi#B~6}J zSAQ%Yi@PCB-i@CAERI7)-H_(_xpH6rSQZyQcWJWg#^RXpzC5(NE`ILPAnC(bXU3e#-Pp&e1!4$ zgK>YP$@^2$ALez7TYDLILv!+ORP={=-Qs?49(O}?@@~}g=RCnYrOEFP_w5fe&+`QL zlZHB0(P!p$XSWtKdf$3<*=5=Sc&NJ?Y=4AII@AHuP*m;6ON<**Zu0AtEJ5R7m zX{bNde75^tyc+T^x`$PA&dOXkn+x_8t)BO4Azpw2N-Jk36Jl}8khwfMPc%E-{ zf9QTwkLUUSU4Q7iZatp+|Ly+JchP!0&$qfi^nJ4)&-4Fwf9N}7J)Y-V-5-DY;wu4@ zV*EYs&*R%i9wQ$DczPrLP$_{df35 z)W)9y8ReoGHkUen5VP^8MMmjshE2bdAH!hh+O$o7NdUjopB5HGq=ySw!)ID=($K? zU;CZ>uv{uiUkaQ4zWlJ{D(Z(6wjZ7Ruv{uiUkaOkCqFEgiqe2dM;9o`TLU`YddDSRP-a(B>g0Ckj?&i*oBlieAf|M3J7Y(= zXok(DlOIH#PHuPXs2`eP`%%RYf1=-Owo;7A{ycX1B-YnUL9EZ8YZo<0GsX^8a*Wv4 z;&!l(($@@|ejPuETrF;o>L`89u<3X5gUFRXcQ5LPX4rnz@q@UOKUptIUo&j_@9=|& zkw0ZG%0)A5E}i@!rsPl2i~6A%wjXu;Aado;$&1q044Zx@KZsoUv+|;TXol@a6+ir0 zZm-!&F(&)-IJ1RlU?l}{I)6@G)DO)V8`8@$B3J&bx~LzTVf#_X4W607e$?@U$kiFwG$%3NZ!SrMe+K%K?>iGcX&#~=z?qV zr0}_P@|2j;1y}7!;rmg?QzBQF#|rlG1fl4vEyb9BCC7+MT^{s;(wD-f-^mXmR~KYk zQjG2RdH7YwQzBOvq=8cS^y_#^TU5v8|h1wHNh6Gi*QV_(5#z=GNpz>1&2fzltAsBv(?5$^JZE3&i?*DTrL%kp@cP z8&tv&3B>W-{W3ZMSBcuLgijwDYCpY6AJO2p`n6iy1CZ5>aEOWl$6 zN#WD)JJLWYd_U@VN?huWtWOG`ekV_fT-}idO5yua#nZ!sZ4up)X58E6m4$cq zhq%@H+@(1@JXp^+i@Wh{{t%5?GnFRKw4y)6q1N1`$#d`O4{@xu8`9+6=;{w~u(cb~ zj3i(bjHAlXs)5Kg8J9Zb*}NqpLr}*Vb-GlXv5D{;X*bLzCuT z4~n$Sk^1_>d~EfF`y)->pNjr4XFE)=N@?iYQqgB-afb<>DGha_qR-6Y)^}QdPmv~n zPwDCp^SZ+X^OT0JEfsxc7I&E7nbJ@<{wbf=y`AiOo}d5wWH$bLwlpJ)lg7HZzLR{L zKO-O8%1fHR?g94Z&&bENp1U-8H+uSWG(0ozhBUw5-}mOv$l11@yENH#<7jwqCl5!? zw)MQE$-B|jpOLd|bwirG8(sYwIonn@q{+LnXMaY{w$&eL^8UQbALd9$!wnl+PK-O!x88}oeo`6ltg%@A8@X*vYJ!+{#OHvU`A<9x@+0nKhGJ-O!x8 z8x{Rw_H{DrA-B4rIe9m_`ok>lG{HQjq5Fi2J~L-KP4G-`neuVsQUN<-bK=reQ3WrAl)L*1z8 zGjq0Of@exY-Kgj@bGBuIXG%le=;||bwq=56N<;mr=reP+b+7p6-XrmMCDKqgDtgGA zZJFSi(oi?vfGrO9*e>ko6b^90Y7hWb;{XXb3@37#npb)%xs z%-PNpJX0F#Mn#{Qvz;e+rZm)zu0Au1J5MlAX{bNn<})+2^8~AuhI0R;&&pRWE`&K7q=n!Fob{jr=a?uImZH+uSWbv!fbhBQy+urGfsXN#Y^ zG}(3I>Ui&;_0Y1f_-{#*=hf98=400hh9(WY7gY3_S>@HOnT)S3nv-8!D*D4L?&{V< z#@*1Iyc-q$VHS6FYbN7vXinaZuKqBKySnw6aep)??@vX4n8jV)`pmc+nv-{y zu5Nv1+zrjiyYU`>)}1@XeLSKpq{%;5_VtJP;cbGUNkjdq=rgmpn_Dv(Ut2UMyUy42 zkU86Jf@exY*NuukGiSR^@Jwl_8x?(K&UTyNnbJ@%X7+WTV2sjGH!Awf zeC$5KA*G>iboH4z+kJv(N<;mr=reP+`vlLFhPqMB=i`HB()vtk^7X5o{UOe_K6h!h z*VlFShdA5%+@;C8@kxJ(eXV&(ljqgdA7Wo?H>AnC(bXT~Y-=~9$-B|jAL49lH>AnC zv1fmX#jX93Cht#Ie~7cK-H;~lMpu7`v#s6u?={Dlz4u?|NHgxe|9$=(9?6fqF3L-q zC&&Kh{jvNo{`W}p`#Qfbe=Hx1pSv`9H@f;`SzO!=Y4UD#^~bWfxEs>s-RSC%WpQyg zq{+L{)gQ~^;%-QjcVo}~SQZ!eN1D7ppY+G_u{bYj^1QnGWBFm+4QcXj^z>(?p2QfX z$r)o`f0$Js-I~eh+9D10r=riy;*M_3WZVtS$=-KrddMv9=+( zGvjV(PTq~K{xGjQx;30}e>5lW&x}9J$Bu5zWSoWO%X0COb;D^#sH!Awfob5EhGo_(!boH4z z+i8MlN<;mr=reP+(*)0yhPqMFXXb3D37#npb)%lo%LLDqCeOXEKg`*d37#np_2*qa zGy7U57^5_lS4E$heJvA=Q5xz-MW30oEfYLb8tO(xpP92Q6FgHI>PA-mQyS_;3-Nd)U|cdOY|4+x@Zkp|APs@jTz^{@8oX*ZlQ(p8vP| zWA7JV^VQ>dzTfVTy>EWaSC8lUR`m$glb8@jTye_s4!0{F<*G z&-1PBkNs}>HGe&x=l^&8@uw}mCLqPg^?n}T3=?y!q+mWH#hCxPyIB5;?4=;Sb8z2= zN7oO{unnr?2hp8_`@TC$Uo&j_b^IXqb8z2iN9k*ZO}~>L#EuT`8|$banqm7<#}6V$ z2lpGBD1FVa>38yj$kW07&L--IX4rnb!w(`x2lpG7C>PDJxzzE4c+tWAVkSyoGi>^O z{P5@gy{0e4nElU#eh>|;q#(BC&pnL#p&4UCDmg}6%Aed9rLP$_{Z4)mx$-9eUs2`eP`%%Xa;!^(PzbJjpu<5_U4W5~G4SA1aM2!5&c~LH!VRPx^2Qejo zdS28I&9MEb;|Gx|e?DH6zGm3;>-a%j%AbH2rQdhP^0H^O_oKVQlB?+1N?~97o&2y| zDoS4poBqE1u;eQ0hZMFSo&2!mDoX#;it}T?h{MZ!_IL`}mg31BwiM4#d|Qg=J^z;C zd0)7tc-~8GDW2~yTZ-p3XiM>I;g;f=T&%bZpsg9?>1Ehu zWNQX_dKq>+*qT9}UeVL*uyb7eSFY&kb=YrfYX{hRYNQrMnG3j5lR6t<_4!g?AhY)>PF^)yo0o<<7mX{4|{eO27i)4S_wG=n_7 zyPiff$kV&)X*7d8y}O=9Gsx3B_H^Cv^Z8vs+~rk6U0pTg?5d%@t{QT8)lg?w4LQ7O zsJE+zTwXQQ-F0V8_IccYb1RE+*UDJq-y>g}v)--z-U)PT2BmqyEd6_A^zWdoHDkPw z|9NzpnlD9X$LN~o?E#%`pIz`BPl~Y}>lODMp3*&p{~Q;+ZZ%^}rjlcH zcX+}3M=8ea*H>j9Pd$HmeeFwO)9>X6eHQcdE$WA6j1B4K7=04=>^16#X4rnz@q>t& z=ju`Vnqkwg;|KAvE7DRa#_WF{pXNGwN;J@aV-{TZ}F4}+6`CjN#V2Y z8?r4ad_U@VN+j=wE6k+u>DTd;xYP~Fl@vbxPM#9Ey5UMUDSSVwcslcoHe!96 zVbkyB2a&6pUp#8Y*pN>-M%3w!Bu|Plx1Y!R;J0{6#AxO>#F{at+siTHQg>v1QjG0b zU;A}DC2}>hJAh`4`B!p`xYQk4pA=*E>ubN0r$nx1_WjU|u_2WlBXV^|8Ysn>{d#ri zY4ZMb^@r%;+6`&)ZglmBSlZeRY4UFD*&kw$Yk#Eq-JjQUi(dWt zvl>gs;=d(Lo>y0YEE$WtAx++mp8l*?sgcD+-H_&A532PS*V>mqmS@J#U7EZbd-lgN zy|_QpAnC(bXTz>*8)mlXs)5KbF_U-H;~l#wY!;3@y$}nmn&P`(qhn z+#hN3{&e++dELRS8jSm+IeC97`op~L@K{sI>`R)w8}aH#8^jMn!*^#T_S@r!@50v!c(; z;*Jx{QyS_@!ias-oJ54Z8X{Z|&eP$MSnqZ#N zP&eM?GxM?21c#J{^6KgHGQlCG$-B|lA7*jO1oM=J`cu(oW^u~|^OT0VQPF2+amxhr zl!m&|)o12)%LEsdhWb;{XJ&EB1oM=Jy76s3GiO^Sc&0Rz`zL*7KDJD7NNFh3ias+R zTP8T9G}Mi*J~OXdCb+0H)Sr4jpC_27GJ z{#X_lcSD-I8(saeEH3VbG7!TiGBHFSzP?wrOB=v z7srJEtcRA5#eYkhJg=_)SjHH4Lz=uBd-jKU=EbeOj60?|dB-aH!@Ta|)?UWl(44#* z75!mecX8`8<8Ek9-i?a>Ft59~b)IoIG$-#ySAUr4UEEsGxIdbc_ot#i%A~bnVH_zt-XxiK+|V4l+Cx%c&lS=?=cc}he5>FP7{y4wU7m4^CL(Pw6r zw+ZGc4RxcU&&=X(6Uc+c#WW#UKM?2K6abnkkU{$y86t#?l!?irJ?>* z^qE=QZGw49L*1z8Gqbqc1oM=Jx>3*P`vmipCeMA}{xGk*PjFFbsACmQ6*k{z&utH=+CT$MUiGxl5CGqpLrb#l_u_Chta9e=LiOyCF^9jXnEgd0pHeY4ZMb z^~bWfxEs>s-RSC%WpQygq{+MSNq;OKi}R8u&#S9HmXF2VkS6cOe*HO2a8YS;Zrs-& z=9%m3irA?%)SrqTGOs(hwU^O*lQh(gias;1JGgb8aW^z4yKm|1Av3*$TMHWZM|1N2 zRP={=-NCH|jk}>ac{kqW4>PobTYDMjr8#+C75!m`c5rJi<8Ek9-i?a>Ft0nfwU==> zG$-#ySAUr49o+iNxIdbc_otpe>uN`0R?_5LqOU*9;*Jx{QyS_|MW30)9VeKlG}MiE z`ON(AIKd&Mp}e~K%zW%P!6Bug{#5jt`PgxSLrO#4sOU4ZxZ?!#l!m%d(Pw6H#|h>s z4Rxcd&&=zN6I@gp>Q6PAJMnZ=zZn5Q(kqTIWrBH1L;dOM zGxNG-f{RK+{i*0Pv$$n~c}hdwsOU4ZxMhNQN<-bK=rgmpWrBH1L*4kK&&<#k$0{$u znF7*0GwtJ#h(^!T_RSU-R0vw@{(sjWyI$b+{!owS{#W;hzVFxLdH&z-4}B-C$Mbxv`$OM5>+wAQZ}-Qa(D?ce zF2#>o;kY+HnD9t3He}`O`8A=Eg7}v|r82sHXol@a9Y2Wv_;VJc^fkk#{~14s>-bY5 zqvSNhCRfJ~qB{N@$S8fyu<6(FgP4*(RWeFnGi>^u{2=D!PnL}Op&7Oxb^IVA<WXh)elX7Nhhv!=~TK4W607e$?@U$dx}0F-l)EZ2EQlATH(4JB-rT44eLU_~B3F zdreM?F}I(`4!1<|zDGff&7W-;rLP%d{*@dfF6B=zjMCQ(n|>!hh+O&838Q{!hV4fk zKZsoU^9Q5!HN&P~#}DFC{)E9Oea*1xck+YCl|N-L>c@XO<7$3CvwG|QiWJth0V5)AO1|c*Yu?rv;TRVM`TG}cgHNri=M3% zV?+EYh_xNFWr*Uim@H*C%#Ue65Bc>4V1$7 zqmHMyyH#{~1q-DP54$ zN#T>L<0&zv3vxOseEM}fB`$SA)+dEezmuoLwk}8mrSScz<0+A=3$iUKeEOX{C31B^ z8YqSDM;%XzTwRa`O5xM5;^`GxpAWVZ_3g3@9o)WpbA`O(nr{Bp_B3D)bW(a)fH)=6h8ero)VY3 zBI}dFr~esGi78!?(@EiztK#VmIh_aRdIXS=iC2F zrLg2G@ogv9z^6(&YW=>JO2&wHwmp-RSBMak#Y`(&XLf z>JKrvwHwmp-T0h8YZ}Dar1{r_G;On{efz_lZS{^jCQaV4ivBP|J4|p$Y3TY>(P!p$ zhY98>4RxcU&&=x%6UPAO(I4h@hY98>4P9F*`pmrUFu^>f zp>Dj(XJ%-J2@WX@cu2`(y4-i^NgFpE1*Fi&ZyKNWpu7I&Or zp3+b^D*DVU?l{3brJ-(g^_h9yae|9VL;b1fGqbqk1oM=Jy74ZbnU5VOIHWX`S4E$h zj~ypCq%_oxias-oJ5Dgqy=d+)JI$}FNvwza(pX*>KX++2hM$cWE=X=V& z{IM)9e(us_*Nu~7!hJlnEG~Xt(&XLvq(7FA#d%4S=e1{lEFX*eBTe3)uKrj)7I#CM zyc=Epu`Dj`hBSFMy82^TT-*(5@^0+eA7*-|3GOEi@r{Z;GtWG^wV?6!M|1M)Pd$H@ z3FawHeogqSKg<}H3C<=BWm?f^W@w9Bdl_BlrJ-(g^_iL8;?`%z{n4E4KB15<=H%U|=nwO{#jU-JyP-LGH!AwWyl!#pJmYR?PTq~K{xH*9+*;7MKbn*Gr=ma1 z;+6^KDGhzzd6&=3$Ce2WDGlXS&*$?5hmBloBqVMIUp>9<4kiUPtOnlEP4RxcZ&)13Xf~Cp3(bpel zde;f=Ck^%IT|P61yiRaPX(+FXJ~JP?PH;$Rs2df1W)^pyV4l)YH~w3n*E@?J_kZh& zU*nu_(2Trp>)#{IUu(km=FiCDww}8*c{jTHGqSj?Zb*}NqpLq7i`(jkG zZDlG=o@q~iZiYj~-H_(@=Zn4hGxD*m=Ppfl-MAS}+sVU`#ce$=Y4UFD*`JZuZS_Z* zygyz2Va|4&U~$sWeM?23nP=Y2TF|X)i{|9lmWuu`ue+Ibo?G3hFlS9~{f0kUaW?Km z_4hPSC${HElV{P@pCr>tS{CSe*?dL8{cHJ0vhwA0wlca7xFKO~_boJ*+Nw>QpP2P=9`tzic+j&Wo=e1{l zp5$`7Khos=>FN)&xbr}WxBH_xd4DSU!z}JR>;$mg4b92BQPCe}apz$tfbDK*PTq}* z{xFL>4?6*DcSCdXZq)PVGOVuM%3YeAXZH1nS>?EM=XQTIC%bOE&qL;8<4&2|d1+3b zS4DrAkBvKtZg)d-@@`c0hgsaXYw313G$-#ySAUqrjXRre_eXQ`{#5jbIor5v>2^0X zC+|i@f0(n4yOwTuLv!+ORP={A+qi4#b~iL9@5ZFlW0Br!Z}ILv!+ORP={A+qjeHb~iL9@5a0QVXigq0J@!*=Hz+(34e~^ z$yzqAzoQws*47+p{>okc*fZV^4;nRcwk?08$@|mQpOLd|bwirG8(sYwIonn@q{+L{ z)1SLppBZ;Un%_KgZ~lxNa_hNElU+CNX8md>4@b_n^}M9XyYWeXM)tLpmo#}^UHuu^ z*H$;A$-B|jpOLd|bwirG8(sZjR(Ut;A-DRYIeCA&`ok>lKEXVtq0grkeP$MSH|sOE zt}U9AUt22r!z}J@)@N>YLv!+Oe9E6SpYeC%QC`wKe+S*kAL57WbCqWMb=uh<;$!P` zmnQEwsu3B zyc?hNhuGJemo#}^UHu{UwRS_Ayc<3JIXsdl7AH;ioz(F`^tyV;ta5$LaDSx9t}Qh^ zWEOXr;F;3UwWXrZ%;F9cJX0F#Mn#{Q#T_PirZm)zias-oJ52CQX{a0T@|oG!VS*n@ zLwQy7nc3H2f*(pl-RSBwv$%B^0sibMP5#-lqCd>y4ih|68oIXB^LZuNbWM;Z&%Lid z%pq5r%l(lidrzt9A#=9l1kaR)t}PXPX3ln;;F;1;H{Rtlv#;X>W0Z#Ss^~Mbuj2$` zl!m%d(P!pt#|fS(4Rxcd&&=YE6UQ6tOlhba^?W`} z@Jwm)+&}9Nv%%8@W0Zz6{cfKRzwD0ZKM!_za{N%5(WAZlW7${S4QYOV@31d_EN6?K zyEJ(>y82@|Tigw4@@{nX$8xr~8`9+6*t0*Dv&H?9Cht#Ie=KKD!|ZEu>mlPT zG$+rZt3S-g7Pn?H?vLi={i)~=v$(~rnT)%kIe9ng`E#D&nbPDuv#&qQD$f(VP8#Y@ zMW30)ohR0CN<-bK=reP+^90Y7hPqMFXXb3@37#npb>m$=Gy6JEFh*%8uWCNqy`x?~ zFY57eZ=`*0neJHKCG%_?JKJF}i+ehV4fuKZpiF{%qg*t@=2FKGVm|(K#wdNwu<3X5gP4;)p)u-*X4rnz@q>tzKZ7w!Uo&j_ zo%|qT<KMuA+WOVf)d^4@<71^rf)rck;t>sVIFZ zZ2J51!;-70A5z$Ubn?S;sVIFZZ2Eih!=JME+7BtlcKkeci?B5CPdR28Tl80?7?bg5 zFV=R9h><^)FnYF{Vf)d^4`N#q ziyh^n88(+He)x0xUbB^AO!nvT`GzQ5B?XZ@e->TT56u`G(#tU-SBu-^u{2+4WPvwjHp&7Oxb^IW5<Z0^D!=~TK4PDJxpeY_n9>>7S*BWbCF`q{^#*dX;=RJDaR}^ zivEfeV=`AqC2KooiBa@iq_FAl%MVMgqJBtW`_ah{%cY|9rLgJm%MVMgqJBtW`_ah{ zORl2yrLgID^22heD19kx`up;On9|kJz^Fl*VH@-gKZvnikvd5+rm~WnDxThuDM?|o z-J2i8`ffbn|DyCY!=~TK4`N$4w>B{9hi2G*yu%NoPB*tEFUmzTY%X>DAYybw3Ma*w z{m;X%PM#9Ex*^+=!uO+!r+1`*QrK*J`9WOjj;v1#-;Yk761ln~4V1$7qmHM<>F&t- zr10r?@|4Kc9ciExz8~-Kl$g>TIh_JL$^wHwmp-T0(G#G%%_q{;K@>JKrfwHwmp-RSBMaj>-;(&XLf>JL$}wHwmp z-RSBM5wf)#(&XLPvp>Yx*8WJ7_ou5rMBvtLNRxM?r$1}*#OtKVdFE&RVLrC@m@}0o zd%f56konkQf-y=%ulI^RGmAS+@Jwl_8x?(K7I&E7ncuEig6|^zzge2```Yzg(6YGL zA8CHyOYF-Z%i`kaE=}HzuKrjS7k5LNyc>J=$FjJ%Khos=d6z$yeZ^TwlV`DCe~ykZ zM*WfI`MGjm{#XtfKX+-eYs=B`-aZ~$&K5r}Y4UD#^~Z9yxEs>s-RSC%<(Y9eq{+L{ z)gNY+#|h>s4c)I+^qE=Q(XG#nuPvIBUt8Yg5A(63TQeEwr8#+C75!oMb#&_?<8Ek9 z-i@yQFt0nhHIs3FG$-#*J%3IUJX4zd{;;n<%qmY4yiOYGPeq@Z#hu*x%;-Hu8tO(x zpP9v--1^M88=8~dZ@kY#=3^(fW-`u8bMm|@`orw&G{G39q3e7_pP7A~CK#hM)QyTh zGiN(Z@Jwl_8(n>77I&Ipp3+c%D*DWv?KHtNrJ-)r^Ld%znbPFB_w|Q4+cLp3rJ?@3 z%V%a^%LHSThVrWDGqb^Ef-y=%-Kgj@bGBuIXG%lesOU3uwq=56N<-bK=reP+WrAl) zL*3}=Gqbp5f_X|q{i*0PbGBuIXG%lesOU3uwq=56N<-avkI&}`#wbmmMPGlIeVr#5 zqcqf?ias-EJ5TUTX{Z|&eP+&fp5U3%P&X?2%$)5!!84_yZdCM{Ioo-HXG%lesOU3u zw(|tfl!m(TZ9X#}J5O*(X(;zk`pjJGJi!m8p-j8_%PM%jqf0&P5 z-I~d`8=8}MqoO~|;;wGZWZVtS$-7a}A7*h^w`MZ#hUVnmsOS%~xT{-N8Fxc-@@{nX zhk4!At>KLOqd9qhD*D4L?&{WO#@*1Iyc_lWxlQm)X>y+VS$~)f-X<8MG?ZyYpP7B# zCK#hM)QyThGiSR^@Jwl_8x?(K&UTyNnbJ@3<*=4|%~o+%A=<6S;8`?^ms zMrkOoias;@x=%1hX{Z|&eP)JspJ0{JP&c~z%$)5$!84_y{#5h%_@J5p`StH#+4GWS zzy1(sTe~66_B!g${t#zdpSv`9H@f;moNeufG}&0YGoYbs=bl$Kt%C$@A*!kL6==H>AnC(bXTz z;^J;dlXs)5KbFPC-H;~lMpu6J{xGXNxb>NFe>5lWPgj4K*B#s%&bU9C zllSLc{xBaqxHXe;UYe8VRnMRG+csh#(&UV>uRqMbjuQ+`8tP9)pP9uS-I~ehJw+Po zMn#{Q#U0(6$+#PulihFB^pIKH(XG#nyP-LGH!AwWEbi#mXU5&ooV*(q{b3e&bn7$Y zZfH*4jd%IO?CUte7^R{6!-_sL*E&w{LusfR6@6xgcAQ|9(oi>g`h1$;nbPFl=<5%2 zw$lX9l!p3K(P!ptrwN`Z4RxcU&&(lD6FgHI>PAJMnX{cHc&0Sejd%IX?CUha7^R`S zD*DXq>oma_rJ-(A^qD!^X@X};L*1z8Gjq1n1kaR)x>3<*=4_`4o+%A=qo>cy1kaQv z??zvLn6oVtJX0F#&$s!^3~iZUmC{h|pY)m8*D}EvrJ+nK`poQWnP804P&X?2%$#kR z;F;1;H!AwfoNbxlnbJ@{QtB+_8#>$A3dJu z^X>l7y}BOH^R4a=-EZpgJpXU^hwd5mc%E-{f9!YIukYV_JkS5z{juLezvipQ^L(rO zW4}j!&0mk_`G31V_PgNMeD!#qZ*_nCNszA%kmARDh^P&Chta9f1X@+yBpHv-Po@`<6ib#{gLLc-=FNypC@PDe(us_*Ou`t zgkBy#3G(*yk|ys)SAU*-dAl3Z>YnIqpwae=KKs-RSC%WpQygq{+LnUw_8E z?6>Y$rFrtq==IgtAImD^=PpflZ5hu(*nWL|n}?RO#kot9=l*T}SUwhKDovhgSAQ%& zjJqLC-i@yQFpC@a`rm$!)116N75!lrH}3Vn-3`sjyHU{}W^v ze(vQTUk~*7@BOiQ`a_=|^mv~C-}Q&@LG!<_|Gu_Abf2lm^L)SEAG%l6<9WW{?hoDX z>G3?@>i*F8&w4!1|J(hc?~wI)p6|E&L*E1I@jTz^{?K>5dOXkn+x;1Lo{tHR6yxvo ze;&Ky5%YVGg2{;#V>0V^68USfmx9RFxL5zyD_b*cgX;J}TxZ;?e=B{>u<6(FgQ(BA zSN~S}nqkxL6spHvLY15OW&$>fh>zX4rnz@q>ue zy6ZcAj*`Nr{|-Nh6dfLWCQ>d^*j%dkaYUvh#hC1R_6Sk9UJ7DcN2Fg;_y*PSl(^J- z5>Ni#AcarAlVe1#*4>4vA5x4BspJ@utK-D4TKdjdg1yM?v#qVLTq=4lQrK7azWlJ{ zD(Z(6wjZDI!xEz?7b$Emo&2!GC`w-noBqE1u;eQ0hZMFSef;pJ0KTR##hCriW5~G4XNZ9k*me6{EO1p44eKt{2->Z zxD|I%E}CI;>Es6yqs6Vsi~6A%wjXu;ATH(4y^GS<44Zx@KZtGlv+tsQXol@a9Y2U| z`P1#9^fkk#U&jyPQvUq9D1FVa>38yj$dy0CF6xJ7*nU*;!=LB&nynOLvOkYAS%~$$ zM?nP5pQIKgrx{~*y&NN^WXh)elX<)ZX8!=~TK z4;YB3EZz8z_bEM;%XzT%B>{pAaVO5`&OnMW|6Yy}xw;_Rl45Mf&%>{GcuK_Rf)q{) zpGzH2i5Ojw!b#!N@8l_ws|(UVDSSVwczQ(|D22`TzxU((vPZX{@y{tNmx}%!QjGau z9sBI=m?c-yvz5a3qmv(&OGW8RVbkB2AC_E2{gA@;<1>C(#unuwh0UdtAC?$J=}TeL z@8pN&Qc?O+*!1`1hb320Kcukz=;VjxQc?O+*!1`0$Ia2e*M3Mbw&UmV&58YmZf(bi z_1%zuN#XlZ$5SF#H@EUH>bho(`M<|8VoEo+;x5WXGi)xM{2-=ub8GUVerSg6M;$+i zT;1H7yeNImu<3X5gV@&1tuTxFp&7Oxb^IW^u z{2;b021?=kQO8r_Qg>v1Quy>cc}nE!jx$@|mQA0ldNH>AnC@kxJ( zaIJYsljqgdAL3tYH>AnC(bXSfaBDZD$-A*%f7W&o_mk#d5304zwfg$Qyl(Y{`y)-> zpNjr4uRBaIPig4dQqgDTb%zP&DGha_tIy2z4ij8d8tTuxd}fArnBb7oP+k>%W`=f{ z;E>W#H~u-FFE2Z%io0Q%o;1Ecd-lgNy|^3F&DSB;Xmu4N7LFlUtt|y%$JB{i*0P z^SYB;pBZ;UbF%w{njSK*JGr%&aW^z4??y#`nAe@$I?uQpnv-{I8oDQ` z=rgmp(**OBhPv@CpP7%HCOD)tlvhQcnU9?&IHWYxje0&W6Up;G)t{ z$13{FEN+=#p3+b^D*DWqo*fPN(rJ-(A^qE=QGQm8hp>9<4nOWR2!91m*ZuIo|Ji$e!$-B|lA7*jq z3Favc^{1lG%;L@y%u^cb#=CrGK6akqkkU|I6@6wtcAnsn(oi?L`pmrUJi$e!q5f3# znOWR4Q<^;Y z&-%lB>@vY2rJ+nK`pkUnGQlCGp>EXo`5K%TaB<928oQVKzWuShF7AdjzkgG_FMlkH zi=VqRc{jTHV_96>4QcXjboIxwxVRhA*u5O)Y+zrjiyYVi6n4w+W+RHdE&B^ns=npfrt6O^+cSCdXZglmBncmf{ z&y4${IeC97`op~L>egPy-O!x88}PAJMnUCEkIHWYxjfy@qi@Q%SPid$dU43R=cc0**(olaY`pmrUKEXw$ zp>9<4nOWR@f_X|q-Kgj@v$*>N^OT0V@h+d4kKHFYq%@RQN1u-mQu&`>|NfOdcWL(P z53#tl8`5mA+3xHQvAFfQOOtn_t3Slz)^13XcVo}~5U*SNBTe3)uKo~J{#afYcSD-I8+-Q0^31qD(&YW= z>CZ}GiFrzsGta*MFwZ=?b)M0+MH=eQyL@Jbc64hmFt0nhb)IoI zG$-#ySAUr49o<^cxIdbc_ot#i%PAJMnZ=zZn5Q(3*PWrBH1ljq*oA7*jO z1oM=J`qR~C=5@;i7nO$kQ_*K;amxhrl!m%d(Pw6H%LMb3hPv@CpP7#>6C6?+%B!o- z%+QtzRw)hjr=riy;+6^KDGha_qR-6YmI>x54RxcU&&=YM3Favcb)%=x=Ls$Z z{xGjQPjFFbs6Q2bW)^pzV4l)YH{Rtl^Re>;hm?l$s^~NGvGW9nl!m&|)o12)=Ls(Q zr!@EAya4~Vq_O7(yvHBA-_@(fdVJgute-#jzV`L`>G3@OZ}-REo4)3&$Mbxv`(y8Q zU-Q@FdH&z-kG)@g%~y}-`Tkvh?0xmC|9U+4zq&v6d+gWz^?08DxBFwii+;^lkLUST z_s4$U{F=WW&-4Fwf9!Y0ulefnJm2d6_!BH&8z9BV9e*C*CKD5^q+os{#hCxP`&oWP z=%pb3b8z3FN7oO{unl^LAH-!2?wj%`7tOG_)bWF;&B1*a9;L4tHvKw&5HmWsZ?dEG zHN&Rg$q!;m2loq}s2`eP`%%XaB2EYQ8=WY9&9Lcr@`H%f!TnAr>W607e$?@Uc-6uE z5+_PuGi>@*{O~6ezGf@MnC#DkZ4m2wkAj$zKQl2(PBX^rdO1eK$e%$N^+PjkKkE2F zT*{x+7^SZnHvLY15V`UvF-HB+4BL-7eh|6xXDvqQYlcm~jvvIO{Ar3&`kG<@BFv>+UY%X>DAY$ZC`is)n44Zx@ zKZsoU)Bd7w3VC`Hn~oIJc-d(`cl~R zJNfbCbX)05VbkB2AH=rK!)|NR&*MIcSl_1-a%j z>Vm9KiZT23p1+f)M6NDK1Eui&sN*SdsSC0`DSY~W&(kXsg)4rNm%?V!%MbdTe#OuF zQuuy!@{~TgUXcb!;rmg?Q~F$b#n1Xu`1Ct@N}pV>NCTws{ix$9eR93xXIm+J`k(QX zK2u)tbGj5hxjLTGXUZ#nPM5-`U&m8gKXS!2Ia2uat9W`t9wdd$c5i;rDwP}ZLMeQM z>Uc`z>V`B>3ZH%_Pl;UJkOoTO`%%YJB3C!0fl~PNzr|CcPB$cZQuu7Y#ZzKRH{^6u z_-yNVN?huOtWOG`ejQJVOWlz5N#WD)8`3~2d_Ssqx~|Xu_pg6Fh|b}WaGxN*nV{K!*Z!8eJO1E`|`t*tEeAR*nV{K!;-5geJO1Eo&2y|DoS4p zoBp2sIQ$<09C_etL!_zT&*8x#{`2_0{`f+l4v+uu@4MZ3{ycX_-R_1o>-YV8^yl|Cv)OZ(Chta9 ze|~?DopnQ+yc=Ep`Tf0b)(vU$ZhX?8-{1CTc}bJ!)zu$nU(fw(v;JsK-k*y8FpGQc z)tYrfbMkIf^oLp8bKlym8=8}MqpLs6;+{L-X8qBeygwEFVHS7!|G&Y>x}iCFH|qKG z+`V}_cWH8-+1DRtanGHqv;JsKcHMZNhs?*GJ85TmX-=M3MSqx&J$KR0x}iCFH!AwW zEbh6-cGeBe$-7a}ALeY&{k5}hXinaZivBQXd+xrSbwhLVZdCM#Ioor8@2ne|lXs({ zKg`gcyMJfh(44#*-{ueVvFEFlT%25}tKKbMkIf^oKdybC>a~8=8}M zqoO~|*`B+UXWh`8yc_TGhuPP2U-2w2&B^ns=nu26=dR;fH#8^jMn!*^k3DxB&$^*G zc{h6c^W33(yBpHvJhQJq%psrqb7%e0ob1|C(?jNL&;7l#ZfH*4jf(y-XS@IZlMl0Q zXinaZivBQXyZ`@l5wmV+PTq}o`D5AFDcB?N?)FHOX51BZJu9fIhn9WCxl8l=b-FKq zEN6?KyEJ(>y82@|Tigw4@@{nX$8xr~8`9+6*sDM5=Y`*AH2(G3;k7@~{Iw_h9{sT# zGVX>n+t-%0GhO|$oGtE#G5pY!abD8od3E*2vah%s(&XLf>JPEFzwV3p9!YcZ z{#5jbSmoLcY4Y5=`a>*k?S?dYH@f;mEN<<{s}wLjA2{rQ|f>#2@(e<;m! z&1CfXtFJ%I#|{$=O&aP?MW30Et=Bldwn&q`7u58SS=_;`nT)Tinv-{y4sOk4 z+zrjiyHU{}=4|UJ*8H9#P2P=){xFL>Oz=!;=w7s<&&=Wu6FgHI>c+c#WBf$ssN$?pN``LmK^%3YfLny_zwn6n)xc&0Sev5G!3hdfU3Olhba6@6yT zcAVgu(oi=l`plf|IKeZep>9<4nK|2Wf@exY-FTPJ%)X8jj8PiOtD?`$zK#=&Q5xz- zMW30o9Vd9EG}MiXJ~L-KPVh`=s2e?fK20!BY4UFL^@lmzX@X};L;b1fGjq1n1kaR) zx>3<*=4_`4o+%A=<6S;8`#Mc9MrkOoias;@I!!P}X{Z|&eP+&fn&6qzP&X?2%$)5s z!84_yZdCM{IooN1XG%lesOU3uw$lX9l!m&|)8}P^XG)WI#>R0v0vadK(X@0N6-s-RSC%p5251GZC-I~d`8=8}MqoO~|;?8b;X50~rOhUVnmsOFE|%jz|AJwERB^?85j9#@a&`Fy)Se2<<#KmGT${h|9zJ)Y-V z-5AvcVf*n8 zKZqFla|febG{fdn#}6V#{uIL~ea*1xck+YCl|RWa>W607e$?@UxRgJuFiKxDZ2F!2 zAado;D~$S~8MYr){P5@Ly=E)LnC#DEUkIXsl@!G3{CR>=KmLgs=a+rS{l8QSo6G;^ zhb33h3@OIzgFj>OPdR3pQuJ4(u(@>d!xEz?eJO1E`|`t*tEeAR*nV{K!;-5geJO1E z`|`t*tEeAR*nV{K!;-5geJO1Eo&2y|DoS4poBp2s@Tbwe_Ct!X9Y2qqKrIdY=Nu#2 z<4^62{-v5Rru#jP5o252?@gm@HN$4x$q!;%i`&gQ>W607e$?@U*w*6qtB%sw44Zx( zKZsl{Zb#}Uea*1xck+YS*78dVn|>!hh+Hkdq_FAl%MW5(%P%QxKfc8e;!?{mDQt38 z{P1Vqz231&F(&)-xWgq1*Goa1&Y##8HApkY4pnlD$dx~nElOWAZ2EQlATH%ku8Y#w z44Zx@KZsoU)9a#sXol@a9Y2U%`Sa>Uc_A>Wm~$3ZH%-PcO)}q_FAt@`E_t<#F1;csj%D9laF3ADtW{ za&^JAfl~N>)bW(a)dg4nN#WD4<0)~e3$FZ=!lz%yQ{qw=T=^%3PyaKX5;3|UQcc}nE!f;3PH-;X+;61ln{4V1#C-^bG{(m*L}`n~)ha&<)-D24Aw z9Z!i%U6J)k;nVNrDUquy(m*MEKi=UfF{LYVIw^cEbvz}ebVW`lg-^eer$nxkCQesLL5%H=)JY28k4~Nv+q%0|d#~4ZDSSWbcuH*R?$+c* z>1)QAe^w@q?Js9jTKPV{R)EsN*RywmWhJUu+f6|pO6#{KAC-?jGc53#M) zA88H`D)yiM+g;gSD}El{^!10h*81F~$-B|jAEJP3H>AnC(bXSfVrw^~$-7a}A7Wi= z?$YGBSM-M{*P6RDdG1~PAqKW~Lz=uBUHu`-wsu3Byc>J=hdABZA8GRb^z>&p7-C=@xN<-b~>N7LF!vq(VhWb;{XXbT> z3Favcb)%loE6F1+Ax)n9XZ>M5cAVgl(om)qeP%v(oZyhsP&c~z%)IV6!9}Hc_UHPt zKm1C#ty82^TT-*(5@^0+eAIt0F{z#Mer=mZW zv&Fefljr_z{#ZU1XDUseX-|JnjzdP>kS70J+1DS-;^J;dlU+AXjtTF}L(A*p=Ppg& zpRWEei#tv5I%(*=siM!!Gf!@vXMAnZoc!8S(I4h@C%4Ws?uO>%-FTNj%+OA5?PZ*o z=Hz)*^oRM_$*sMNyP-LGH@f=6obBY+UdH{=oV-63{b62ra%(T+ZfH*4je7np6UQ7gnnb$3DEok(x54RzyPJ~JO%COD)tlvhQc znU5_K98wzUMpvJi*DVuVR2u3}MW311EfZW+8tO(xpP9ui6UPAJMnZ+#=%u^cb zMo*v56I@i9yc;$BVHS6uV4l)YH$Lez^Re>;hm?jgt>`oJvGW9nl!m%d(Pw6H=LzO1 z4Rxcd&&=!26I@gp>Q67 zUU!+`qS8=*D*DVU?lQqVrJ-(A^qE=QWrBH1L*00n&&RXn z$-A*pNjri&KBn`O`iL=`D6K5oT)Tk?Pc5z&B?n_(I4h@H@EgO?uO>%-Kgjf z^SYZ`dl`2_bMkI<^@o|>&8-EE`=dE|e=7RJyzb`Kg2vs@oV*(q{b62rbL%|gZfH*4 zjraI-pWu+vQ7gnnP=W7xTrMLpNc*+i@Q%SPid$d6@6wFcb{OM z(oi=l`phiuKEXVtp>A~bnR(rPf{RK+{i*0Pv$*>N^OT0V@h+d4kKHFYq%@RQMW30E z-6uGtG}Mi1J|7>%^FP1-{VRK3((KnCVsUFXq}l#%V(4m4-T2(P!p$>ou3JKhk9HP4DxN8QNij zLrO!h<%&KtLpw}xNNK1W6@6x2cbH(F(oi?P+voesc>%}AouBg zKbF_U-H_(@{o%g+vAiyR?$YGl=<1Ksq&fL})4Tj(hIVvoFXOy4C(o;^Kg`*VZhdClAI-`8 zQ_r8%1c#I+zX#~+53{(_1k;m-`cu(o=5;5x_A+`;k%qca(P!p$C%4Ws?uO=M_ZxjZ zWTtm=YeD1wXinarivBQ*J54Z8Y3P0DT|P4(J56v%X(+FXJ~JOXO>jtQs2df1W)^pv zV4l)YH@f=FEbcVHJf)%j)bn|nV4l+Cx%c&lS==(gJf)%jRP>oy+%myDrJ-(g^_h9* zGQmZqq5izfXXaze1c#J{@~Y@F^RZ=uLrO#4sOU4ZxMhNQN<-bK=rgmpWrBH1L*3}= zGxNG-f{RK+{i*0Pv$$n~c}hdwsOR%}f_X}l=l)rLn2((&IHWX`X+@uzkDVttq%_ox zu0As#J5O*(X{bLHeP$MSo?xERP&X?2%q;Fa!91m*ZdCJ`_OjCB`MyWh{h@nkJ)Y-Z z-5j`@iQ8-Dm3Y+~05ahwc^ic%E-{f9QTtkLUS+yFc_j_W1baLGs7_+t>fC z$DjFE^k@98I{NqP@jTye_hW&d(vnLeB&sHe)(^fkk#-^q{b z3<*=4|%~o+%A=qpQ!%;_eg7QyS{ejL*!q?i2h_8p@)Y&+C4G&m95d?<=Lr zf1kT|e~7cK{z$X^efOX9XL;GX=Jjv=S&ijv@!yi>cQ^LskL7IfbC)LXMpu6J{#ecycSD-I8(saeoGtE#G5pY!abD8od3E*2a;>-<(&XLf>W}4YaW|yN zyRlz?#?y*d<{9-znkVbtmp_(O#?M`v?AkJ(_PqW2s^}rJ%GHFsW4PTq}*{xFLhPnq8ChUVnm=;{yiy73h1?fz&^-k*B@tgE`{^My1y&+O|D zbGG$b!TpgYyKcPCLuOy&xz$_Od1>hNUeRY}U*oCP+uhKd{Iy)sALe7@nb+Ih(44#* z75!n(HlBCA-3`sjyHU{}=4|6>*xTLEoV*(q{b9~_biVD;U#D0Oxi5b#tBjw!G{1S~p8PpGo*6xN zX`b&F^2c6R&yH2b{#X_#&0ajToGs2>n(Te&?0D~=_0Y1f_-{#*=hf98%f8}nNRxM? zt3Q^Z#odr5??y*|?A}qYz0l+1-bnrYq5FP4p6CDV{_wqf{`~ac*Y=0*b@h0jZ*_m@ zepZj?`Tt#i=$=uJ=l*}YKlVH7*ZV^~p66TLANxJ@YyNsX&%e4q^qsXH&-4Fwf9N}R zJ)Y-V-5-Av8`j9xEw93%R*eqWGZ|D+h(v0fcI zIYxBIpZOTQ8Z={U$a@?kYU9sjjB?Qon@b%(h#C3Q8>93!!=~TK4`NRK1jnc!nqm7< z#}6V-{*1;bea*1xck+XXls~62>W607e$?@Uc$Gh8F-l)EZ2DFF@TUO2W-G;*?9bz~ zJh8rB3L;nQ`8YWblEOFW9gY!G^5-E&uWZd2ld0qw5j1})VwApS*z`O3LFCGxj2QJp zGi*QV_(9~#pM4mmuNgM|PJR%%^5-8${m=~Ck2-!3x$>tMM(JyYO}~yG#HIWhhEe*O zVbkyA2azj(Mq$(s&9MFW`+oS-_Fi3=V)XpyvFj{xx=IQnM*g(Hs2`d!Hl&whMDqM; zf>A#-!}g<&A4IPFd4W;-nqkxL-cOW0n|2*-Bwwb9?f`pH=tT z4=KiW{5*Erw=}S}W0vGa&qazce}67vZO1H^ik^!UHvN71VaZk04=HRvI{9I_RFu9H zHvLY1SS}T%FNID2Tl}z0DN0TXn_MS9EHR4Gm%^ss$qyn|{+zg|ADUtN(a8^DTgxvg zZ2Eot@aNpUzV@XUv;TRVKTWK!l7dK{KkF{)hh~fo>E#%)Eq_*9)DO+D{ix#yk*o7# z9rXC?{3v}XZ2Ir;gP79!@r@MaB8APRlOIH#&X2no>W37zA9eg7a&`VCh0S(feh}L_ z|B}M?qmv&*uFk)tu<3X5gUHnxS)UYRJ60al$I}b4Eh%jJz5F1OcX7M%y?)-8!uR7H zo)R&-xHBN4Tr^`$rk7*HlrG5Wq!`=r^Z0~Z$5SF#7o>qw`1I>|N?huKtWOG`ekV_f zZC#KCO5yua$5SF#7i4`>`1Ct@N^I+bG*AlPk2;X6 zk*gchKq-7b>Uc_A>V~XO3ZH%_Pl;UJkOoTO`%%YJ;!-zcegD1U`m$HJpCN_K<)8Dz zlB?+7A;tLWzd1VkryR3PDf%l?*jzgKVTnw8UKiZT122N}1!@pX61lB?+1N-;L%?&xT3$1J&uo{JPV{Z4*ZE)}IOg-!o6 zeh}@sI|>&irx`Z6PJR$$yCZdyVr<8H*H_0=B3E~}CNH`=XvUa-FUN>&-QAkJs2`eP z`%%XaVq15&@-IqXGi>^G{2+35cPsy*^fkk#-^Y)`gKZJrl4jh;`t|kE*&iZ(>vNap z@K_;teE1M|pRWE8 zSzNmzP2P>J{t!i5yCF^9jjsL>V_Ul+P2P^<%f~Z(IzFeA!+L}Kev7PQ(vEjfXsZ=KK&*%88(;&~L%)cI%Y1=jR<--o` zFySGUq5f3l%)V}Y&hTrCGWlyuS3d0Y4ijEf8G3E0$eEqqVZw_lL*1yznSI@1!g(q~ z-KfZ!ecfTgc`8HQco%1OXzRE8{2o%7{5@n>KJ3{J6RuJjdcIfW%nt1^;USfwZq(y^ zoN%7X7S z#|h`D40WR(=hKAq?2x&=+{1p|A!PTsDl^_!VdZ08T+BzA-#$uwe1EK~jQJ>&_ve#* ztRIW#rA$7ru6(Q?i@Tvr-i@w&tc#1gp-kS5J@c`?F7A&qd4Ia{u`Vv|hBA3Ky7I9u zF7Adhc{jT9u`Vv|hBA3KKF4R7aB<2!{d3gkee+=txlH&>WvF8nIkQ7s+}_Lh`K5KT zzZW$bvaeg*-pjZfS|{&DMLz877Pt2@?uORMyU~>oJH5s21&#Zob@KjHjjo*8*PSQ4s4~=_ik#WS zohO{9GSrQCab`bup74;$(7Y;gWDj3GyAd2gojjy=GB!m`?1S}hg638 zQ;{?KvCD*qRED}yku$rv%Y^e(hPqLaGrPFUg!5E}y3v(0`?|}77gdJ(Q;{>fxXXm| zRED}ykMniHc`B37{j+@7k6kA`q%t(qik#VxT_-%GGSrQVoY}=)C!D7;)Qzs3*~MKa zoToC>pNgE>#a$F9UNZOKya0dgeKOX?#n+|G@86$_kG;?T)%nbr zkM(uR{7Ht^kHxc4CV#&7;$vN0eC^6)uNyb#g!?eGE-t<=hZZxI8SBr*MxoZVdr_D@P5ir$0~AW zr+0UIL8HGr%1}2da%Nw5cY8tOZfKqCJ<0nRvO~MOy_fO4v`#*+ihS6i-QC{HxEoq0 z??y#F?Becj?`7N#t&?}7D<5`o_X+2z484b}$eCT-eZqMvL*1yznO)p{!g(q~-KfU- z_%NRT`StH#*>x!+KF5cdIy_z>#=Yw6e_p#mE>0Ql&nFp@A6w_8%=YJt&V0xpuGg+i z-i@w&$i=PQP$uujp81fkTl=F--k+{~$k(miP$ut2S3cz8)@~@1ccUvGa&c=nl*zmC zZG6a~tus|7pJ`7%hsWf}r6`lT+`fF+p&ce%r83l?ik#VJuCJ&3+M-PMcc&&p_H~B| z=cx?6Zgl0$PVX?`MU|ocROHOQ?l9pzm7#7_Dj3Gdr}ygojjy=2ek1 zJG8@uhg62T(Umj%x^?#ze?CqoWLLTF z>g8@IlXqj}v%b>2?vb{ft7JxBxAkvU=C5w-jnC-fwys^7yc?h7Gy1Wuc`1|6t1F+; zk8O2BnYK-+ZfKpn8x{GmLpzzhms{P? zI(auL@?l?hGJ7w#x}kOQZdByMzV2l9UT$?m>*U?&%7>la$?OH)>W|jR`%{q*`?{0a z3%b<}t&?}7A|Lj3C$rCUs~cJ;@5X!hEE675ncPG6<-?9~nec4NP=6|NX3w@v_)KM} z8(lfGi(4j~r!v%^ik#WSEfdaD8R|ww&g|lr3FoN{b)zC@c5%yu^Hheq(Umj1xMjk5 zDntEw7iack%Y=tihUQg~GyAb+!b2)U-KfX;JmEZ*$>+XrKJ4qx6JAsq>R3h2?CZ`G zUQ`+CMn%r-;?5J!QyJ<;Mb7Nv&J)g48S2Kjac0kUp75E<(A>X?^LW3jX#a~If8MjF zBOiKStH<;Ce>)$3Z<=49{`BA9|0e$MgArJ0E&4smJsAR_8^E+p`{{PkfaU)=NdxSHezz zUp&b59o;W(q6TRV+n{&wAg6S6zjle{qBZPX>hK_^bacOYiKeeL?DRYFAh&gN_wkAP zp*3tj>hK`9b#!;(iKeeL?DRYFAh&gNcm0X_p*3tj>hK`9b#(XjiKeeL?DVVf@Mj{v z&Q^(WvOkYcx8(YICCK&plL4a!X^pW%?;%Fk$)A20%|&b2xzyo7#>k&<7)@Vm*y(rT zLFUSzaTxVOYuJ9&;X&rgpJEtIUu)Ru*Wp24%AZphO38Bm=E|Q#81+MI*nZUE zL0-zAG#E`^YuM>`;z8!hpEelv->mC3u&lh19i#arD_=C6B=?vKyYi*H}MGTH0KZ8#TTe+-|#di&ay$@|ll&(mga zcSD)H8(sN4P4;#-l*zl%mCw_2Z+AnPyc?h7^EA`j^HL_C*Pi*XXS+?fIAxxnVef&f z^n7Y$tj~=9&C2|KZP^ze>+9lcS0?X9Pd<0&Jfm(XlmETgHy`Uf|vLz%oAUHMq& z8FxdOyc=Elu+O{?cSBgebBX(-b@KjHpeoBcMgcVq0I05 z&VC0Ua*XS|l-YhRcjiM5ZM}A7@@{nHLk?~2hBA3Ky7D1kw{}CByc>JwL%we9k1~0G zy7D1kw{}CByc=Elkgr?2p-kS5u6)SFt=&*2@5U$jkRMy;rA$7r{qh;lF5mKO%4GX9 z*YkYX<<`uw&m2!b-|mmr$zFeIGGt%3UNbp-W$3k~B186dhY9DY40YpOoY|qRcYoyfkjmt*^A-89Lpw}( zNM-1`+?6vsy~BhTRfhUgkMnB8>2HcM`P}>RVOKex;J)?QQyJ<{Mb7NvjuXyP8R|w? z&g|>fJErsBCS|hEJMUx2e(X50KT{cczE|YTe(X5mA(f$SROHNl>^R{em7#7_~%p>A~L%)ah8;YF39{#4}5F77ztJe8qt)Z;v!L%-#$l*#Abmk+zR@tpeY{%D=d zOT3RE`?1r6hg621?_D{wKRiu%NM)!$|6k76$2XJXX|n5oUTx;M&Oebb9piMAnn9(ba7kPrA*$9J@a9QwoG_7W$15H zMb7Lq7qicE>-9(L;;Yg?kGdusK}XJ+J)ZaD+xhVO(){}L->=Pw-h1lte7@EB(ECe0p3nc=`Oy1O zJ)Y0EIv@J(TaV}S|EKxT_t<(opU=1Rq3@#gcs}3ieCYdTJ)Y0MIv;y-V`Pw&u=lL! z#e@Bi665^sX_oQxr4BK&W9wd}{Pj0aJGnYM$O+jKAmiz44LkihJjgiNGbiKeYYjX7PCUq1*)t{M zerOHbk2*ZaSJ@LG{lyo}AXOllv1q4&nXLM*|-vtW#2AUp%aril(oGeP-{Ahc#DG zKa{Zj=)}XCt7!U4*y(rTVZBr|eI@Ml_r=4StEeAJ*nafkVbA-!K6b8*SGxXZB`lHe z;b9$HG&v>4+1axRFTMop_Mj zI=Q>(ME%ejwjXtPkhxmVw$8szP-2|@`WdJbF>+fcckl1$)j?~F4XH$o+}6q6-8-7T z*09t63=gtSCwK4dXmVP^PVPH+_|pJiC#S?Xx1Y!78@ng3J2CQ7{!F}xht?Q7REZdw ztHu4^G@8EFu+#6vgWQ%s(J$(U*0BAk!-LF~Ki4mszSgkQufv19ls~yIn!eVs)9=KC z%#}aAFY1TZu>JTJ9%SMCDSpvxwT7MTXLyh?@@MQtlhYb@a-DdPm-6TAMg7nkwjWh^ z_;cW1XRE|G*`LR^*<=GNCCJnHGwz~(XpONUy@-*y^5@(|{m>e=A9Z+;m+~jsMbpMrYh%ro=e6^*w(lrevMYxF=5u z-;X*>$y}XrPo5Hf`gNF+mpbFVJ|+D0`!Kzr+fu?#zZVZOd6&m;w)0Lpc1|xb(oU5x}XhI!cV^n)AgS0`KL9XIKJGk zPYFByUOcS1il(o`IREu7f8#UipCV?RQuM!~gq=$#9@d~m(^tYye_uSTxr+LsgzZNs z9@bn%(^tYyzY`DZrK0I8VW+<@9@bn%{ZPX8qZ1G7rK0I8VW;1ThxJm?^p&vF{|+8E z=jmQ2r^Gn7pT{>A)@;@$Mo#I5)=3H9k2*}rT;1HByr}D1W1N34V&t}NZckp+53OPQ zQHKYatDD=$7ENDk*y(rTL2m2j_6A1%&>FTMb$F25y1AWy(e$;3oqio2WUg**=U+5^ ztzoDC4j$x`Zf?h2G#9O5=hBG>S*M%ZlNa?vYuJ8N;c-WErNlVdpT~27TwkvQnX5b6 zKqY*G>M$jfcSjqjgr9yLrsSpW==zlK)9=KT%+(!jpc1|xb(oTux})n;!cYGlOvxDC z(ZVU==hBHOIi)*#IwgER>M$j9bw?Yhgr9yLrsSpW==zlK)9=Id@NipXx0K0$aoL#< zd8_r>l{q||*y-^e>h*h)&V0yft=Fzh-i@w&$a$^ZP$uujC;5tXG-oz-Xgus=LZI7Ve?rWHA}A6t9O&v#|==X*sy?8gohj!_wU-KfZ!UEE>9XDUP8 zsK}XJ++o6JDns3<$eCT-VZvwrFPYQJozK^IwD#Yl%(xTh8~IpY7tc$X-|t2D#mBn1 z_}Z1pyYWdr){n*WQYN2QPd-QI7^7||^L&4}FFw|@#n-M(_PTL&zPArU>)GP#QYP<4 zS3cIW#obUQ??zWX*0aUkP$ut2S3cIW#obUQ@5Y|_uwy(^_Z)Z=rS@R`cwf8YD^VOM#Y@O8>i ze=2fj7k6^|Go!yL%1}2da%LBIa{DvmZfKqC{YFiO?BY&te`eebt&?}-U3}P&o!p+u zcwSm3pI1db?6po4{!kfu573n}ySVk1kwGT}3o$>-je4|}#{!e=T&{dpH>c3;bcV^oIbRgp8h!DYfRDns3<$eG>O zGT|7Np>9;<%${wT@R`a`H@b3W7q?6}Pi3e-6*;qKTPA#_GSrQVoY}K26FyTJ>PAJ* z?AewHpQ#LW<2{_u6OK`td=`EAu=_esI7VftKNUH%XFE^$Ol7DW6*;qKJ5TsbWvCk! zIkRUwPxwq_s2deIvu8U`_)KM}8(lfGXFE^$Ol7D)6*;qKJ5TsbWvCnP;>_;rJmDCX zp?Ov0%AJ=)GOKS0?X9MLyP{#dB9CpL<0<)_uiuS0*O=7$cO#d)$N&#yP1ocd$#+8&s2uGQIRuy zw)=$7REE0Il{34z`-JmUhWhhK&g{qT6CP3-n(4Q3X7_cUaE!{(+$(Zs_jR9ejLJ|q zDspDecAxN>%1}3|aXvn5=6`4Q29f?3oWaw6#CVyZSBTB zGUu0j@4sIAzB1Oc#n-OP@7Ikz@i{zR6-HkdUAr<*-@7k9)>X#Wu1xm2ad5u(pJizM zSp2`GOg^u!e5@afyP-_pjjnvGi;KIVOx}&Ie5{L$yP-_pjXm?RE-vnmGI@Wx^06*1 z?uIgXH@fn%t}^b1GI=+;@?lqbaQidk{%D=NKkwnQ+IMn{%H)o*FCX@Y#|ej~4E3iX zXLfN%w`VeXomYmsQIRvdxTD)M8FxeLWbXlLGGrHbbo(>oZfKpn8(sOZuRFRuoN<4& zPTrr2eAvYu-TutD8(Jst#=H2iA3M4|lkvQ?PCl=SeAtg2-JZ#~8(JstMnyjCzK#=) zQ5pK|S&#E+!e=Uz&%G}n_H3sKpQ#M>ry^(eY^MpIsSI_aB4_rHrwN~_40WR-XZCET z37@G9b>m%}*=wC9{Gl>5udbZgeVry8qcYT=ik#WAohE#yGSrQVoY}LTCVZwc)QyUq z*|VJ{e5Nwgje4Ay37@G9;<%${wT@R`a` zH!5;w&$dkXOl7DW^*Em=e5Nw_+&{~Q-Pd`-F)Bkdt;m_(*LlJ*Dns3<$eBIcdBSHZ zL*1yznLXQi!e=T&-LRZ5!M*oA!#|&~o-O|ODD(R_ed6;owA$Xw>XnTiAMf>5kB@zi z{QB?L@qGT@&WGMt>+yWP)%n=( zs9#^-^>{x2>U`|?(695?Ooz?f}uT4sf{aK&cb%>D{I=FAjqi2KG80TM! z7+Il%`z}11zSgkQ@5FGjRgPhXA{W>R_zSgkQ@5FGjRgN)R{{RStRzSgkQe+LgTMg9!LXf9gA&ZP4Lki# zJjh)66aJ!pXbszsIy}f+`7`{Y>1z!;{W?6zOZij!qUmc5JN-U9{8@Cb(^q1g{me=AMfBnPRXCU7tKX$*tyi2zWUm{y;jH<8p5b%n!1n)^GWoo^@?o!an{Z#s(BFcJ zoY~jiCY+u!)QyUq*~Q(4`?+ub-O)Pv-<_^}*u~w3JHl`GN9*MMsmO<2+-PAJ*?Ah)UK2sU$Mn%r-+3piQQyJ<;SI+F&?h`&! z8S2lsab|~hpKz7R(A+=CncdfY!Z9jCGp)#({n&lNF)BmdsK$9c+3|UYr`S0t^Y35T z+&l9j&$eE>GTYxxbml{zZM}A7@@{nHL!NEzhBA3Ky7D2JwLw;=Sk1~0Gy7D2fxb=?0{2o%7{5@nvKJ4NS6FyTJdflkVnO)pr!e=V; z?8f=!e)z|S*|D4}WLA?s{=JC)&C29+|12NtzT$Z)^ZW1nzW7)-7+KJ3}f6FyTJ>d(74v-?`l;i7v!C`0qA$dKLFdBQO&L*1yznLXQi!e=T&-KfZ! zJ==N0XDUP8sK%M@9i_+f_gU5X(0f)rp3lEJAAS#Z^gHn&w{>*Cd5QX=HEciX@F2H!biZnermr>Z^y}~-b9HpTTZyKxHSF{|@gTQ# zbob(k`k^&!KkD!xb9Hog(ut<8HSF}?!GoOA(cQ%+nv2%3bLqr`oRU99FzScau>GjQ z!=HrrI$I^i$^JY(-ID9;l^~Pn&kBqhq&3D4RU$^_%Aa-@ODS>wUdo>d7)@Vm z*y(rTLFUSz3mEl7YuJ9&;X&rgpZph1Uu)Ruzk>%EBY(nQG#9O5=hBG>IVFF}U(^q+ zVf#^s2bn8>Mqf02tzoBMhX;8nf5KigeXU`q--m}kNA7j{N{qArdF*x|8(1kpp3a}6 z7xhDHj1B2UjLelkOE2n&*0BAk!-LF~KP@kszSgkQe+LgTM*dX1Xf9gA&ZQF%a!USW zyr>^q!}g;N4>DK&?7L|CTEkAi4iEBD{^Yu7`dY(IzY`BKSN`<6s2^Ix_M;9DGFSe5 zx@h`Z!%n{s4}S{V>-3cvXaDo~^$Xd+N(nM~{uH{XA6jE<$a{#9G4iL)MRU;_b}pTG zkW=y}&PDyu8nz#Gc#ygBXUav>*BW;Eb$F1M@~6f{)7Khy`rpapYVH)h{)_!=ql7hA zO6-e=HCNH}m9WqKPCTrail(oGo&LUfSaTKiLkZiDPw==nr}R1(CB~`zJnk`KEnID4 z)}Te#qQp4=i@Q5vcVgCDMOUkY?MEjb)=NdxSHezzUp%b2iu$31?MEjb)?7u?SHe!e z6AyA*7k4+ls2^Ix_M;OIa$6U7zrLs+TEq6^9X!Z7UEKZpqPb`dJC`~<$SGZZDPd>3 zCmvUHTS|=W_<8&dBO6#LL9XwL_Dc!hk2*}rTwUGS9Ix*Tl`;z4ff>Q3*7`k^&!KR&~QtkV@uo)Y8S)=vfB!jz2B6)l_+ zeztX(l9#%o>r=u{zY|k(TUWG!O89DOUOp6-UOPYFN$Z(&N->4qjx2|wF!VM@m6h89iobzeif#NhwGzXtt#{HU;lbIujAt#^6~MP($4zl z@yPcvB;U0Do0Z9D+Le#BQMa(q%KYxezW7+*6<@nDc{jT9u{JF3hBA3Ky7I9mEbfLf zc{ldV$GWt*Kg#6&>B`5NwzwP0o-OKz zGEWaFKBI>{JZz@*buk}hve%Zr4B2O{T=?}znY=$0`LM4$xSf;nYm3&&yHSx3`?`bM zR~dIh>*U?&%7>la!R@<@`=fR8{=AD1JG6t_DH+d8>*VvQ$cG);!R@1ryPAUEFcP zc`8HQsK}XJ+;PHrDns4)BxiPL#|c-d49&D6XZB<3uUqK*FJ-736&bRNJ5D%HWvCk! zIkSsfe-X#88_HzvqAx@Cb;k)WstmohROHOQ?l|E^m7#9b<9wQMp33BN|12N&W2XrZ zsSM4uB4_qvrwI?K40WR`XLe|(30J8M^`|0dc5$Z(=cx>JqatT^ai7S zrwQk&40WR`XZD$=2`{P)^`|0dc5$Z(=cx>J<6WHDkDVqwq%t(GdYqRD52;K(_r84C z#Vr%gQyJ<{SI+F~mI*Ja4E3iXXLfPRg!5E}x>1ocySQb-c`8HQsK}XJ+%n-jm7#8Q z<;=crned{@P=DUVnf=%@;USfwc~#`her%cWkpD~O9-JxQ*HOmazwWbqtc#0hq0H|+ z+k4`3cFr@pc4eM_FT}^bj-8$JjQLonr_5d$S{E13U776f&Uyyf_d(74vqQT~cs6BdUKKgBL%X=W zm(lwKWvCk!IkT_3xV@KgH?&Un9%rd!+z{K z;USfw{#4}5F77(vJe8qtROHMq?mFQ-m7#8Q<;*_wI^ji?q5f3l%r5Ra;XIY0ZdByV zF77(vJe8qtyo)pYvFn6~REFkNku&?T>x73?hPu&}GyAdYgojjy`csedZNhmflh3^` zA9iuK3FoN{^`|0dc5$}}=cx>Jqbq0jb+-vGstom~B4>7Sw+ZK|40YpOoY{}vCOo7v zG_Q)B*^k{OJft$zjf$Mv#oZ>Hr!v%yik#WS-6ou;GSrQ(oY}?QCY+}-)Sr5s?-R~b znSAbj`LK(-PdHCys6Q1svx~b=I8SA$8=vINe(XNsA(f$-R^-fn>^|Wk|6Jzuc&9Vo z|9Jh+hsV3#@w$|;gl74SE^dpVGJpNB?txaa-L`Chx|l_#7Ya&Hpo;HxbQCndf;Nd*d_uv8`)YX8XCkK6m!aXLM*= z{ZS_GPgg#pi`(jkGI=+;@*y|4zOE{hccUvG@|kNll*zlXXFlZg*8V7y_opi#a(Zhw zl*zmCNj~Jz)_EzD&#NmRa%gKel*zl%lh5HXd2)Kn{N76we>U&Shke~)!s#hP{pre? zeck$+%dbDmWPh7#GGt$OF#9~WUVF7p-i?ZU*w-BJ<6WHDj~ypGq%t(Gik#Vx9Va}bGSrQ(oY{{Z zCp@Gw)Srr+*~J|voToC>jf$Mv#T_S{r!v%yuAJG|9Vfh~GSr`noY~hMC%mXK)Qx(a z*Bv(GJeA4k{#ick$4(O-QW=_QMb7NUP7@wd8R|ww&g|k&6V6i^>PA=2?CVYwUQ`+C zPesn`;!YFJQyJ<;Mb7NvP7}^k8R|ww&g|k&6V6i^>PA=2?BY%n&Qlrc&$~FYA3IHW zNM&eV^*ApR9&#_4!^?RA>uwV3Y4??}E-t=yWq$A3-WMP1;^J#pChx|c`B+~U_eYt$ zKVA7)7Z-O!nYhXNO)%no-Q9Yi||L^jl@51$X z&i~u_(0A2(JfClMKJ)$4g5#?JQsT$_5@~Nd*Z?UpHpHL# z89k%w5F`J!ep`^g0xB`KFTMRe1Pw3twle#5mcX$7gxkAy+9uUdo@_81+MIj1Bo7Vq~5Cxr@U;9{$X` z*Xb)U&i?1+l)&!9$n`Dm?$;3ytuc0}5;1aHi~GH4G<~gMr(cH$nXAR!!8)40*09s> z#Dm<{;_jFo^+Rjee$?SXZfkM(#Ezz~HSF}ikH_V4TKwze#^0U%?}_L8!mTxw82d5) z-lIOT=lh_oYf-{Ze_uSF@07Osp@i*6CmzrDL0i*T!cKo*Jf82Aw)&xj?MEjb&+kpQ zrmuvZekUH!?@hO+uY{fczIZ&pS>5V~61E?o;qm<5bZah3*tzuKG5!J~p1u;}?Cozx z_CSnW-}pO=Ego89>`*0QotJCmJ^VamWhMj&V9^|%8zm%}k{|pbZPN!d06Q|%8{`OjwuuduBp@e-_ zcH&{pRWyAi?DY47#SpY*-;`Bn+rk3Kxk!#QX1^pzNA|MU31`*|{4ePU#; z&ci)swysudj18$ojNI1Q?fiRv=cvRu`}Nh~Gfc@ko!y?iXmVO(oLwbiWS!1#PhK>A ztzoBMhX38BmZtLv!i)_w^~^XZsz*uITBMu#@Y>gRIjPO`a0IA9a|Lm%5_sQ^HTb6H_u* zSG0jj_E80LM{PgQEB`eI%GFLaWflB!4cVbHB z>V`J3b7Fb9SGd30+6il}qH9rNeD>d*9j#5wda3AIl(5tP3=eCJqPZwx=dv#z)+t5( zP{Q`36A$a9qUkGPr@t>A)?7vXP{Q`350AUEfv?k7Vx0ZY!;IUz@zo|~y;O89N{sWr zJNMb0m^D|?)hc28(TRt3ebMxlu+#qx4{~gGv`$Klb6fwacVbG`>F)OAMbB)lF*c+U zF>+gXwB@(l z-eJOvDnqX=6*;r7J4`rFWvCk!IkT@jOgK+vs2deIv#&c$I8SA$8}H)G4(%}EA(f$d zb>++s?J(gXm7)GrEXUe4KEe%H(tJ%ZFXual&~jL;dN>nSI@H!iy?H z{i(>AUEFcPc`8HQsK}XJ+;PHrDns3P7iack#|aOq49%-6XLe}ojsyDsR2k||MTYF_ zjuT!~8R|ww&g|lj6V6i^>PAJ*?Bb3S&Qlrc#{Zx5`Q?7~>#iTW&OezsIp-PuZz=Pf zyZDUvURZZoSzj0PQReqvzCX{$`my-mqf9=pu6(Q?i@Tvr-i@w&tRIWJp-kS5u6(SE zi@Tvr-ihd59ejV zLn@QcV&8n&F)kCXQW@%4Mb7N&7Pt2@dM}|2b)zC@_H~Qfdl`2_>tydUYcgbCx46BR zaW}M1-i?ZU*w-y?pJ&_+t&?}7DpNgE>#hoXdr!v%y zik#V1o+q5AGSrQ(oY~i%C%mXK)Sq{8W`}m3aFxo?yee{LKX#t*kjhXuDspB&cAoH% z%1}2da%LBIo^YPZP&X=aW*2v!aGuIgH+piuOgK+v@^19y!!GVJ;XIY0{#4}5F77hn zJe8qtyo)pYvCD*qREFkNku$rm%Y*RD+Vx^Z((xDP|?;^OO4Chx|c`B+~U_eYt$KVA7)7Z-O!nY*UY(u6)?(-Q51nxIbDa?@vWO?CWlB z?`7N#t&?}79-sS!^He5(ztNWu`^@`<(^H1})0Hzjy}R2B8vWf-hWb;HGyA%`+Y1_Z zL+fPkN#4hh9opUPy^QCjb@F*t$>-IR&*3q7@@&fFo_61S*k>LloToC>v5K78 z*R8L){Q9Fz_P41fL-uut3FoN{y>3+G%)ah0;XIY0Zgl0$PVX?`MU|ocROHOQ?l9pz zm7#9Di!(d4!-R)ahUQg~Gdr}ygojjyx>1oc`?|w~^Hheq(UbFP#K}u2lXs&pA9iua z3FoN{^`|0d>ng7==LH-e##5Q!K677utc#1UU75Ta-^Rx}w0Ne<M&GW`}lidoSazYMuP~-jxsgx|7?V8TUu) z^_ZROG|H?&S7f#@*05c{eKZVPAK0`#j@rXq~(p75T8QJGp(H zaW}M1-i@w&*w>xhUeLHdS|{(%d-yC99#WayOZ4T#j&YgrY|2o7DspBQw@f%sWvCln zIkT@@CcLOJ)Srr+*~Kjr&QlrcMn%r-;+6^LsSI_aB4>7S%Y^e(hPv@d&g{^Z30J8M z&9owCc4*6lt5k-%QIRwIv1P(TDns3<$N41ocySVd&^Hheq@h;Bn$IcTTQW=_8HO}^4R! zeXSnP=U<%=J@4oeTKL5YV zhrXxQ<2nE8eCWGqJ)Y0MIv@JJS&!%Q|8_q9gvVDyq{NT8)AinXupv@nY=}SaGkQkV zAx3^|{ncdt3i$s|+|2WBW$V{a!czZpJgh&8{vAr#SBFkKtUZdRuY{d`9Uj&kMYC1H z&bAH@YlWiODq&~aiHCJk(e#zD)9=K?8mVadO4#Y|i-$E@( z|2*u6-C@|Bm^D|?)haPI#Giy&n;2OqfBs{1wOYgW<6C%;mpZ!N%0#o(8g{my;XzL6 z=zhr(O-^gr$#vpEUh3$6ITQ6mYuJ9&;X&r==38BmZtLjo_Y?I)YuJ9& z;X!We=DS>w=IZF~*%M7)YuM@c;o(n2e4V}$d?L*7G-jFCUtFq(_juyg6egRGN30Ws=_*0BAk!-LF~Kff@VzSgkQ@5F=5l|REU z>W9{_{iwr(%#}Z-Fq*#Bu+y)@gS?bKhcKGH*09s>#DmP0KZ`Kxht{zDsKbNIl|M-^ zn!eVs)BpQC{CRh;)Rh>S|2%d(kcI1&AjjrU1dJM_HO3BAB1Y!QpZOO}Uu)Ru*Wp24 z%AeR5O38Bm=E|Si7xhDH*nZUEL0-zA%NI>wYuM>`;z8!hpUoHbLu=T6)Zszq z%AevFOA!;q86$s!UNjf2Vdv6`2RS8wieA(Ytzr97g@->0?sc|GjFbI&{I-Q` zV5J0kI)4&g)DNvOHl!CZGFSejyQm*p!}g;N4>DK&EW2p>TEkAi6Av<1{ye*=A6moq zqYe);SN?RoX!=^iPX8S|$QYgR7rIJ}Q(52hcVbFT>5RY7Rl@h94pTB$XZ(fkpGn+b z?&9tL9ZJ~QMm(&SQbIh&SF($9Td)04V&wJncwb;`U~OX7e=A9Z+; z+q$~5Iil%n4Lki#JjiWb-A=ctA6moqqYe*pTUWR9FPgsAu+y)@gS^xgU7r%;>{lbu zi7A<@E80LMd_Vp^(;HeRB`oz`JjfW`(84L<`_YLhnX4PxKqY)X>M$jfcS9Sfgr9yV zrev;eXakk-{iwr~%+(ETpb~!ib(oTux}ob+!cV^wQ!-aKw1GM$i^bVCcLgr9yNrgyY~O4#Z5;z8!>jy6yU-;X*>$xGeQ^(o<}--#)it2^32C44{X zFeNW_N7tu>pMEE%WUlUL1C{Xocn4E*N_X^hO8B|dVM@m6juuV{Km9sP$xGeQ^(o<} z--#)it2^32C44`sFg-k6AN}G~nf(51o%xWrTCZK1!^4TK_c3_=EyLdVkoj8qD3kZ6 zD<866Yd4h1yYWdr^I_+C7#pJ`2B-2 zxvTjsAO2f>oOsWp49&D6XZ~Bf?xZ6(s|vcmJ>Q6<^{2k?K_`S(? zH?&Unezh+{{vPu*{3d0)KUyd6&%5}r8$3<;LuKf1K}F8&$4(O-QW@$-Mb7NUP7@wd z8R|ww&g?2r6V6i^>PA=2?CVYwUQ`+CPesn`;!YFJQyJ<;JA~L%)V}!@S@64e=2fj7q?6}Pi3eZ6*;quTa5EOJpRAu{aM!2fe*p`7M1y{ zE8;W$UTpo(Yk!^|XPb{Q>mHr`@p(FChx|c z`8=J`c7K$~`_q-r(;01dLz%oAUHLqH&~`VJ$-D7MK2JxpJuhYQd3ELUbYa`wP$uuj zUilm!R+PM`GQaOd5^C6$PUb`~euPvSVkgr>>U75TaUHOo&Tf3o5-i*O7)$cLTY`b*YvKU@6zqfFk7dVJPz3~27kj&6Tu+#juzy-%pgkbT{F_Vd=~3uWlFr6Oncb>kV^+uhJQ z`RhhSKJ4qpGq$(8p>^_ZbmhZNZ#>g_yFXed?@vWO?Bd2Vzqh-gb@Fb!ix2y;@r>>5 zd1;+|UiJ8lXGm|&U77r|Ltj4Z;>I(!xBH`Yve%8i4B6L>=S*++N9*MMsmO<2<#-PF zb~m(6-i?ZU*u{*U?2$cJ6rc%JumH?&UPjc?<_o^3pW8)dy+uhJQc{eKZVHY=^vAx|5t&?}79-r|H>8-gdlRM9S^I@Mk zp2NM}F|Cumw$x^_Zyo(R}vGI)U?RjaPd|nm# zupb-G*xv4j*2%k3kq>5ZfKpn8(sOZiyP0_-tLdq$@^2054*VWjP31iXq~(p z75T7>8_(h1?uORMyHStNdE)ox%H+;--+b6ro+p0)t_*eTU7XpEt#{g`dr&At^Qy>@ z{n&Zp_vXq_H!5=Z?{#12ugCNG|6M-xzFm*!{J)(Ky|32e`FyMM zvEOySzP{@5eE!w>*zc-e=dZ`}`F}ef`+f84eD!!f-|BqqcgnBx*W>y8znzai!SZ#& zN{qhn=kaYaIl*2DHatp<4e{q%M$f2s5F<0Q`u_a2Nr`c8>odC!G4e78_f2`!Lai~* zzY;OBLI?aVT#0e^>vO*oQ?g2j$9d-Tw?T=qA(e=cQ#$-o!p^o64>C%JUrN~N?~4Z+ zDSs|x^v+Rh*ap?%K|ac#{1{DNYuM@keIEYIz*p)@jLd%?pVZ01^-7R2@+UY(4bmE8 zhbj>xFXhi@jHa(O?DXsKAW!E{5R9g;HSF{|@gQ^MPg#ump*3tj>hK^>=g(SZ z^gHn&x8=`UjQXK9Y(MJoAh+dDON^$kHSF}?!GnyEKdCU9i`KAnsl$Vekw5n^n!eVs z)9=H>pWOF4eI>@(|2+1(kPWPqAW!E{=8O8FHO7WiB1T@ypG_D|Uu)Rucj7_j%AZdd z^+Rjee$?SXUdo?97)@Vm*y(rTLFUSzLKyW!YuJ9gg9jNSe@b997p-CEQilf_BY#$4 zG<~gMr(cH$c`1JyU^IQLVW;1T2bn8>B4E@Htzr97g@-?}?sc|GjFbI&{7#2lU!??j zI)B<+)DNvOHl!CZGFSf8zNjBs!}g;N5Ass}T)t@fTEkBN9X!Yw`SbUpx%_|ESYGaV z?f+MluuT6P4{MB~e}@wGS=ot)^-|IFm9W$A#KU^2X!=Un>FG$E`PilLez7pf?e;#+Kv97N>F>CUot5srbh(EXQ&k?guDf)LPVJBCIhc!mg zY?ZLH-4_qCPX6Szs6kr8HmD8{GFNAJuf1scTEkAi4i7R{XLql?X!=^iPQMcma$9G2 zH@>JJTEq6E4i7R{=U+>VV=IZ=Q2|N8NJTB;^lo%)b^LQ6TChvO^Q; z&wl-zt%RR`9b)9AF7A|wX!=@XoPRH33t7N%sKF6il$ z@UyML^om|e2|L@p@gQ?`MH{GuZ%`ekWb&?P1C{X8ufvqQ)D>Ny5`Oxfn3B1=q778S z_oEI|@={kcS4#Nl*I`Ot>WZ#U2|xYMFeRsSMNg-MpIjZLWSy>P@|5t?ufvqQ)D>Ny z5`Ox9nBLF^Dq*MJiwAkB8@fIvd_OudC3AH{8>ocuM;)eQu5M@pmGINA!<4+#4PBoS ze){iVO2+7h7ETF2mrhK{Dc#W1DdGE3hbeif8@fIv{PgQEB`B@&(+u99f@@{nHL!NEzhBA3K zKFNp7*g7v|@_BXTL*8udhBA3K_RD8&2YEJS{`D|>+g__LANF;J3FoN{^`|0d_I2xX zhF@Eh$zNM4@?l?hm~fuT(CbE5&g}FK6JAsq>Q6<^?CTB_&Qlrc#=AJPLpw}(NM&eV z6*;p*J4|>;WvCk!IkT@jOgK+vs2g25v(r0Fcu{4jKlL~tC!D7;`P}>RVHbCtaGuIg ze=2fj7k8X+p2|=+x^iY;cbxE|%20pa#hLxsal%6?L-VT0nf=&t!b2)U-KfZ!UEFcP zc`8HQsK}XJ+;PHrDns4q%9(xLx>JevT_{8SsmPFB+;PHrDns3<$N4njJeA4k{#ick z$4(O-QW=_QSI+FvP7|(D8R}0(&g{od6CP3->PAJ*?BY%n&QlrcMn%r-;!YFJQyJ<; zMb7NvP7}^^FPY2BUG>*rJ6MMM%2;0)U%N8De=D>vKGwy>*RD+7jZgBiek`7sGWooE z@>!gRjJl!B^Zntz_*fSgU%N8d>&D`o@V*#Y7Z+c&blMZv*3QD3f=iA|Li+=Lrv~ z482dN$eCT-dBS-rL*1yznO)p@!g(q~-RR1hecgG&iz-9?smJ*;;YF3n=iZkOySU4Q z^HhfV^DfTp$1W2dQW=_8Mb7LGFB2Y88R|ww&g|JP6FyTJ>PA=2?BXsH&QlrcPesn` z;w}@;QyJ<;Mb7NvE)&jE8R|ww&g|kY6V6i^>PA=2?BXsH&Qlrc&wDsuCp@Gw`7HYK zVLx`A@Q}(-e=2fj7k8a-p2|=+DspBQcb#ya%1}4Da%Nw5o$#W{P=6|NW*2vzaGuIg zH!5;w7k8a-p2|=+KFOIK+I7NJDnm2Q6n+w+ZK| zOg{I%eAva^CY+}-)Srr+*~Q%^oToC>4a@l&oEP93*2q|27yp};`ThITeetm_F1~hU z@@{;RkM(2myp+l3)s>I+V{tc>$-B{&kM(SEH-B2d) zMo&I>=RBisDD(6Z`{H9=Tzu`yWUm`{=Y;pgkbT|VdC{1U*2z2eE<-<hY9DY40WR-XZCf63FoN{b)z2V z)pnC}P$r-IzWK1PTdgp6OqtAU)nv%7@;Koq+TvHmdr_b8J+-%rld_F-uK zSbSZ|*O=7$cO#dGT|YWq0bjxIkT@@CcLOJ z)Sr5s&lAp5nSAbj`LK&SPdHCys6Q1svx_@VI8SA$8(lfG&pc0fQDvw<@8ZmU>^$Ki zm7#f69;;Ouy^Wm;kLUBR&WGQ-=GU+P{&(}C_m+A* zpI>!8^j=ku=kxz|KJp zdOV+Rbw2(C$5#WS#CWf$pU1b&5F@*_?qkef|CAWpvA#NV zB1U$|pFtTt8??sQkV?eJ4f#_hqv>l6JNhK`rZ^gHn&BjwM8jQXK9Y(Kt}$9=fR^#4 z=k?Fyv%GbE-HBOq6*-2o?>zSgkQ@5F=L*2&!kC+dgRu>GjRgWT51-IF_-zSgkQufv1P z)ydtxJDR@Mu+#6vgWQ%sB{1rT*0B9}2M;nv{=~p&E?UFRr3w#!THWhxl^7@c^Z0y2 zd-8fE$mIF+{GtYFjj=@4_C-z0t*BW;Eop_MB@~6^8{m>e=A9Z+;x$@`oMbpFTM@8CgB$)Bk(M7foMl z*y(rTLFUSzffw~dYuJ8N;o;A5d!4Nk<79sx-)55ytdt;6=g+Z=`k^((hV&vv=E|RC z7xhDH*nZUEL0-zAL>En8YuM>`;z8!hpL`efLu=T6yn_chC4cH%G#9O5=Te6U8KX1q z$x~vS{raB24pZ_{XWWyggr9yVrev)(bxOfTrRl(5t9 z#e+=V<#F1;csj%D=LRKwKk5)8FLl9R`TlR~c$L~)_ z+y7D}#x@`S`vEQGNwy#AAJNGjRgUr?Q zu20+3*BW;Eop_Mjdft6%yB}J^_M-}q=be(aW~;(lmJw1%BaCmv*-o_BrP?uXW}{iwr(%+>R*PutVi8g}}1c#xNR-t}pF`dY(I zzY`BKSI@gXZTDl(Yg}G-xq4#XoUmRh`j;wUpZlG7ST7Y#UkN+?eetkfD(Z(4wjZD1 z@w`LPUw@Hb=c2?omGQ1m9f(A)=NeGP{Q`3 z6A$a9qUkGPr@t>A)?7vXP{Q`36A$a@qUkGPr{9SOnXBiWqqg5CYYp3vckm#m^t^}B z_FS}vol7Sk+m3Rb@`=)o$bDOklVUEPDdW^?h*a1RKhl>4i7R{7k9tD zX!=^iPX8S|$SGaiz2&00Xbn4;Iy}f2UH*HA_w9FVTEkAi6Av<1m;c`3eY+o8!}g;N z5Asr%|K6{Bd-__#PQMS2E4nQu#@YWo{+5yrtdt;6cm3}j-nU*Il<@ti!<4+#^}ly` z-=4nK80X)M7`d%0+CU}7cC3Fr-occN(G@M65`Hdqn36HNqJ>k!PrnmWGFMl$flBy( z)L}~I>WVf{2|xWhOvy`K(e)|er{9SwnX4<>KqY)XsxZBwxl+Q;wigfbQa5ycO89=f zgDDxb8(KIe{9HOQC1Z3$r=*1MM;)f*rEci@lr=w_ zqYhK@Qa5ycO8Dt_VoK)fhBi$xGeP^(o<}|M!{R(ZVTVsrTYR#^{a~P6^+S zPE5&M-O&ar;rsD^rq`EybbIRmTf%y&XbmOC>E50D>`u&@tLSQ#u>I)7!PteKGti+*RD+7jjnvi6Rxi<%H-YX%7>iT+6`s$ zZtR&4S+%u4%H;j|Bp>o%>%5f7=hc-DIk2@G%H-YX%7;AM+6`s$ZtR&4nY^_>%H;j& z$!DEBc|T?T^{{{2UaK!3_L+wXFRBdnry^(ebqBXYGV-FzP&X=aW?#3yp7P%vW%9o} zpX9@y?J(ggm7(W*Mb7Nd4ig?y8R|ww&g|PAJ*?CTB_&QlrcMpw@4^bQkV zR2k||Mb7N&4inB(8R|wo&c_MosZ2ii&+=hEcAW5#%Fs+Ja%MkvobZs!P&c}AW`}m1 zaFxnXe=2fj7k8X+p2|=+DspBQcbssZ%1}2da%LBIoN%7XP&c}AW?#4d!iv5>RfhUg zks-UdyAQt4Ob?gdtW~6;!YFJQyJ<{SI+F~P7_{K z8R}0(&g|k&6V6i^>PAJ*?BY%n&QlrcMn%r-;!YFJQyJ<;Mb7NvP7}^k8S2I-IkO)- zO?XIUXr>i8vmZN6ct~Za8{f_O_HzII^%qOl#VKR&CAeoki*ue)HPQ)Vv=t&5B2uFUV>6z_|Vb#d{vE0cHQlYFcni|3_GKCiBPtRIWJp-kS5u6(Q? zi@Tvr-im5D)M1pcXs9;<%r5RS;XIY0Zgl0$zV0&NMU|ocROHMq?lR##m7#9Di!=MN%Y=tihUQg~GyAd2 zgojjyx>1oc`?1S}hg62TQIGR=!g(r_&wbx~*u`BZoToC>v5K78#a$EUGSrQVoY}=)C!D7;)QwMaWdJ@w*xC(c@^0*z5Ba*aKg#6&>B@&(+}aIg@^19xb9hXi zoSrhd6Yk50edb}pc`8Hw>B^a%-eJOvDntEw7iV^8>)%NJd!bDBUZN&Lc4&tQ52*}2 zmn(8+hjy6okjhXuDspCDcbIUV%1}2da%Nw5m~fuTP&c}AW?y%haGuIge=2fjUw4>r zp2|=+>TzCeH+_axCZGFf`LG{5PIyRVXr>i8v->(uI7Vft8(lfGt2|CPPi3e-6*;qu zJ5D%HWvCk!IkSs9PB>3xs2deIvx_@UI8SA$8(lfGuRBh7QDvw<6*;quJ5D%HWvCnP z;>>>RIN>3cp?THge46l(%H(tJ%ZFXuX~KE_Gntk8kNdyXfQ3-Y>)MscyU~@;=;F4zp-kS5u6#xpx77`0@@{;R&*;at=A}$NuRZe_{n%E2 zl*#+kmCxwMwz{EA-i@w&Mi;l$4Q29f^yIS`=NWfHncvP+e7r+jCLE(O)F1Y=H5szc zT+Ck3t>>54$^JIgWXQg5G5b8Xx}kOQZoG>RJG8~@z1*6Y*2(8pkqW0?I zyU~>oJH5s1&)n*d*2()*kq`U2#q7P@>W0?IyHSx3`?|&Kz1-@C*2%k3kq`U2#q9Ik z>W0?IyU~-+dBTe-lY6bceAw5WC%mXK)Sq{8W`B5|@Q}*Tyee{LKX#t*kjhXuDspBQ zcb;&b%1}4Da%Nw5p75f|P=Bg%9`AP*eeTrb&-;OO{x2>U{Wpa(?~#?|(NR zdatX;^ZEVLeCYkA9?$3V?R@C{pdQcXTb&Pm&#lMv`B&#d-(~CZeE!w>(D&7PJfHu! z^P%sY^>{wt>U``8kC7o#!v0dH7Z3J7N{sWjCw|7ymv;~&FJ(`TjQ<^4!%nUf5Ar(e zPP6JTGqWY40EUmdi@IR8q-$SK*=CgbUA4Lki#JjglO6DQ+-Xbszs zIy}fY*)t{M>1z!;{Z2f{NZB(Z<9=uj+mAXt$XD4@A>-+54Lkk6&%>TM7*SVZWd8H` zjREcKtCS#PWY2eu`%!g`gS*@MI$L`!N?3Ch@laxXeXwUCUoekfu4(TRsOSJCv9u+#6v!+NP``bya8?~8{uS5ZHdu>JT94{MB~ zxhP@h(us#PM$z<@u+#6uW3@Nq&WzXTD>2Ug=dmwiU&P3M`O^ra25F74LzRe;$ve6G z>qOJn8g}}fc#yd|xqWO=KeUGJM;#tyu1@YQI??pChMj&L9%Qag?jAVN^tFba{yTV( zQ#!eOZbx&`8g?$7c#u;%x%+NM{m>e=A9Z+;xjMN!Ye&=98g}}1c#yd|xqD|v)7Khy z`h9r#69HeRuf#a}pU3ALvVoNnIv6YHXWXbszsIy}fr`E&iE z>1z!;{de#nW8}~8i{_#=>|E;bAYSWHSF{|@gQ^MPvDFCp*3tj>hK^h<Z^y}~-FXd0si>9wN?DRYFAamtU(u?|`HEchs@bIU&z0OvNak4*;Z?nnu^-7S* z^XJ?}4bmE8hu%YsjFCUjE}Dzhuyd)ygN%_su`Zgv*09sB!-Kq(Ka(z+zSgkQ@5F=5 zl|OSX>W9{_{iwr(ywn+Y{wXoeetpkhhbeifGw$nC!cV^wQ!-a)-1(=3??)Y`ZOMP!V$e>;D{&Y(C2GwCoUh0Cszg5CdzYbIKQWyMntrC9votToj zy5R3`mGJ$j!<4+#1%H35gr9yLrsSnAXs(p-)9=KT%+&>LVCTf~T7foMljPw5#F|tlKw9wN?DXsKAaiwdd-9^`YYjX7Iy}f+-Q145X!=^iPQMcmGFLZrTS|=WSdBm( zrsU~v==zlK)9=Idj&4f{JN;ff$Xwmg1}fqE@foJ%lvo8Lzb)%H-YX%7<*%+6`s$ZtR&4`LeY?%H;j&%7<*)+6`s$Zgk~CCT;D8 zGI=*X$%ow6Ixl7Nd3EJO-fQiKGI=+8@>wTOE>4-;Rrck>F77blGnJwKROHMq?l9pq zm7#7_ew}|dV_jVQzopFYx$ldQ^=$FAE0cHQlYFfE zisz+FKCiBPtow?)p-kS5J@c_HF7A&qd4Ia{u`Vv|hBA3Kdh$6spBZ&SnWuBu7a!}{ e;%iqXd)+uX-`j_w^=$EVDU)}jE1$nS -#include "State.h" -#include "BMP390.h" -#include "BNO055.h" -#include "MAX_M10S.h" -#include "DS3231.h" #include "RFM69HCW.h" -#include "RecordData.h" -BNO055 bno(13, 12); // I2C Address 0x29 -BMP390 bmp(13, 12); // I2C Address 0x77 -MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 -DS3231 rtc(); // I2C Address 0x68 -APRSConfig config = {"KC3UTM", "APRS", "WIDE1-1", '[', '/'}; -RadioSettings settings = {915.0, true, false, &hardware_spi, 10, 31, 32}; -RFM69HCW radio = {&settings, &config}; -State computer;// = useKalmanFilter = true, stateRecordsOwnData = true -uint32_t radioTimer = millis(); +#define CALLSIGN "KC3UTM" +#define TOCALL "APRS" +#define PATH "WIDE1-1" -PSRAM *ram; - -#define BUZZER 33 -#define BMP_ADDR_PIN 36 - -static double last = 0; // for better timing than "delay(100)" +APRSConfig config = {CALLSIGN, TOCALL, PATH, '[', '/'}; +RadioSettings settings = {915.0, false, false, &hardware_spi, 10, 31, 32}; +RFM69HCW receive = {&settings, &config}; void setup() { - recordLogData(INFO, "Initializing Avionics System. 10 second delay to prevent unnecessary file generation.", TO_USB); - delay(5000); - - pinMode(BMP_ADDR_PIN, OUTPUT); - digitalWrite(BMP_ADDR_PIN, HIGH); - - pinMode(LED_BUILTIN, OUTPUT); - pinMode(BUZZER, OUTPUT); //its very loud during testing - - pinMode(0, OUTPUT); // RASPBERRY PI TURN ON - pinMode(1, OUTPUT); // RASPBERRY PI TURN ON - - - digitalWrite(LED_BUILTIN, HIGH); - delay(100); - digitalWrite(LED_BUILTIN, LOW); - ram = new PSRAM(); // init after the SD card for better data logging. - - // The SD card MUST be initialized first to allow proper data logging. - if (setupSDCard()) - { - - recordLogData(INFO, "SD Card Initialized"); - digitalWrite(BUZZER, HIGH); - delay(1000); - digitalWrite(BUZZER, LOW); - } - else - { - recordLogData(ERROR, "SD Card Failed to Initialize"); - - digitalWrite(BUZZER, HIGH); - delay(200); - digitalWrite(BUZZER, LOW); - delay(200); - digitalWrite(BUZZER, HIGH); - delay(200); - digitalWrite(BUZZER, LOW); - } - - // The PSRAM must be initialized before the sensors to allow for proper data logging. + Serial.begin(9600); + // while (!Serial) + // ; - if (ram->init()) - recordLogData(INFO, "PSRAM Initialized"); - else - recordLogData(ERROR, "PSRAM Failed to Initialize"); + if (!receive.begin()) + Serial.println("Reciever failed to begin"); - if (!computer.addSensor(&bmp)) - recordLogData(INFO, "Failed to add BMP390 Sensor"); - if (!computer.addSensor(&gps)) - recordLogData(INFO, "Failed to add MAX_M10S Sensor"); - if (!computer.addSensor(&bno)) - recordLogData(INFO, "Failed to add BNO055 Sensor"); - computer.setRadio(&radio); - if (computer.init()){ - recordLogData(INFO, "All Sensors Initialized"); - digitalWrite(BUZZER, HIGH); - delay(1000); - digitalWrite(BUZZER, LOW); - } - else{ - recordLogData(ERROR, "Some Sensors Failed to Initialize. Disabling those sensors."); - digitalWrite(BUZZER, HIGH); - delay(200); - digitalWrite(BUZZER, LOW); - delay(200); - digitalWrite(BUZZER, HIGH); - delay(200); - digitalWrite(BUZZER, LOW); - } - - digitalWrite(LED_BUILTIN, HIGH); - delay(1000); - digitalWrite(LED_BUILTIN, LOW); - sendSDCardHeader(computer.getCsvHeader()); + Serial.println("RFM69r began"); } -static bool more = false; + void loop() { - double time = millis(); - - if (time - radioTimer >= 2000) + if (receive.available()) { - more = computer.transmit(); - radioTimer = time; - } - if (radio.mode() != RHGenericDriver::RHModeTx && more){ - more = !radio.sendBuffer(); - } - if (time - last < 100) - return; - - last = time; - computer.updateState(); - recordLogData(INFO, computer.getStateString(), TO_USB); - - - // RASPBERRY PI TURN ON - if (time / 1000.0 > 600) { - digitalWrite(0, HIGH); - } - if (computer.getStageNum() == 1) { - digitalWrite(1, HIGH); + Serial.println("s"); + Serial.println(receive.receive(ENCT_GROUNDSTATION)); + Serial.println("e"); } } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp index a44acb50..57d80725 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/test/ReceiverTest.cpp @@ -25,8 +25,8 @@ void loop() { if (receive.available()) { - Serial.print("s\n"); - Serial.print(receive.receive(ENCT_GROUNDSTATION)); - Serial.print("\ne\n"); + Serial.println("s"); + Serial.println(receive.receive(ENCT_GROUNDSTATION)); + Serial.println("e"); } } \ No newline at end of file From 2b783deecde23ed8b4ac1263dfb362720ef0dd04 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 15 May 2024 16:54:06 -0400 Subject: [PATCH 11/41] minor changes --- .../Teensy-Based Avionics/include/Radio.h | 30 +- .../lib/imumaths/imumaths.h | 31 - .../lib/imumaths/matrix.h | 185 ----- .../lib/imumaths/quaternion.h | 214 ----- .../lib/imumaths/vector.h | 184 ----- .../Teensy-Based Avionics/src/APRSMsg.cpp | 432 +++-------- .../Code/Teensy-Based Avionics/src/APRSMsg.h | 225 ++---- .../Teensy-Based Avionics/src/APRSMsgOld.cpp | 372 +++++++++ .../Teensy-Based Avionics/src/APRSMsgOld.h | 227 ++++++ .../Teensy-Based Avionics/src/RFM69HCW.cpp | 733 ------------------ .../Code/Teensy-Based Avionics/src/RFM69HCW.h | 87 --- .../Teensy-Based Avionics/src/RFM69HCWNew.cpp | 324 ++++++++ .../Teensy-Based Avionics/src/RFM69HCWNew.h | 91 +++ .../Code/Teensy-Based Avionics/src/State.cpp | 14 +- .../Code/Teensy-Based Avionics/src/State.h | 6 + .../Code/Teensy-Based Avionics/src/main.cpp | 14 +- 16 files changed, 1221 insertions(+), 1948 deletions(-) delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/imumaths.h delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/matrix.h delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/quaternion.h delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/vector.h create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h index 9e8ab573..2f46df68 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h @@ -28,18 +28,34 @@ enum EncodingType ENCT_NONE }; +class RadioMessage +{ +public: + virtual const uint8_t *encode() = 0; // use stored variables to encode a message + virtual bool decode(const uint8_t *message, int len) = 0; // use `message` to set stored variables + virtual int length() const = 0; // return the length of the message + virtual ~RadioMessage(){}; + +protected: + uint8_t len; +}; + class Radio { public: virtual ~Radio(){}; // Virtual descructor. Very important - virtual bool begin() = 0; - virtual bool tx(const char *message, int len = -1) = 0; - virtual const char *rx() = 0; - virtual bool encode(char *message, EncodingType type, int len = -1) = 0; - virtual bool decode(char *message, EncodingType type, int len = -1) = 0; - virtual bool send(const char *message, EncodingType type, int len = -1) = 0; - virtual const char *receive(EncodingType type) = 0; + virtual bool init() = 0; + virtual bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) = 0; // designed to be used internally. cannot exceed 66 bytes including headers + virtual const uint8_t *rx() = 0; virtual int RSSI() = 0; + virtual bool enqueueSend(const uint8_t *message, uint8_t len) = 0; + virtual bool enqueueSend(const char *message) = 0; + virtual bool enqueueSend(RadioMessage *message) = 0; + virtual bool dequeueReceive(RadioMessage *message) = 0; + virtual bool dequeueReceive(char *message) = 0; + virtual bool dequeueReceive(uint8_t *message) = 0; }; + + #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/imumaths.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/imumaths.h deleted file mode 100644 index a168750e..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/imumaths.h +++ /dev/null @@ -1,31 +0,0 @@ - -// Inertial Measurement Unit Maths Library -// -// Copyright 2013-2021 Sam Cowen -// -// Permission is hereby granted, free of charge, to any person obtaining a -// copy of this software and associated documentation files (the "Software"), -// to deal in the Software without restriction, including without limitation -// the rights to use, copy, modify, merge, publish, distribute, sublicense, -// and/or sell copies of the Software, and to permit persons to whom the -// Software is furnished to do so, subject to the following conditions: -// -// The above copyright notice and this permission notice shall be included in -// all copies or substantial portions of the Software. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS -// OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING -// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER -// DEALINGS IN THE SOFTWARE. - -#ifndef IMUMATH_H -#define IMUMATH_H - -#include "matrix.h" -#include "quaternion.h" -#include "vector.h" - -#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/matrix.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/matrix.h deleted file mode 100644 index e71b2db9..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/matrix.h +++ /dev/null @@ -1,185 +0,0 @@ -// Inertial Measurement Unit Maths Library -// -// Copyright 2013-2021 Sam Cowen -// Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) -// -// Permission is hereby granted, free of charge, to any person obtaining a -// copy of this software and associated documentation files (the "Software"), -// to deal in the Software without restriction, including without limitation -// the rights to use, copy, modify, merge, publish, distribute, sublicense, -// and/or sell copies of the Software, and to permit persons to whom the -// Software is furnished to do so, subject to the following conditions: -// -// The above copyright notice and this permission notice shall be included in -// all copies or substantial portions of the Software. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS -// OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING -// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER -// DEALINGS IN THE SOFTWARE. - -#ifndef IMUMATH_MATRIX_HPP -#define IMUMATH_MATRIX_HPP - -#include -#include - -#include "vector.h" - -namespace imu { - -template class Matrix { -public: - Matrix() { memset(_cell_data, 0, N * N * sizeof(double)); } - - Matrix(const Matrix &m) { - for (int ij = 0; ij < N * N; ++ij) { - _cell_data[ij] = m._cell_data[ij]; - } - } - - ~Matrix() {} - - Matrix &operator=(const Matrix &m) { - for (int ij = 0; ij < N * N; ++ij) { - _cell_data[ij] = m._cell_data[ij]; - } - return *this; - } - - Vector row_to_vector(int i) const { - Vector ret; - for (int j = 0; j < N; j++) { - ret[j] = cell(i, j); - } - return ret; - } - - Vector col_to_vector(int j) const { - Vector ret; - for (int i = 0; i < N; i++) { - ret[i] = cell(i, j); - } - return ret; - } - - void vector_to_row(const Vector &v, int i) { - for (int j = 0; j < N; j++) { - cell(i, j) = v[j]; - } - } - - void vector_to_col(const Vector &v, int j) { - for (int i = 0; i < N; i++) { - cell(i, j) = v[i]; - } - } - - double operator()(int i, int j) const { return cell(i, j); } - double &operator()(int i, int j) { return cell(i, j); } - - double cell(int i, int j) const { return _cell_data[i * N + j]; } - double &cell(int i, int j) { return _cell_data[i * N + j]; } - - Matrix operator+(const Matrix &m) const { - Matrix ret; - for (int ij = 0; ij < N * N; ++ij) { - ret._cell_data[ij] = _cell_data[ij] + m._cell_data[ij]; - } - return ret; - } - - Matrix operator-(const Matrix &m) const { - Matrix ret; - for (int ij = 0; ij < N * N; ++ij) { - ret._cell_data[ij] = _cell_data[ij] - m._cell_data[ij]; - } - return ret; - } - - Matrix operator*(double scalar) const { - Matrix ret; - for (int ij = 0; ij < N * N; ++ij) { - ret._cell_data[ij] = _cell_data[ij] * scalar; - } - return ret; - } - - Matrix operator*(const Matrix &m) const { - Matrix ret; - for (int i = 0; i < N; i++) { - Vector row = row_to_vector(i); - for (int j = 0; j < N; j++) { - ret(i, j) = row.dot(m.col_to_vector(j)); - } - } - return ret; - } - - Matrix transpose() const { - Matrix ret; - for (int i = 0; i < N; i++) { - for (int j = 0; j < N; j++) { - ret(j, i) = cell(i, j); - } - } - return ret; - } - - Matrix minor_matrix(int row, int col) const { - Matrix ret; - for (int i = 0, im = 0; i < N; i++) { - if (i == row) - continue; - - for (int j = 0, jm = 0; j < N; j++) { - if (j != col) { - ret(im, jm++) = cell(i, j); - } - } - im++; - } - return ret; - } - - double determinant() const { - // specialization for N == 1 given below this class - double det = 0.0, sign = 1.0; - for (int i = 0; i < N; ++i, sign = -sign) - det += sign * cell(0, i) * minor_matrix(0, i).determinant(); - return det; - } - - Matrix invert() const { - Matrix ret; - double det = determinant(); - - for (int i = 0; i < N; i++) { - for (int j = 0; j < N; j++) { - ret(i, j) = minor_matrix(j, i).determinant() / det; - if ((i + j) % 2 == 1) - ret(i, j) = -ret(i, j); - } - } - return ret; - } - - double trace() const { - double tr = 0.0; - for (int i = 0; i < N; ++i) - tr += cell(i, i); - return tr; - } - -private: - double _cell_data[N * N]; -}; - -template <> inline double Matrix<1>::determinant() const { return cell(0, 0); } - -}; // namespace imu - -#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/quaternion.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/quaternion.h deleted file mode 100644 index c5b907a1..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/quaternion.h +++ /dev/null @@ -1,214 +0,0 @@ -// Inertial Measurement Unit Maths Library -// -// Copyright 2013-2021 Sam Cowen -// Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) -// -// Permission is hereby granted, free of charge, to any person obtaining a -// copy of this software and associated documentation files (the "Software"), -// to deal in the Software without restriction, including without limitation -// the rights to use, copy, modify, merge, publish, distribute, sublicense, -// and/or sell copies of the Software, and to permit persons to whom the -// Software is furnished to do so, subject to the following conditions: -// -// The above copyright notice and this permission notice shall be included in -// all copies or substantial portions of the Software. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS -// OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING -// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER -// DEALINGS IN THE SOFTWARE. - -#ifndef IMUMATH_QUATERNION_HPP -#define IMUMATH_QUATERNION_HPP - -#include -#include -#include -#include - -#include "matrix.h" - -namespace imu { - -class Quaternion { -public: - Quaternion() : _w(1.0), _x(0.0), _y(0.0), _z(0.0) {} - - Quaternion(double w, double x, double y, double z) - : _w(w), _x(x), _y(y), _z(z) {} - - Quaternion(double w, Vector<3> vec) - : _w(w), _x(vec.x()), _y(vec.y()), _z(vec.z()) {} - - double &w() { return _w; } - double &x() { return _x; } - double &y() { return _y; } - double &z() { return _z; } - - double w() const { return _w; } - double x() const { return _x; } - double y() const { return _y; } - double z() const { return _z; } - - double magnitude() const { - return sqrt(_w * _w + _x * _x + _y * _y + _z * _z); - } - - void normalize() { - double mag = magnitude(); - *this = this->scale(1 / mag); - } - - Quaternion conjugate() const { return Quaternion(_w, -_x, -_y, -_z); } - - void fromAxisAngle(const Vector<3> &axis, double theta) { - _w = cos(theta / 2); - // only need to calculate sine of half theta once - double sht = sin(theta / 2); - _x = axis.x() * sht; - _y = axis.y() * sht; - _z = axis.z() * sht; - } - - void fromMatrix(const Matrix<3> &m) { - double tr = m.trace(); - - double S; - if (tr > 0) { - S = sqrt(tr + 1.0) * 2; - _w = 0.25 * S; - _x = (m(2, 1) - m(1, 2)) / S; - _y = (m(0, 2) - m(2, 0)) / S; - _z = (m(1, 0) - m(0, 1)) / S; - } else if (m(0, 0) > m(1, 1) && m(0, 0) > m(2, 2)) { - S = sqrt(1.0 + m(0, 0) - m(1, 1) - m(2, 2)) * 2; - _w = (m(2, 1) - m(1, 2)) / S; - _x = 0.25 * S; - _y = (m(0, 1) + m(1, 0)) / S; - _z = (m(0, 2) + m(2, 0)) / S; - } else if (m(1, 1) > m(2, 2)) { - S = sqrt(1.0 + m(1, 1) - m(0, 0) - m(2, 2)) * 2; - _w = (m(0, 2) - m(2, 0)) / S; - _x = (m(0, 1) + m(1, 0)) / S; - _y = 0.25 * S; - _z = (m(1, 2) + m(2, 1)) / S; - } else { - S = sqrt(1.0 + m(2, 2) - m(0, 0) - m(1, 1)) * 2; - _w = (m(1, 0) - m(0, 1)) / S; - _x = (m(0, 2) + m(2, 0)) / S; - _y = (m(1, 2) + m(2, 1)) / S; - _z = 0.25 * S; - } - } - - void toAxisAngle(Vector<3> &axis, double &angle) const { - double sqw = sqrt(1 - _w * _w); - if (sqw == 0) // it's a singularity and divide by zero, avoid - return; - - angle = 2 * acos(_w); - axis.x() = _x / sqw; - axis.y() = _y / sqw; - axis.z() = _z / sqw; - } - - Matrix<3> toMatrix() const { - Matrix<3> ret; - ret.cell(0, 0) = 1 - 2 * _y * _y - 2 * _z * _z; - ret.cell(0, 1) = 2 * _x * _y - 2 * _w * _z; - ret.cell(0, 2) = 2 * _x * _z + 2 * _w * _y; - - ret.cell(1, 0) = 2 * _x * _y + 2 * _w * _z; - ret.cell(1, 1) = 1 - 2 * _x * _x - 2 * _z * _z; - ret.cell(1, 2) = 2 * _y * _z - 2 * _w * _x; - - ret.cell(2, 0) = 2 * _x * _z - 2 * _w * _y; - ret.cell(2, 1) = 2 * _y * _z + 2 * _w * _x; - ret.cell(2, 2) = 1 - 2 * _x * _x - 2 * _y * _y; - return ret; - } - - // Returns euler angles that represent the quaternion. Angles are - // returned in rotation order and right-handed about the specified - // axes: - // - // v[0] is applied 1st about z (ie, roll) - // v[1] is applied 2nd about y (ie, pitch) - // v[2] is applied 3rd about x (ie, yaw) - // - // Note that this means result.x() is not a rotation about x; - // similarly for result.z(). - // - Vector<3> toEuler() const { - Vector<3> ret; - double sqw = _w * _w; - double sqx = _x * _x; - double sqy = _y * _y; - double sqz = _z * _z; - - ret.x() = atan2(2.0 * (_x * _y + _z * _w), (sqx - sqy - sqz + sqw)); - ret.y() = asin(-2.0 * (_x * _z - _y * _w) / (sqx + sqy + sqz + sqw)); - ret.z() = atan2(2.0 * (_y * _z + _x * _w), (-sqx - sqy + sqz + sqw)); - - return ret; - } - - Vector<3> toAngularVelocity(double dt) const { - Vector<3> ret; - Quaternion one(1.0, 0.0, 0.0, 0.0); - Quaternion delta = one - *this; - Quaternion r = (delta / dt); - r = r * 2; - r = r * one; - - ret.x() = r.x(); - ret.y() = r.y(); - ret.z() = r.z(); - return ret; - } - - Vector<3> rotateVector(const Vector<2> &v) const { - return rotateVector(Vector<3>(v.x(), v.y())); - } - - Vector<3> rotateVector(const Vector<3> &v) const { - Vector<3> qv(_x, _y, _z); - Vector<3> t = qv.cross(v) * 2.0; - return v + t * _w + qv.cross(t); - } - - Quaternion operator*(const Quaternion &q) const { - return Quaternion(_w * q._w - _x * q._x - _y * q._y - _z * q._z, - _w * q._x + _x * q._w + _y * q._z - _z * q._y, - _w * q._y - _x * q._z + _y * q._w + _z * q._x, - _w * q._z + _x * q._y - _y * q._x + _z * q._w); - } - - Quaternion operator+(const Quaternion &q) const { - return Quaternion(_w + q._w, _x + q._x, _y + q._y, _z + q._z); - } - - Quaternion operator-(const Quaternion &q) const { - return Quaternion(_w - q._w, _x - q._x, _y - q._y, _z - q._z); - } - - Quaternion operator/(double scalar) const { - return Quaternion(_w / scalar, _x / scalar, _y / scalar, _z / scalar); - } - - Quaternion operator*(double scalar) const { return scale(scalar); } - - Quaternion scale(double scalar) const { - return Quaternion(_w * scalar, _x * scalar, _y * scalar, _z * scalar); - } - -private: - double _w, _x, _y, _z; -}; - -} // namespace imu - -#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/vector.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/vector.h deleted file mode 100644 index 10345c34..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/imumaths/vector.h +++ /dev/null @@ -1,184 +0,0 @@ -// Inertial Measurement Unit Maths Library -// -// Copyright 2013-2021 Sam Cowen -// Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) -// -// Permission is hereby granted, free of charge, to any person obtaining a -// copy of this software and associated documentation files (the "Software"), -// to deal in the Software without restriction, including without limitation -// the rights to use, copy, modify, merge, publish, distribute, sublicense, -// and/or sell copies of the Software, and to permit persons to whom the -// Software is furnished to do so, subject to the following conditions: -// -// The above copyright notice and this permission notice shall be included in -// all copies or substantial portions of the Software. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS -// OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING -// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER -// DEALINGS IN THE SOFTWARE. - -#ifndef IMUMATH_VECTOR_HPP -#define IMUMATH_VECTOR_HPP - -#include -#include -#include - -namespace imu { - -template class Vector { -public: - Vector() { memset(p_vec, 0, sizeof(double) * N); } - - Vector(double a) { - memset(p_vec, 0, sizeof(double) * N); - p_vec[0] = a; - } - - Vector(double a, double b) { - memset(p_vec, 0, sizeof(double) * N); - p_vec[0] = a; - p_vec[1] = b; - } - - Vector(double a, double b, double c) { - memset(p_vec, 0, sizeof(double) * N); - p_vec[0] = a; - p_vec[1] = b; - p_vec[2] = c; - } - - Vector(double a, double b, double c, double d) { - memset(p_vec, 0, sizeof(double) * N); - p_vec[0] = a; - p_vec[1] = b; - p_vec[2] = c; - p_vec[3] = d; - } - - Vector(const Vector &v) { - for (int x = 0; x < N; x++) - p_vec[x] = v.p_vec[x]; - } - - ~Vector() {} - - uint8_t n() { return N; } - - double magnitude() const { - double res = 0; - for (int i = 0; i < N; i++) - res += p_vec[i] * p_vec[i]; - - return sqrt(res); - } - - void normalize() { - double mag = magnitude(); - if (isnan(mag) || mag == 0.0) - return; - - for (int i = 0; i < N; i++) - p_vec[i] /= mag; - } - - double dot(const Vector &v) const { - double ret = 0; - for (int i = 0; i < N; i++) - ret += p_vec[i] * v.p_vec[i]; - - return ret; - } - - // The cross product is only valid for vectors with 3 dimensions, - // with the exception of higher dimensional stuff that is beyond - // the intended scope of this library. - // Only a definition for N==3 is given below this class, using - // cross() with another value for N will result in a link error. - Vector cross(const Vector &v) const; - - Vector scale(double scalar) const { - Vector ret; - for (int i = 0; i < N; i++) - ret.p_vec[i] = p_vec[i] * scalar; - return ret; - } - - Vector invert() const { - Vector ret; - for (int i = 0; i < N; i++) - ret.p_vec[i] = -p_vec[i]; - return ret; - } - - Vector &operator=(const Vector &v) { - for (int x = 0; x < N; x++) - p_vec[x] = v.p_vec[x]; - return *this; - } - - double &operator[](int n) { return p_vec[n]; } - - double operator[](int n) const { return p_vec[n]; } - - double &operator()(int n) { return p_vec[n]; } - - double operator()(int n) const { return p_vec[n]; } - - Vector operator+(const Vector &v) const { - Vector ret; - for (int i = 0; i < N; i++) - ret.p_vec[i] = p_vec[i] + v.p_vec[i]; - return ret; - } - - Vector operator-(const Vector &v) const { - Vector ret; - for (int i = 0; i < N; i++) - ret.p_vec[i] = p_vec[i] - v.p_vec[i]; - return ret; - } - - Vector operator*(double scalar) const { return scale(scalar); } - - Vector operator/(double scalar) const { - Vector ret; - for (int i = 0; i < N; i++) - ret.p_vec[i] = p_vec[i] / scalar; - return ret; - } - - void toDegrees() { - for (int i = 0; i < N; i++) - p_vec[i] *= 57.2957795131; // 180/pi - } - - void toRadians() { - for (int i = 0; i < N; i++) - p_vec[i] *= 0.01745329251; // pi/180 - } - - double &x() { return p_vec[0]; } - double &y() { return p_vec[1]; } - double &z() { return p_vec[2]; } - double x() const { return p_vec[0]; } - double y() const { return p_vec[1]; } - double z() const { return p_vec[2]; } - -private: - double p_vec[N]; -}; - -template <> inline Vector<3> Vector<3>::cross(const Vector &v) const { - return Vector(p_vec[1] * v.p_vec[2] - p_vec[2] * v.p_vec[1], - p_vec[2] * v.p_vec[0] - p_vec[0] * v.p_vec[2], - p_vec[0] * v.p_vec[1] - p_vec[1] * v.p_vec[0]); -} - -} // namespace imu - -#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index 44a26d2e..527eab30 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -1,372 +1,178 @@ -/* -MIT License - -Copyright (c) 2020 Peter Buchegger - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -*/ - #include "APRSMsg.h" -char *s_min_nn(uint32_t min_nnnnn, int high_precision); -int numDigits(unsigned int num); - -APRSMsg::APRSMsg() : _body() -{ -} - -APRSMsg::APRSMsg(APRSMsg &otherMsg) - : _type(otherMsg.getType()), _body() -{ - strcpy(_source, otherMsg.getSource()); - strcpy(_destination, otherMsg.getDestination()); - strcpy(_path, otherMsg.getPath()); - strcpy(_rawBody, otherMsg.getRawBody()); - _body.setData(otherMsg.getBody()->getData()); -} - -APRSMsg &APRSMsg::operator=(APRSMsg &otherMsg) -{ - if (this != &otherMsg) - { - setSource(otherMsg.getSource()); - setDestination(otherMsg.getDestination()); - setPath(otherMsg.getPath()); - _type = otherMsg.getType(); - strcpy(_rawBody, otherMsg.getRawBody()); - _body.setData(otherMsg.getBody()->getData()); - } - return *this; -} -APRSMsg::~APRSMsg() -{ -} +#define MAX_ALLOWED_MSG_LEN 255 /* max length of 1 message supported by radio buffer */ -const char *APRSMsg::getSource() -{ - return _source; -} -void APRSMsg::setSource(const char source[8]) -{ - strcpy(_source, source); -} -const char *APRSMsg::getDestination() +APRSMsg::APRSMsg(APRSHeader &header) { - return _destination; + this->header = header; } -void APRSMsg::setDestination(const char destination[8]) +const uint8_t *APRSMsg::encode() { - strcpy(_destination, destination); + char *msg = new char[MAX_ALLOWED_MSG_LEN]; + int c = encodeHeader(msg); + encodeData(msg, c); + return (uint8_t *)msg; } -const char *APRSMsg::getPath() +bool APRSMsg::decode(const uint8_t *message, int len) { - return _path; + //message needs to be decoded and values reinstered into the header and data structs + int c = decodeHeader((char *)message, len); + decodeData((char *)message, len, c); + return false; } -void APRSMsg::setPath(const char path[10]) -{ - strcpy(_path, path); -} +#pragma region Encode Helpers -APRSMessageType APRSMsg::getType() +int APRSMsg::encodeHeader(char *message) const { - return _type; -} - -const char *APRSMsg::getRawBody() -{ - return _rawBody; -} - -APRSBody *APRSMsg::getBody() -{ - return &_body; -} - -bool APRSMsg::decode(char *message) -{ - int len = strlen(message); - int posSrc = -1, posDest = -1, posPath = -1; - for (int i = 0; i < len; i++) + // format: CALLSIGN>TOCALL,PATH: + int cursor = 0; + for (int i = 0; header.CALLSIGN[i] && i < 8; i++, cursor++) { - if (message[i] == '>' && posSrc == -1) - posSrc = i; - if (message[i] == ',' && posDest == -1) - posDest = i; - if (message[i] == ':' && posPath == -1) - posPath = i; + message[cursor] = header.CALLSIGN[i]; } - if (posSrc >= 8) - return false; - if (posDest - (posSrc + 1) >= 8) - return false; - if (posPath - (posDest + 1) >= 10) - return false; - - if (posSrc >= 0) + message[cursor++] = '>'; + for (int i = 0; header.TOCALL[i] && i < 8; i++, cursor++) { - strncpy(_source, message, posSrc); - _source[posSrc] = '\0'; + message[cursor] = header.TOCALL[i]; } - else - { - _source[0] = '\0'; - } - - if (posDest != -1 && posDest < posPath) - { - strncpy(_path, message + posDest + 1, posPath - (posDest + 1)); - strncpy(_destination, message + posSrc + 1, posDest - (posSrc + 1)); - _path[posPath - (posDest + 1)] = '\0'; - _destination[posDest - (posSrc + 1)] = '\0'; - } - else - { - _path[0] = '\0'; - if (posSrc >= 0 && posPath >= 0) - { - - strncpy(_destination, message + posSrc + 1, posPath - (posSrc + 1)); - _destination[posPath - (posSrc + 1)] = '\0'; - } - else - { - _destination[0] = '\0'; - } - } - strcpy(_rawBody, message + posPath + 1); - _rawBody[strlen(message + posPath + 1)] = '\0'; - _type = APRSMessageType(_rawBody[0]); - _body.decode(_rawBody); - return bool(_type); -} - -void APRSMsg::encode(char *message) -{ - sprintf(message, "%s>%s", _source, _destination); - if (strlen(_path) > 0) + message[cursor++] = ','; + for (int i = 0; header.PATH[i] && i < 10; i++, cursor++) { - sprintf(message + strlen(message), ",%s", _path); + message[cursor] = header.PATH[i]; } - sprintf(message + strlen(message), ":%s", _body.encode()); + message[cursor++] = ':'; // end of header + return cursor; } -void APRSMsg::toString(char *str) +void APRSMsg::encodeData(char *message, int cursor) { - char body[87]; - _body.toString(body); - sprintf(str, "Source:%s,Destination:%s,Path:%s,Type:%s,%s", _source, _destination, _path, _type.toString(), body); -} + /* Small Aircraft symbol ( /' ) probably better than Jogger symbol ( /[ ) lol. + I'm going to use the Overlayed Aircraft symbol ( \^ ) for now, with the overlay of 'M' for UMD ( M^ ). + Uses base91 encoding to compress message as much as possible. APRS messages are apparently supposed to be only 256 bytes. -APRSBody::APRSBody() -{ -} -APRSBody::~APRSBody() -{ -} + takes the regular format of !DDMM.hhN/DDDMM.hhW^ALTSPD/HDG SSOrientation -const char *APRSBody::getData() -{ - return _data; -} + which expands to !(lat)/(lng)^altspd/hdg (stage #)(orientation) -void APRSBody::setData(const char data[80]) -{ - strcpy(_data, data); -} + and compresses it to /YYYYXXXX^ ccssaasoooooo -bool APRSBody::decode(char *message) -{ - strcpy(_data, message); - return true; -} + which expands to /(lat)(lng)^ (course)(speed)(altitude)(stage)(orientation [as euler angles]) -const char *APRSBody::encode() -{ - return _data; -} + specifically does not use the csT compressed format because we don't need T and want better accuracy on course angle. + for more information on APRS, see http://www.aprs.org/doc/APRS101.PDF -void APRSBody::toString(char *str) -{ - sprintf(str, "Data:%s", _data); -} -// creates the latitude string for the APRS message based on whether the GPS coordinates are high precision -void APRSMsg::formatLat(char *lat, bool hp) -{ - bool negative = lat[0] == '-'; + lat and lng are in decimal degrees. no need to convert to DMS. + course is in degrees, speed is in knots, altitude is in feet, stage is an integer, orientation is in degrees. + */ - int len = strlen(lat); - int decimalPos = 0; - // use for loop in case there is no decimal - for (int i = 0; i < len; i++) - { - if (lat[i] == '.') - { - decimalPos = i; - break; - } - } - int decLen = strlen(lat + decimalPos + 1); - int dec = atoi(lat + decimalPos + 1); - - // make sure there are nine digits - int missingDigits = 9 - decLen; - if (missingDigits < 0) - for (int i = 0; i < missingDigits * -1; i++) - dec /= 10; - if (missingDigits > 0) - for (int i = 0; i < missingDigits; i++) - dec *= 10; - - // we like sprintf's float up-rounding. - // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation - // ;) - sprintf(lat, "%02d%s%c", atoi(lat) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'S' : 'N'); -} + // lat and lng + message[cursor++] = 'M'; // overlay + encodeBase91(message, cursor, (int)380926 * (90 - data.lat), 4); // 380926 is the magic number from the APRS spec (page 38) + encodeBase91(message, cursor, (int)190463 * (180 + data.lng), 4); // 190463 is the magic number from the APRS spec (page 38) + message[cursor++] = '^'; // end of lat and lng + message[cursor++] = ' '; // space to start 'Comment' section -// creates the longitude string for the APRS message based on whether the GPS coordinates are high precision -void APRSMsg::formatLong(char *lng, bool hp) -{ - bool negative = lng[0] == '-'; + // course, speed, altitude + encodeBase91(message, cursor, (int)(data.hdg * HDG_SCALE), 2); // (91^2/360) scale to fit in 2 base91 characters + encodeBase91(message, cursor, (int)(data.spd * SPD_SCALE), 2); // (91^2/1000) scale to fit in 2 base91 characters. 1000 knots is the assumed max speed. + encodeBase91(message, cursor, (int)(data.alt * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. - int len = strlen(lng); - int decimalPos = 0; - // use for loop in case there is no decimal - for (int i = 0; i < len; i++) - { - if (lng[i] == '.') - { - decimalPos = i; - break; - } - } + // stage and orientation + message[cursor++] = (char)(data.stage + (int)'0'); // stage is just written in plaintext. + encodeBase91(message, cursor, (int)(data.orientation.x() * ORIENTATION_SCALE), 2); // same as course + encodeBase91(message, cursor, (int)(data.orientation.y() * ORIENTATION_SCALE), 2); // same as course + encodeBase91(message, cursor, (int)(data.orientation.z() * ORIENTATION_SCALE), 2); // same as course - int decLen = strlen(lng + decimalPos + 1); - int dec = atoi(lng + decimalPos + 1); - - // make sure there are nine digits - int missingDigits = 9 - decLen; - if (missingDigits < 0) - for (int i = 0; i < missingDigits * -1; i++) - dec /= 10; - if (missingDigits > 0) - for (int i = 0; i < missingDigits; i++) - dec *= 10; - - // we like sprintf's float up-rounding. - // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation - // ;) - sprintf(lng, "%02d%s%c", atoi(lng) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'W' : 'E'); + len = cursor; } -// creates the dao at the end of aprs message based on latitude and longitude -void APRSMsg::formatDao(char *lat, char *lng, char *dao) -{ - // !DAO! extension, use Base91 format for best precision - // /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest - // integer https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm - // http://www.aprs.org/aprs12/datum.txt - - int len = strlen(lat); - int decimalPos = 0; - // use for loop in case there is no decimal - for (int i = 0; i < len; i++) - { - if (lat[i] == '.') - decimalPos = i; - } - sprintf(dao, "!w%s", s_min_nn((int)(lat + decimalPos + 1), 2)); +#pragma endregion - len = strlen(lng); - decimalPos = 0; - for (int i = 0; i < len; i++) - { - if (lng[i] == '.') - decimalPos = i; - } - sprintf(dao + 3, "%s!", s_min_nn((int)(lng + decimalPos + 1), 2)); -} +#pragma region Decode Helpers -// adds a specified number of zeros to the begining of a number -void APRSMsg::padding(unsigned int number, unsigned int width, char *output, int offset) +int APRSMsg::decodeHeader(const char *message, int len) { - unsigned int numLen = numDigits(number); - if (numLen > width) + // format: CALLSIGN>TOCALL,PATH: + int cursor = 0; + for (int i = 0; message[cursor] != '>'; i++, cursor++) + { + header.CALLSIGN[i] = message[cursor]; + } + header.CALLSIGN[cursor] = '\0'; + cursor++; // skip '>' + for (int i = 0; message[cursor] != ','; i++, cursor++) { - width = numLen; + header.TOCALL[i] = message[cursor]; } - for (unsigned int i = 0; i < width - numLen; i++) + header.TOCALL[cursor] = '\0'; + cursor++; // skip ',' + for (int i = 0; message[cursor] != ':'; i++, cursor++) { - output[offset + i] = '0'; + header.PATH[i] = message[cursor]; } - sprintf(output + offset + width - numLen, "%u", number); + header.PATH[cursor] = '\0'; + cursor++; // skip ':' + return cursor; } -// takes in decimal minutes and converts to MM.dddd -char *s_min_nn(uint32_t min_nnnnn, int high_precision) +void APRSMsg::decodeData(const char *message, int len, int cursor) { - /* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth - * degree (-> *= 6 -> nn.mmmmmm minutes) high_precision: 0: round at decimal - * position 2. 1: round at decimal position 4. 2: return decimal position 3-4 - * as base91 encoded char - */ + // lat and lng + cursor++; // skip overlay + decodeBase91(message, cursor, data.lat, 4); + data.lat = 90 - data.lat / 380926.0; + decodeBase91(message, cursor, data.lng, 4); + data.lng = data.lng / 190463.0 - 180; + cursor++; // skip '^' + cursor++; // skip ' ' - static char buf[6]; + // course, speed, altitude + decodeBase91(message, cursor, data.hdg, 2); + data.hdg /= HDG_SCALE; + decodeBase91(message, cursor, data.spd, 2); + data.spd /= SPD_SCALE; + decodeBase91(message, cursor, data.alt, 2); + data.alt /= ALT_SCALE; - min_nnnnn = min_nnnnn * 0.006; + // stage and orientation + data.stage = message[cursor++] - (int)'0'; + decodeBase91(message, cursor, data.orientation.x(), 2); + data.orientation.x() /= ORIENTATION_SCALE; + decodeBase91(message, cursor, data.orientation.y(), 2); + data.orientation.y() /= ORIENTATION_SCALE; + decodeBase91(message, cursor, data.orientation.z(), 2); + data.orientation.z() /= ORIENTATION_SCALE; +} + +#pragma endregion + +#pragma region Base91 Encoding - if (high_precision) +void APRSMsg::encodeBase91(char *message, int &cursor, int value, int precision) const +{ + for (int i = precision - 1; i >= 0; i--) { - if ((min_nnnnn % 10) >= 5 && min_nnnnn < 6000000 - 5) - { - // round up. Avoid overflow (59.999999 should never become 60.0 or more) - min_nnnnn = min_nnnnn + 5; - } + int divisor = pow(91, i); + message[cursor++] = (char)((int)(value / divisor) + 33); + value %= divisor; } - else +} + +void APRSMsg::decodeBase91(const char *message, int &cursor, double &value, int precision) const +{ + value = 0; + for (int i = 0; i < precision; i++) { - if ((min_nnnnn % 1000) >= 500 && min_nnnnn < (6000000 - 500)) - { - // round up. Avoid overflow (59.9999 should never become 60.0 or more) - min_nnnnn = min_nnnnn + 500; - } + value += (message[cursor++] - 33) * pow(91, precision - i - 1); } - - if (high_precision < 2) - sprintf(buf, "%02u.%02u", (unsigned int)((min_nnnnn / 100000) % 100), (unsigned int)((min_nnnnn / 1000) % 100)); - else - sprintf(buf, "%c", (char)((min_nnnnn % 1000) / 11) + 33); - // Like to verify? type in python for i.e. RawDegrees billions 566688333: i = - // 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33) - return buf; } -int numDigits(unsigned int num) -{ - if (num < 10) - return 1; - return 1 + numDigits(num / 10); -} \ No newline at end of file +#pragma endregion \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h index 43f298d3..5eb8f32e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h @@ -1,27 +1,3 @@ -/* -MIT License - -Copyright (c) 2020 Peter Buchegger - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -*/ - #ifndef APRSMSG_H #define APRSMSG_H @@ -37,150 +13,10 @@ SOFTWARE. // TODO #endif -class APRSMessageType -{ -public: - enum Value : uint8_t - { - PositionWithoutTimestamp, // = and ! - PositionWithTimestamp, // @ and / - Status, // > - Query, // ? - Message, // : - Weather, // _ - Telemetry, // T - CurrentMicEData, // ` - // you can add more types ;) - Error, - }; - - APRSMessageType() = default; - // cppcheck-suppress noExplicitConstructor - APRSMessageType(char type) - { - switch (type) - { - case '=': - case '!': - value = PositionWithoutTimestamp; - break; - case '@': - case '/': - value = PositionWithTimestamp; - break; - case '>': - value = Status; - break; - case '?': - value = Query; - break; - case ':': - value = Message; - break; - case '_': - value = Weather; - break; - case 'T': - value = Telemetry; - break; - case '`': - value = CurrentMicEData; - break; - default: - value = Error; - } - } - // cppcheck-suppress noExplicitConstructor - constexpr APRSMessageType(Value aType) : value(aType) {} - constexpr bool operator==(APRSMessageType a) const { return value == a.value; } - constexpr bool operator!=(APRSMessageType a) const { return value != a.value; } - explicit operator bool() const { return value != Error; } - - const char *toString() const - { - switch (value) - { - case PositionWithoutTimestamp: - return "Position Without Timestamp"; - case PositionWithTimestamp: - return "Position With Timestamp"; - case Status: - return "Status"; - case Query: - return "Query"; - case Message: - return "Message"; - case Weather: - return "Weather"; - case Telemetry: - return "Telemetry"; - case CurrentMicEData: - return "Current Mic-E Data"; - default: - return "Error"; - } - } - -private: - Value value = Error; -}; - -class APRSBody -{ -public: - APRSBody(); - virtual ~APRSBody(); - - const char *getData(); - void setData(const char data[80]); - - virtual bool decode(char *message); - virtual const char *encode(); - virtual void toString(char *str); - -private: - char _data[80]{0}; -}; - -class APRSMsg -{ -public: - APRSMsg(); - APRSMsg(APRSMsg &otherMsg); - APRSMsg &operator=(APRSMsg &otherMsg); - virtual ~APRSMsg(); - - const char *getSource(); - void setSource(const char source[8]); - - const char *getDestination(); - void setDestination(const char destination[8]); +#include "Radio.h" +#include - const char *getPath(); - void setPath(const char path[10]); - APRSMessageType getType(); - - const char *getRawBody(); - APRSBody *getBody(); - - virtual bool decode(char *message); - virtual void encode(char *message); - virtual void toString(char *str); - - static void formatLat(char *lat, bool hp); - static void formatLong(char *lng, bool hp); - static void formatDao(char *lat, char *lng, char *dao); - static void padding(unsigned int number, unsigned int width, char *output, int offset = 0); - -private: - char _source[8]{0}; - char _destination[8]{0}; - char _path[10]{0}; - APRSMessageType _type; - char _rawBody[80]{0}; - APRSBody _body; -}; /* APRS Configuration @@ -190,13 +26,11 @@ APRS Configuration - SYMBOL - OVERLAY */ -struct APRSConfig +struct APRSHeader { char CALLSIGN[8]; char TOCALL[8]; char PATH[10]; - char SYMBOL; - char OVERLAY; }; /* @@ -206,22 +40,51 @@ APRS Telemetry Data - alt - spd - hdg -- precision +- orientation - stage -- t0 -- dao */ struct APRSData { - char lat[16]; - char lng[16]; - char alt[10]; - char spd[4]; - char hdg[4]; - char precision; - char stage[3]; - char t0[9]; - char dao[6]; + double lat; + double lng; + double alt; + double spd; + double hdg; + int stage; + imu::Vector<3> orientation; +}; + + +class APRSMsg : public RadioMessage +{ +public: + APRSMsg(APRSHeader &header); + virtual ~APRSMsg(){}; + + bool decode(const uint8_t *message, int len) override; + const uint8_t *encode() override; + int length() const override { return this->len; } + APRSData data; + APRSHeader header; + +private: + + int encodeHeader(char *message) const; + void encodeData(char *message, int cursor); + + int decodeHeader(const char *message, int len); + void decodeData(const char *message, int len, int cursor); + + void encodeBase91(char *message, int &cursor, int value, int precision) const; + void decodeBase91(const char *message, int &cursor, double &value, int precision) const; + + //Scale factors for encoding/decoding ignoring lat/long + const double ALT_SCALE = (pow(91, 2) / 15000.0); // (91^2/15000) scale to fit in 2 base91 characters + const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters + const double HDG_SCALE = (pow(91, 2) / 360.0); // (91^2/360) scale to fit in 2 base91 characters + const double ORIENTATION_SCALE = (pow(91, 2) / 360.0); // same as course }; + + #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp new file mode 100644 index 00000000..8adb533d --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp @@ -0,0 +1,372 @@ +// /* +// MIT License + +// Copyright (c) 2020 Peter Buchegger + +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: + +// The above copyright notice and this permission notice shall be included in all +// copies or substantial portions of the Software. + +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// */ + +// #include "APRSMsg.h" + +// char *s_min_nn(uint32_t min_nnnnn, int high_precision); +// int numDigits(unsigned int num); + +// APRSMsg::APRSMsg() : _body() +// { +// } + +// APRSMsg::APRSMsg(APRSMsg &otherMsg) +// : _type(otherMsg.getType()), _body() +// { +// strcpy(_source, otherMsg.getSource()); +// strcpy(_destination, otherMsg.getDestination()); +// strcpy(_path, otherMsg.getPath()); +// strcpy(_rawBody, otherMsg.getRawBody()); +// _body.setData(otherMsg.getBody()->getData()); +// } + +// APRSMsg &APRSMsg::operator=(APRSMsg &otherMsg) +// { +// if (this != &otherMsg) +// { +// setSource(otherMsg.getSource()); +// setDestination(otherMsg.getDestination()); +// setPath(otherMsg.getPath()); +// _type = otherMsg.getType(); +// strcpy(_rawBody, otherMsg.getRawBody()); +// _body.setData(otherMsg.getBody()->getData()); +// } +// return *this; +// } + +// APRSMsg::~APRSMsg() +// { +// } + +// const char *APRSMsg::getSource() +// { +// return _source; +// } + +// void APRSMsg::setSource(const char source[8]) +// { +// strcpy(_source, source); +// } + +// const char *APRSMsg::getDestination() +// { +// return _destination; +// } + +// void APRSMsg::setDestination(const char destination[8]) +// { +// strcpy(_destination, destination); +// } + +// const char *APRSMsg::getPath() +// { +// return _path; +// } + +// void APRSMsg::setPath(const char path[10]) +// { +// strcpy(_path, path); +// } + +// APRSMessageType APRSMsg::getType() +// { +// return _type; +// } + +// const char *APRSMsg::getRawBody() +// { +// return _rawBody; +// } + +// APRSBody *APRSMsg::getBody() +// { +// return &_body; +// } + +// bool APRSMsg::decode(char *message) +// { +// int len = strlen(message); +// int posSrc = -1, posDest = -1, posPath = -1; +// for (int i = 0; i < len; i++) +// { +// if (message[i] == '>' && posSrc == -1) +// posSrc = i; +// if (message[i] == ',' && posDest == -1) +// posDest = i; +// if (message[i] == ':' && posPath == -1) +// posPath = i; +// } +// if (posSrc >= 8) +// return false; +// if (posDest - (posSrc + 1) >= 8) +// return false; +// if (posPath - (posDest + 1) >= 10) +// return false; + +// if (posSrc >= 0) +// { +// strncpy(_source, message, posSrc); +// _source[posSrc] = '\0'; +// } +// else +// { +// _source[0] = '\0'; +// } + +// if (posDest != -1 && posDest < posPath) +// { +// strncpy(_path, message + posDest + 1, posPath - (posDest + 1)); +// strncpy(_destination, message + posSrc + 1, posDest - (posSrc + 1)); +// _path[posPath - (posDest + 1)] = '\0'; +// _destination[posDest - (posSrc + 1)] = '\0'; +// } +// else +// { +// _path[0] = '\0'; +// if (posSrc >= 0 && posPath >= 0) +// { + +// strncpy(_destination, message + posSrc + 1, posPath - (posSrc + 1)); +// _destination[posPath - (posSrc + 1)] = '\0'; +// } +// else +// { +// _destination[0] = '\0'; +// } +// } +// strcpy(_rawBody, message + posPath + 1); +// _rawBody[strlen(message + posPath + 1)] = '\0'; +// _type = APRSMessageType(_rawBody[0]); +// _body.decode(_rawBody); +// return bool(_type); +// } + +// void APRSMsg::encode(char *message) +// { +// sprintf(message, "%s>%s", _source, _destination); +// if (strlen(_path) > 0) +// { +// sprintf(message + strlen(message), ",%s", _path); +// } +// sprintf(message + strlen(message), ":%s", _body.encode()); +// } + +// void APRSMsg::toString(char *str) +// { +// char body[87]; +// _body.toString(body); +// sprintf(str, "Source:%s,Destination:%s,Path:%s,Type:%s,%s", _source, _destination, _path, _type.toString(), body); +// } + +// APRSBody::APRSBody() +// { +// } + +// APRSBody::~APRSBody() +// { +// } + +// const char *APRSBody::getData() +// { +// return _data; +// } + +// void APRSBody::setData(const char data[80]) +// { +// strcpy(_data, data); +// } + +// bool APRSBody::decode(char *message) +// { +// strcpy(_data, message); +// return true; +// } + +// const char *APRSBody::encode() +// { +// return _data; +// } + +// void APRSBody::toString(char *str) +// { +// sprintf(str, "Data:%s", _data); +// } + +// // creates the latitude string for the APRS message based on whether the GPS coordinates are high precision +// void APRSMsg::formatLat(char *lat, bool hp) +// { +// bool negative = lat[0] == '-'; + +// int len = strlen(lat); +// int decimalPos = 0; +// // use for loop in case there is no decimal +// for (int i = 0; i < len; i++) +// { +// if (lat[i] == '.') +// { +// decimalPos = i; +// break; +// } +// } +// int decLen = strlen(lat + decimalPos + 1); +// int dec = atoi(lat + decimalPos + 1); + +// // make sure there are nine digits +// int missingDigits = 9 - decLen; +// if (missingDigits < 0) +// for (int i = 0; i < missingDigits * -1; i++) +// dec /= 10; +// if (missingDigits > 0) +// for (int i = 0; i < missingDigits; i++) +// dec *= 10; + +// // we like sprintf's float up-rounding. +// // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation +// // ;) +// sprintf(lat, "%02d%s%c", atoi(lat) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'S' : 'N'); +// } + +// // creates the longitude string for the APRS message based on whether the GPS coordinates are high precision +// void APRSMsg::formatLong(char *lng, bool hp) +// { +// bool negative = lng[0] == '-'; + +// int len = strlen(lng); +// int decimalPos = 0; +// // use for loop in case there is no decimal +// for (int i = 0; i < len; i++) +// { +// if (lng[i] == '.') +// { +// decimalPos = i; +// break; +// } +// } + +// int decLen = strlen(lng + decimalPos + 1); +// int dec = atoi(lng + decimalPos + 1); + +// // make sure there are nine digits +// int missingDigits = 9 - decLen; +// if (missingDigits < 0) +// for (int i = 0; i < missingDigits * -1; i++) +// dec /= 10; +// if (missingDigits > 0) +// for (int i = 0; i < missingDigits; i++) +// dec *= 10; + +// // we like sprintf's float up-rounding. +// // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation +// // ;) +// sprintf(lng, "%02d%s%c", atoi(lng) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'W' : 'E'); +// } + +// // creates the dao at the end of aprs message based on latitude and longitude +// void APRSMsg::formatDao(char *lat, char *lng, char *dao) +// { +// // !DAO! extension, use Base91 format for best precision +// // /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest +// // integer https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm +// // http://www.aprs.org/aprs12/datum.txt + +// int len = strlen(lat); +// int decimalPos = 0; +// // use for loop in case there is no decimal +// for (int i = 0; i < len; i++) +// { +// if (lat[i] == '.') +// decimalPos = i; +// } +// sprintf(dao, "!w%s", s_min_nn((int)(lat + decimalPos + 1), 2)); + +// len = strlen(lng); +// decimalPos = 0; +// for (int i = 0; i < len; i++) +// { +// if (lng[i] == '.') +// decimalPos = i; +// } +// sprintf(dao + 3, "%s!", s_min_nn((int)(lng + decimalPos + 1), 2)); +// } + +// // adds a specified number of zeros to the begining of a number +// void APRSMsg::padding(unsigned int number, unsigned int width, char *output, int offset) +// { +// unsigned int numLen = numDigits(number); +// if (numLen > width) +// { +// width = numLen; +// } +// for (unsigned int i = 0; i < width - numLen; i++) +// { +// output[offset + i] = '0'; +// } +// sprintf(output + offset + width - numLen, "%u", number); +// } + +// // takes in decimal minutes and converts to MM.dddd +// char *s_min_nn(uint32_t min_nnnnn, int high_precision) +// { +// /* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth +// * degree (-> *= 6 -> nn.mmmmmm minutes) high_precision: 0: round at decimal +// * position 2. 1: round at decimal position 4. 2: return decimal position 3-4 +// * as base91 encoded char +// */ + +// static char buf[6]; + +// min_nnnnn = min_nnnnn * 0.006; + +// if (high_precision) +// { +// if ((min_nnnnn % 10) >= 5 && min_nnnnn < 6000000 - 5) +// { +// // round up. Avoid overflow (59.999999 should never become 60.0 or more) +// min_nnnnn = min_nnnnn + 5; +// } +// } +// else +// { +// if ((min_nnnnn % 1000) >= 500 && min_nnnnn < (6000000 - 500)) +// { +// // round up. Avoid overflow (59.9999 should never become 60.0 or more) +// min_nnnnn = min_nnnnn + 500; +// } +// } + +// if (high_precision < 2) +// sprintf(buf, "%02u.%02u", (unsigned int)((min_nnnnn / 100000) % 100), (unsigned int)((min_nnnnn / 1000) % 100)); +// else +// sprintf(buf, "%c", (char)((min_nnnnn % 1000) / 11) + 33); +// // Like to verify? type in python for i.e. RawDegrees billions 566688333: i = +// // 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33) +// return buf; +// } + +// int numDigits(unsigned int num) +// { +// if (num < 10) +// return 1; +// return 1 + numDigits(num / 10); +// } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h new file mode 100644 index 00000000..f600f2e1 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h @@ -0,0 +1,227 @@ +// /* +// MIT License + +// Copyright (c) 2020 Peter Buchegger + +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: + +// The above copyright notice and this permission notice shall be included in all +// copies or substantial portions of the Software. + +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// */ + +// #ifndef APRSMSG_H +// #define APRSMSG_H + +// #if defined(ARDUINO) +// #include +// #elif defined(_WIN32) || defined(_WIN64) // Windows +// #include +// #include +// #include +// #elif defined(__unix__) // Linux +// // TODO +// #elif defined(__APPLE__) // OSX +// // TODO +// #endif + +// class APRSMessageType +// { +// public: +// enum Value : uint8_t +// { +// PositionWithoutTimestamp, // = and ! +// PositionWithTimestamp, // @ and / +// Status, // > +// Query, // ? +// Message, // : +// Weather, // _ +// Telemetry, // T +// CurrentMicEData, // ` +// // you can add more types ;) +// Error, +// }; + +// APRSMessageType() = default; +// // cppcheck-suppress noExplicitConstructor +// APRSMessageType(char type) +// { +// switch (type) +// { +// case '=': +// case '!': +// value = PositionWithoutTimestamp; +// break; +// case '@': +// case '/': +// value = PositionWithTimestamp; +// break; +// case '>': +// value = Status; +// break; +// case '?': +// value = Query; +// break; +// case ':': +// value = Message; +// break; +// case '_': +// value = Weather; +// break; +// case 'T': +// value = Telemetry; +// break; +// case '`': +// value = CurrentMicEData; +// break; +// default: +// value = Error; +// } +// } +// // cppcheck-suppress noExplicitConstructor +// constexpr APRSMessageType(Value aType) : value(aType) {} +// constexpr bool operator==(APRSMessageType a) const { return value == a.value; } +// constexpr bool operator!=(APRSMessageType a) const { return value != a.value; } +// explicit operator bool() const { return value != Error; } + +// const char *toString() const +// { +// switch (value) +// { +// case PositionWithoutTimestamp: +// return "Position Without Timestamp"; +// case PositionWithTimestamp: +// return "Position With Timestamp"; +// case Status: +// return "Status"; +// case Query: +// return "Query"; +// case Message: +// return "Message"; +// case Weather: +// return "Weather"; +// case Telemetry: +// return "Telemetry"; +// case CurrentMicEData: +// return "Current Mic-E Data"; +// default: +// return "Error"; +// } +// } + +// private: +// Value value = Error; +// }; + +// class APRSBody +// { +// public: +// APRSBody(); +// virtual ~APRSBody(); + +// const char *getData(); +// void setData(const char data[80]); + +// virtual bool decode(char *message); +// virtual const char *encode(); +// virtual void toString(char *str); + +// private: +// char _data[80]{0}; +// }; + +// class APRSMsg +// { +// public: +// APRSMsg(); +// APRSMsg(APRSMsg &otherMsg); +// APRSMsg &operator=(APRSMsg &otherMsg); +// virtual ~APRSMsg(); + +// const char *getSource(); +// void setSource(const char source[8]); + +// const char *getDestination(); +// void setDestination(const char destination[8]); + +// const char *getPath(); +// void setPath(const char path[10]); + +// APRSMessageType getType(); + +// const char *getRawBody(); +// APRSBody *getBody(); + +// virtual bool decode(char *message); +// virtual void encode(char *message); +// virtual void toString(char *str); + +// static void formatLat(char *lat, bool hp); +// static void formatLong(char *lng, bool hp); +// static void formatDao(char *lat, char *lng, char *dao); +// static void padding(unsigned int number, unsigned int width, char *output, int offset = 0); + +// private: +// char _source[8]{0}; +// char _destination[8]{0}; +// char _path[10]{0}; +// APRSMessageType _type; +// char _rawBody[80]{0}; +// APRSBody _body; +// }; + +// /* +// APRS Configuration +// - CALLSIGN +// - TOCALL +// - PATH +// - SYMBOL +// - OVERLAY +// */ +// struct APRSConfig +// { +// char CALLSIGN[8]; +// char TOCALL[8]; +// char PATH[10]; +// char SYMBOL; +// char OVERLAY; +// }; + +// /* +// APRS Telemetry Data +// - lat +// - lng +// - alt +// - spd +// - hdg +// - precision +// - stage +// - t0 +// - dao +// */ +// struct APRSData +// { +// char lat[16]; +// char lng[16]; +// char alt[10]; +// char spd[4]; +// char hdg[4]; +// char precision; +// char stage[3]; +// char t0[9]; +// char dao[6]; +// }; + +// #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp deleted file mode 100644 index 97145a81..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ /dev/null @@ -1,733 +0,0 @@ -#include "RFM69HCW.h" - -#ifndef max -int max(int a, int b); -#endif - -#ifndef min -int min(int a, int b); -#endif - -/* -Constructor - - frequency in hertz - - transmitter true if the radio will be on the rocket - - highBitrate true for 300kbps, false for 4.8kbps - - config with APRS settings -*/ -RFM69HCW::RFM69HCW(const RadioSettings *s, const APRSConfig *config) : radio(s->cs, s->irq, *s->spi) -{ - - this->settings = *s; - this->cfg = *config; - this->avail = false; - this->msgLen = -1; - - if (this->settings.transmitter) - { - // addresses for transmitters - this->addr = 0x02; - this->toAddr = 0x01; - } - else - { - // addresses for receivers - this->addr = 0x01; - this->toAddr = 0x02; - } - this->id = 0x00; // to fit the max number of bytes in a packet, this will change - // based on message length, but it will be reset to this value - // after each complete transmission/reception -} - -/* -Initializer to call in setup -*/ -bool RFM69HCW::begin() -{ - // reset the radio - pinMode(this->settings.rst, OUTPUT); - digitalWrite(this->settings.rst, LOW); - delay(10); - digitalWrite(this->settings.rst, HIGH); - delay(10); - digitalWrite(this->settings.rst, LOW); - - if (!this->radio.init()) - return false; - - // then use this to actually set the frequency - if (!this->radio.setFrequency(this->settings.frequency)) - return false; - - // set transmit power - this->radio.setTxPower(this->txPower, true); - - // always set FSK mode - this->radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); - - // set headers - this->radio.setHeaderTo(this->toAddr); - this->radio.setHeaderFrom(this->addr); - this->radio.setThisAddress(this->addr); - this->radio.setHeaderId(this->id); - - // configure unlimited packet length mode, don't do this for now - // this->radio.spiWrite(0x37, 0b00000000); // Packet format (0x37) set to 00000000 (see manual for meaning of each bit) - // this->radio.spiWrite(RH_RF69_REG_38_PAYLOADLENGTH, 0); // Payload length (0x38) set to 0 - - if (this->settings.highBitrate) // Note: not working - { - // the default bitrate of 4.8kbps should be fine unless we want high bitrate for video - // set300KBPS(); - this->radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); - // remove as much overhead as possible - // this->radio.setPreambleLength(0); - // this->radio.setSyncWords(); - } - - return true; -} - -/* -Most basic transmission method, simply transmits the string without modification - \param message is the message to be transmitted, set to nullptr if this->msg already contains the message - \param len [optional] is the length of the message, if not used it is assumed this->msgLen is already set to the length -*/ -bool RFM69HCW::tx(const char *message, int len) -{ - // figure out how long the message should be - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - else if (this->msgLen == -1) - return false; - - // reset variables for tx - this->totalPackets = 0x00; - - // get number of packets for this message, and set this radio's id to that value so the receiver knows how many packets to expect - this->totalPackets = len / this->bufSize + (len % this->bufSize > 0); - this->radio.setHeaderId(this->totalPackets); - sendBuffer(); - - if (message != nullptr) - memcpy(this->msg, message, len); - - return true; -} - -bool RFM69HCW::sendBuffer() -{ - memcpy(this->buf, this->msg + this->id * this->bufSize, min(this->bufSize, this->msgLen - this->id * this->bufSize)); - this->radio.send(this->buf, min(this->bufSize, this->msgLen - this->id * this->bufSize)); - this->id++; - return this->id == this->totalPackets; -} - -void RFM69HCW::endtx() -{ - this->msgLen = -1; - this->id = 0x00; - this->radio.setHeaderId(this->id); -} - -RHGenericDriver::RHMode RFM69HCW::mode() { return radio.mode(); } - - -// partially adapted from RadioHead library -bool RFM69HCW::txs(const char *message, int len) -{ - // figure out how long the message should be - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - else if (this->msgLen == -1) - return false; - - if (message != nullptr) - memcpy(this->msg, message, len); - - this->radio.waitPacketSent(); // Make sure we dont interrupt an outgoing message - this->radio.setModeIdle(); // Prevent RX while filling the fifo - - if (!this->radio.waitCAD()) - return false; // Check channel activity - - ATOMIC_BLOCK_START; - this->settings.spi->beginTransaction(); - digitalWrite(this->settings.cs, LOW); - this->settings.spi->transfer(RH_RF69_REG_00_FIFO | RH_RF69_SPI_WRITE_MASK); // Send the start address with the write mask on - this->settings.spi->transfer(this->msgLen + 1); // Include length of headers - // First the header - this->settings.spi->transfer(this->toAddr); // type of transmitter that should receive this message - // Now the payload - while (this->msgIndex++ != this->msgLen && !this->radio.spiRead(RH_RF69_IRQFLAGS2_FIFOFULL)) // these conditions need to be verified - this->settings.spi->transfer(this->msg[this->msgIndex]); - digitalWrite(this->settings.cs, HIGH); - this->settings.spi->endTransaction(); - ATOMIC_BLOCK_END; - - this->radio.setModeTx(); // Start the transmitter - return true; -} - -bool RFM69HCW::txT() -{ - if (!this->radio.spiRead(RH_RF69_IRQFLAGS2_FIFONOTEMPTY) || !this->radio.spiRead(RH_RF69_FIFOTHRESH_FIFOTHRESHOLD)) - { - // this is basically tx without preprocessing and no toAddr byte - ATOMIC_BLOCK_START; - this->settings.spi->beginTransaction(); - digitalWrite(this->settings.cs, LOW); - this->settings.spi->transfer(RH_RF69_REG_00_FIFO | RH_RF69_SPI_WRITE_MASK); // Send the start address with the write mask on - while (this->msgIndex++ != this->msgLen && !this->radio.spiRead(RH_RF69_IRQFLAGS2_FIFOFULL)) // these conditions need to be verified - this->settings.spi->transfer(this->msg[this->msgIndex]); - digitalWrite(this->settings.cs, HIGH); - this->settings.spi->endTransaction(); - ATOMIC_BLOCK_END; - return this->radio.spiRead(RH_RF69_IRQFLAGS2_PACKETSENT); - } - return false; -} - -void RFM69HCW::txe() // try to get rid of this one -{ - this->msgLen = -1; - this->id = 0x00; - this->radio.setHeaderId(this->id); -} - -/* -Receive function -Most basic receiving method, simply checks for a message and returns a pointer to it -Note that the message may be incomplete, if the message is complete available() will return true -The received message must be less than MSG_LEN -*/ -const char *RFM69HCW::rx() -{ - if (this->radio.available()) - { - // Should be a message for us now - uint8_t receivedLen = this->bufSize; - if (this->radio.recv(this->buf, &(receivedLen))) - { - // check if this is the first part of the message - if (this->totalPackets == 0) - { - this->totalPackets = this->radio.headerId(); - if (this->totalPackets <= 0) - return 0; - this->msgLen = 0; - this->rssi = 0; - } - - // copy data from this->buf to this->msg, making sure not to overflow - memcpy(this->msg + this->msgLen, this->buf, min(MSG_LEN - (this->msgLen + receivedLen), receivedLen)); - - this->msgLen += receivedLen; - this->id++; - this->rssi += radio.lastRssi(); - - // check if the full message has been received - if (this->totalPackets == this->id) - { - this->id = 0x00; - this->rssi /= this->totalPackets; - this->totalPackets = 0; - this->avail = true; - } - - return this->msg; - } - return 0; - } - return 0; -} - -/* -\return ```true``` if the radio is currently busy -*/ -bool RFM69HCW::busy() -{ - RHGenericDriver::RHMode mode = this->radio.mode(); - if (mode == RHGenericDriver::RHModeTx) - return true; - return false; -} - -/* -Multi-purpose encoder function -Encodes the message into a format selected by type -char *message is the message to be encoded -sets this->msgLen to the encoded length of message -- Telemetry: - message - input: latitude,longitude,altitude,speed,heading,precision,stage,t0 -> output: APRS message -- Video: - message - input: char* filled with raw bytes -> output: char* filled with raw bytes + error checking -- Ground Station: TODO - message - input: Source:Value,Destination:Value,Path:Value,Type:Value,Body:Value -> output: APRS message -*/ -bool RFM69HCW::encode(char *message, EncodingType type, int len) -{ - if (type == ENCT_TELEMETRY) - { - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - else if (this->msgLen == -1) - return false; - - // holds the data to be assembled into the aprs body - APRSData data; - - // find each value separated in order by a comma and put in the APRSData array - { - char *currentVal = new char[this->msgLen]; - int currentValIndex = 0; - int currentValCount = 0; - for (int i = 0; i < msgLen; i++) - { - if (message[i] != ',') - { - currentVal[currentValIndex] = message[i]; - currentValIndex++; - } - if (message[i] == ',' || (currentValCount == 7 && i == msgLen - 1)) - { - currentVal[currentValIndex] = '\0'; - - if (currentValCount == 0 && strlen(currentVal) < 16) - strcpy(data.lat, currentVal); - if (currentValCount == 1 && strlen(currentVal) < 16) - strcpy(data.lng, currentVal); - if (currentValCount == 2 && strlen(currentVal) < 10) - strcpy(data.alt, currentVal); - if (currentValCount == 3 && strlen(currentVal) < 4) - strcpy(data.spd, currentVal); - if (currentValCount == 4 && strlen(currentVal) < 4) - strcpy(data.hdg, currentVal); - if (currentValCount == 5) - data.precision = currentVal[0]; - if (currentValCount == 6 && strlen(currentVal) < 3) - strcpy(data.stage, currentVal); - if (currentValCount == 7 && strlen(currentVal) < 9) - strcpy(data.t0, currentVal); - - currentValIndex = 0; - currentValCount++; - } - } - - delete[] currentVal; - } - // get lat and long string for low or high precision - if (data.precision == 'L') - { - strcpy(data.dao, ""); - APRSMsg::formatLat(data.lat, 0); - APRSMsg::formatLong(data.lng, 0); - } - else if (data.precision == 'H') - { - APRSMsg::formatDao(data.lat, data.lng, data.dao); - APRSMsg::formatLat(data.lat, 1); - APRSMsg::formatLong(data.lng, 1); - } - // get alt string - int altInt = max(-99999, min(999999, atoi(data.alt))); - if (altInt < 0) - { - strcpy(data.alt, "/A=-"); - APRSMsg::padding(altInt * -1, 5, data.alt, 4); - } - else - { - strcpy(data.alt, "/A="); - APRSMsg::padding(altInt, 6, data.alt, 3); - } - - // get course/speed strings - // TODO add speed zero counter (makes decoding more complex) - int spd_int = max(0, min(999, atoi(data.spd))); - int hdg_int = max(0, min(360, atoi(data.hdg))); - if (hdg_int == 0) - hdg_int = 360; - APRSMsg::padding(spd_int, 3, data.spd); - APRSMsg::padding(hdg_int, 3, data.hdg); - - // generate the aprs message - APRSMsg aprs; - - aprs.setSource(this->cfg.CALLSIGN); - aprs.setPath(this->cfg.PATH); - aprs.setDestination(this->cfg.TOCALL); - - char body[80]; - sprintf(body, "%c%s%c%s%c%s%c%s%s%s%s%c%s%c%s", '!', data.lat, this->cfg.OVERLAY, data.lng, this->cfg.SYMBOL, - data.hdg, '/', data.spd, data.alt, "/S", data.stage, '/', - data.t0, ' ', data.dao); - aprs.getBody()->setData(body); - aprs.encode(message); - return true; - } - if (type == ENCT_VIDEO) - { - // lower bound for received message length, for basic error checking - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - // if len wasn't set, make sure this->msgLen is - if (this->msgLen == -1) - return false; - message[this->msgLen] = this->msgLen / 255; - } - if (type == ENCT_NONE) - return true; - return false; -} - -/* -Multi-purpose decoder function -Decodes the message into a format selected by type -char *message is the message to be decoded -sets this->msgLen to the length of the decoded message -- Telemetry: TODO: fix - message - output: latitude,longitude,altitude,speed,heading,precision,stage,t0 <- input: APRS message -- Video: TODO - message - output: char* filled with raw bytes <- input: Raw byte array -- Ground Station: - message - output: Source:Value,Destination:Value,Path:Value,Type:Value,Body:Value <- input: APRS message -*/ -bool RFM69HCW::decode(char *message, EncodingType type, int len) -{ - if (type == ENCT_TELEMETRY) - { - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - else if (this->msgLen == -1) - return false; - - // make sure message is null terminated - message[this->msgLen] = 0; - - APRSMsg aprs; - aprs.decode(message); - - char body[80]; - char *bodyptr = body; - strcpy(body, aprs.getBody()->getData()); - // decode body - APRSData data; - int i = 0; - int len = strlen(body); - - // TODO this could probably be shortened - // body should start with '!' - if (body[0] != '!') - return false; - i++; - bodyptr = body + i; - - // find latitude - while (body[i] != '/' && i != len) - i++; - if (i == len) - return false; - strncpy(data.lat, bodyptr, i - (bodyptr - body)); - data.lat[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find longitude - while (body[i] != '[' && i != len) - i++; - if (i == len) - return false; - strncpy(data.lng, bodyptr, i - (bodyptr - body)); - data.lng[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find heading - while (body[i] != '/' && i != len) - i++; - if (i == len) - return false; - strncpy(data.hdg, bodyptr, i - (bodyptr - body)); - data.hdg[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find speed - while (body[i] != '/' && i != len) - i++; - if (i == len) - return false; - strncpy(data.spd, bodyptr, i - (bodyptr - body)); - data.spd[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find altitude - if (body[i] != 'A' && body[i + 1] != '=') - return false; - i += 2; - bodyptr = body + i; - while (body[i] != '/' && i != len) - i++; - if (i == len) - return false; - strncpy(data.alt, bodyptr, i - (bodyptr - body)); - data.alt[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find stage - if (body[i] != 'S') - return false; - i++; - bodyptr = body + i; - while (body[i] != '/' && i != len) - i++; - if (i == len) - return false; - strncpy(data.stage, bodyptr, i - (bodyptr - body)); - data.stage[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find t0 - while (body[i] != ' ' && i != len) - i++; - if (i == len) - return false; - strncpy(data.t0, bodyptr, i - (bodyptr - body)); - data.t0[i - (bodyptr - body)] = 0; - i++; - bodyptr = body + i; - - // find dao - strncpy(data.dao, bodyptr, len - (bodyptr - body)); - data.dao[len - (bodyptr - body)] = '\0'; - - // convert lat and lng to degrees - - int latMult = (data.lat[strlen(data.lat) - 1] == 'N') ? 1 : -1; - int lngMult = (data.lat[strlen(data.lat) - 1] == 'E') ? 1 : -1; - - int lenLat = strlen(data.lat); - int decimalPosLat = 0; - // use for loop in case there is no decimal - for (int i = 0; i < lenLat; i++) - { - if (data.lat[i] == '.') - { - decimalPosLat = i; - break; - } - } - - int lenLng = strlen(data.lng); - int decimalPosLng = 0; - // use for loop in case there is no decimal - for (int i = 0; i < lenLng; i++) - { - if (data.lng[i] == '.') - { - decimalPosLng = i; - break; - } - } - - double lat = 0; - for (int i = decimalPosLat - 3; i >= 0; i--) - { - int t = data.lat[i]; - for (int j = 0; j < i; j++) - t *= 10; - lat += t; - } - - double latMins = 0; - for (int i = lenLat - 2; i > decimalPosLat - 3; i--) - { - if (data.lat[i] == '.') - continue; - double t = data.lat[i]; - for (int j = (lenLat - 2 - decimalPosLat) * -1; j < i - 2; j++) - t *= j < 0 ? 1 / 10 : 10; - latMins += t; - } - latMins /= 60; - - lat += latMins; - - double lng = 0; - for (int i = decimalPosLng - 3; i >= 0; i--) - { - int t = data.lng[i]; - for (int j = 0; j < i; j++) - t *= 10; - lat += t; - } - - double lngMins = 0; - for (int i = lenLng - 2; i > decimalPosLng - 3; i--) - { - if (data.lng[i] == '.') - continue; - double t = data.lng[i]; - for (int j = (lenLng - 2 - decimalPosLng) * -1; j < i - 2; j++) - t *= j < 0 ? 1 / 10 : 10; - lngMins += t; - } - lngMins /= 60; - - lng += lngMins; - - lat *= latMult; - lng *= lngMult; - - sprintf(message, "%f,%f,%s,%s,%s,%c,%s,%s", lat, lng, data.alt, data.spd, data.hdg, strlen(data.dao) > 0 ? 'H' : 'L', data.stage, data.t0); - - this->msgLen = strlen(message); - return true; - } - if (type == ENCT_GROUNDSTATION) - { - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - else if (this->msgLen == -1) - return false; - - // make sure message is null terminated - message[this->msgLen] = 0; - - // put the message into a APRSMessage object to decode it - APRSMsg aprs; - aprs.decode(message); - aprs.toString(message); - - // add RSSI to the end of message - sprintf(message + strlen(message), "%s%d", ",RSSI:", this->rssi); - - this->msgLen = strlen(message); - return true; - } - if (type == ENCT_VIDEO) - { - if (len > 0) - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - - // if len wasn't set, make sure this->msgLen is - if (this->msgLen == -1) - return false; - - // otherwise, check if the length of the message is within the expected bounds - return this->msgLen >= message[this->msgLen] * 255 && this->msgLen < (message[this->msgLen] + 1) * 255; - } - if (type == ENCT_NONE) - return true; - return false; -} - -/* -Encodes the message into the selected type, then sends it. Transmitted and encoded message length must not exceed ```MSG_LEN``` - \param message is the message to be sent - \param type is the encoding type - \param len optional length of message, required if message is not a null terminated string -\return ```true``` if the message was sent successfully -*/ -bool RFM69HCW::send(const char *message, EncodingType type, int len) -{ - if (type == ENCT_TELEMETRY || type == ENCT_GROUNDSTATION) - { - // assume message is a valid string, but maybe it's not null terminated - strncpy(this->msg, message, MSG_LEN); - this->msg[MSG_LEN] = 0; // so null terminate it just in case - // figure out what the length of the message should be - if (len > 0 && len <= MSG_LEN) - this->msgLen = len; - else - this->msgLen = strlen(this->msg); - return encode(this->msg, type, this->msgLen) && tx(nullptr, strlen(this->msg)); // length needs to be updated since encode() modifies the message - } - if (type == ENCT_VIDEO && len != -1) - { - // can't assume message is a valid string - this->msgLen = len > MSG_LEN ? MSG_LEN : len; - memcpy(this->msg, message, this->msgLen); - return encode(this->msg, type) && tx(nullptr); // length does not change with ENCT_VIDEO - } - if (type == ENCT_NONE && len != -1) - { - return tx(message, len); - } - return false; -} - -/* -Comprehensive receive function -Should be called after verifying there is an available message by calling available() -Decodes the last received message according to the type -Received and decoded message length must not exceed MSG_LEN - \param type is the decoding type -*/ -const char *RFM69HCW::receive(EncodingType type) -{ - if (this->avail) - { - this->avail = false; - if (!decode(this->msg, type, this->msgLen)) // Note: this->msgLen is never set to -1 - return 0; - return this->msg; - } - return 0; -} - -/* -Returns true if a there is a new message -*/ -bool RFM69HCW::available() -{ - rx(); - return this->avail; -} - -/* -Returns the RSSI of the last message -*/ -int RFM69HCW::RSSI() -{ - return this->rssi; -} - -// probably broken -void RFM69HCW::set300KBPS() -{ - this->radio.spiWrite(0x03, 0x00); // REG_BITRATEMSB: 300kbps (0x006B, see DS p20) - this->radio.spiWrite(0x04, 0x6B); // REG_BITRATELSB: 300kbps (0x006B, see DS p20) - this->radio.spiWrite(0x19, 0x40); // REG_RXBW: 500kHz - this->radio.spiWrite(0x1A, 0x80); // REG_AFCBW: 500kHz - this->radio.spiWrite(0x05, 0x13); // REG_FDEVMSB: 300khz (0x1333) - this->radio.spiWrite(0x06, 0x33); // REG_FDEVLSB: 300khz (0x1333) - this->radio.spiWrite(0x29, 240); // set REG_RSSITHRESH to -120dBm - this->radio.spiWrite(0x37, 0b10010000); // DC=WHITENING, CRCAUTOOFF=0 - // ^^->DC: 00=none, 01=manchester, 10=whitening -} - -// utility functions -#ifndef max -int max(int a, int b) -{ - if (a > b) - return a; - return b; -} -#endif - -#ifndef min -int min(int a, int b) -{ - if (a < b) - return a; - return b; -} -#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h deleted file mode 100644 index 19abb2ff..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h +++ /dev/null @@ -1,87 +0,0 @@ -#ifndef RFM69HCW_H -#define RFM69HCW_H - -#if defined(ARDUINO) -#define MSG_LEN 200 -#elif defined(TEENSYDUINO) -#define MSG_LEN 10 * 1024 -#elif defined(RASPBERRY_PI) -#define MSG_LEN 10 * 1024 -#endif - -#include "Radio.h" -#include "APRSMsg.h" -#include "RH_RF69.h" - -/* -Settings: -- double frequency in Mhz -- bool transmitter -- bool highBitrate -- RHGenericSPI *spi pointer to radiohead SPI object -- uint8_t cs CS pin -- uint8_t irq IRQ pin -- uint8_t rst RST pin -*/ -struct RadioSettings -{ - double frequency; - bool transmitter; - bool highBitrate; - RHGenericSPI *spi; - uint8_t cs; - uint8_t irq; - uint8_t rst; -}; - -class RFM69HCW : public Radio -{ -public: - RFM69HCW(const RadioSettings *s, const APRSConfig *config); - bool begin() override; - bool tx(const char *message, int len = -1) override; - bool sendBuffer(); - void endtx(); - bool txs(const char *message, int len = -1); - bool txT(); - void txe(); - const char *rx() override; - void rxL(); - bool busy(); - bool encode(char *message, EncodingType type, int len = -1) override; - bool decode(char *message, EncodingType type, int len = -1) override; - bool send(const char *message, EncodingType type, int len = -1) override; - const char *receive(EncodingType type) override; - int RSSI() override; - bool available(); - void set300KBPS(); - RHGenericDriver::RHMode mode(); - - // stores full messages, max length determined by platform - char msg[MSG_LEN + 1]; - // length of msg for recieving binary messages - int msgLen = 0; - -private: - RH_RF69 radio; - // all radios should have the same networkID - const uint8_t networkID = 0x01; - // default to the highest transmit power - const int txPower = 20; - // set by constructor - uint8_t addr; - uint8_t toAddr; - uint8_t id; - RadioSettings settings; - // for sending/receiving data - // stores messages sent to radio, length determined by max radio message length - uint8_t buf[RH_RF69_MAX_MESSAGE_LEN + 1]; - uint8_t bufSize = RH_RF69_MAX_MESSAGE_LEN; - APRSConfig cfg; - bool avail; - int rssi; - int totalPackets; - int msgIndex = 0; -}; - -#endif // RFM69HCW_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp new file mode 100644 index 00000000..50727b56 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp @@ -0,0 +1,324 @@ +#include "RFM69HCWNew.h" + +#ifndef max +int max(int a, int b); +#endif + +#ifndef min +int min(int a, int b); +#endif + +/* +Constructor + - frequency in hertz + - transmitter true if the radio will be on the rocket + - highBitrate true for 300kbps, false for 4.8kbps + - config with APRS settings +*/ +RFM69HCWNew::RFM69HCWNew(const RadioSettings *s) : radio(s->cs, s->irq, *s->spi) +{ + + this->settings = *s; + this->avail = false; + + if (this->settings.transmitter) + { + // addresses for transmitters + this->thisAddr = 0x02; + this->toAddr = 0x01; + } + else + { + // addresses for receivers + this->thisAddr = 0x01; + this->toAddr = 0x02; + } +} + +/* +Initializer to call in setup +*/ +bool RFM69HCWNew::init() +{ + // reset the radio + pinMode(settings.rst, OUTPUT); + digitalWrite(settings.rst, LOW); + delay(10); + digitalWrite(settings.rst, HIGH); + delay(10); + digitalWrite(settings.rst, LOW); + + if (!radio.init()) + return false; + + // then use this to actually set the frequency + if (!radio.setFrequency(settings.frequency)) + return false; + + // set transmit power + radio.setTxPower(txPower, true); + + // always set FSK mode + radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); + + // set headers + radio.setHeaderTo(toAddr); + radio.setHeaderFrom(thisAddr); + radio.setThisAddress(thisAddr); + radio.setHeaderId(0); + + // configure unlimited packet length mode, don't do this for now + // this->radio.spiWrite(0x37, 0b00000000); // Packet format (0x37) set to 00000000 (see manual for meaning of each bit) + // this->radio.spiWrite(RH_RF69_REG_38_PAYLOADLENGTH, 0); // Payload length (0x38) set to 0 + + if (this->settings.highBitrate) // Note: not working + { + // the default bitrate of 4.8kbps should be fine unless we want high bitrate for video + // set300KBPS(); + this->radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); + // remove as much overhead as possible + // this->radio.setPreambleLength(0); + // this->radio.setSyncWords(); + } + + return initialized = true; +} + +/* +Most basic transmission method, simply transmits the string without modification + \param message is the message to be transmitted must be less than maxDataLen + \param len optional length of message, required if message is not a null terminated string +*/ +bool RFM69HCWNew::tx(const uint8_t *message, int len, int packetNum, bool lastPacket) +{ + // figure out how long the message should be + if (len == -1) + { + len = strlen((char *)message); + } + radio.setHeaderId(packetNum); + radio.setHeaderFlags(lastPacket ? 0 : RADIO_FLAG_MORE_DATA); + + return radio.send((uint8_t *)message, len); +} + +/* +Receive function +Most basic receiving method, simply checks for a message and returns it +Note that the message may be incomplete, if the message is complete available() will return true +The received message will be truncated if it exceeds the maximum message length +\return the received message with the length in the first byte or `nullptr` if no message is available +*/ +const uint8_t *RFM69HCWNew::rx() +{ + if (!radio.available()) + return nullptr; + + // Should be a message for us now + // Stores the length of the message in the first byte of the returned array + uint8_t receivedLen; + uint8_t receivedMsg[1 + maxDataLen]; + if (!radio.recv(1 + receivedMsg, &(receivedLen))) + return nullptr; + + receivedMsg[0] = receivedLen; + rssi = radio.lastRssi(); + return receivedMsg; +} + + + +#pragma region External Send and Receive + + + +bool RFM69HCWNew::enqueueSend(const uint8_t *message, uint8_t len) +{ + // fill up the buffer with the message. buffer is a circular queue. + buffer[bufTail] = len; + bufTail = (bufTail + 1) % RADIO_BUFFER_SIZE; + for (int i = 0; i < len; i++) + { + if (bufTail == bufHead) // buffer is full + return false; + + buffer[bufTail] = message[i]; + bufTail = (bufTail + 1) % RADIO_BUFFER_SIZE; + } + + return true; +} + +bool RFM69HCWNew::enqueueSend(const char *message) +{ + return enqueueSend((uint8_t *)message, strlen(message)); +} + +bool RFM69HCWNew::enqueueSend(RadioMessage *message) +{ + return enqueueSend(message->encode(), message->length()); +} + +bool RFM69HCWNew::dequeueReceive(uint8_t *message) +{ + if (bufHead == bufTail) // buffer is empty + return false; + + // get the length of the message + int len = buffer[bufHead]; + inc(bufHead); + // Empty the buffer up to the length of the expected message + for (int i = 0; i < len && bufHead != bufTail; i++) + { + message[i] = buffer[bufHead]; + inc(bufHead); + } + return true; +} + +bool RFM69HCWNew::dequeueReceive(char *message) +{ + if (bufHead == bufTail) + return false; + + // Empty the buffer up to the first null terminator + inc(bufHead); // skip the length byte + int i = 0; + for (; buffer[bufHead] != '\0' && bufHead != bufTail; i++) + { + message[i] = buffer[bufHead]; + inc(bufHead); + } + message[i] = '\0'; + + return true; +} + +bool RFM69HCWNew::dequeueReceive(RadioMessage *message) +{ + if (bufHead == bufTail) + return false; + + uint8_t len = buffer[bufHead]; + uint8_t *msg = new uint8_t[len]; + if (!dequeueReceive(msg)) + return false; + + message->decode(msg, len); + delete[] msg; + return true; +} + +#pragma endregion + + + +bool RFM69HCWNew::update() +{ + if (busy()) // radio is busy, cannot send or receive + return false; + if (settings.transmitter) + { + if (bufHead == bufTail) + { // buffer is empty, nothing to send + remainingLength = 0; + return false; + } + // send the message + if (remainingLength == 0) // start a new message + { + remainingLength = buffer[bufHead]; + inc(bufHead); + tx(&buffer[bufHead], min(remainingLength, maxDataLen), 0, remainingLength <= maxDataLen); + } + else // continue the message + { + int len = min(remainingLength, maxDataLen); + remainingLength -= len; + tx(&buffer[bufHead], len, radio.headerId() + 1, remainingLength <= maxDataLen); + } + } + else // receiver + { + const uint8_t *msg = rx(); + if (msg == nullptr) + return false; + // store the message in the buffer + if (radio.headerId() == 0) + { // start of a new message + orignalBufferTail = bufTail; + buffer[bufTail] = msg[0]; // store the length of the message + inc(bufTail); + for (int i = 1; i <= msg[0]; i++) + { + buffer[bufTail] = msg[i]; + inc(bufTail); + } + } + else + { + buffer[orignalBufferTail] += msg[0]; // update the length of the message + for (int i = 1; i <= msg[0]; i++) + { + buffer[bufTail] = msg[i]; + inc(bufTail); + } + } + } + return true; +} + +#pragma region Helpers + +/* +\return `true` if the radio is currently transmitting or receiving a message +*/ +bool RFM69HCWNew::busy() +{ + RHGenericDriver::RHMode mode = this->radio.mode(); + if (mode == RHGenericDriver::RHModeTx || mode == RHGenericDriver::RHModeRx) + return true; + return false; +} +/* +Returns the RSSI of the last message +*/ +int RFM69HCWNew::RSSI() +{ + return rssi; +} + +// probably broken +void RFM69HCWNew::set300KBPSMode() +{ + this->radio.spiWrite(0x03, 0x00); // REG_BITRATEMSB: 300kbps (0x006B, see DS p20) + this->radio.spiWrite(0x04, 0x6B); // REG_BITRATELSB: 300kbps (0x006B, see DS p20) + this->radio.spiWrite(0x19, 0x40); // REG_RXBW: 500kHz + this->radio.spiWrite(0x1A, 0x80); // REG_AFCBW: 500kHz + this->radio.spiWrite(0x05, 0x13); // REG_FDEVMSB: 300khz (0x1333) + this->radio.spiWrite(0x06, 0x33); // REG_FDEVLSB: 300khz (0x1333) + this->radio.spiWrite(0x29, 240); // set REG_RSSITHRESH to -120dBm + this->radio.spiWrite(0x37, 0b10010000); // DC=WHITENING, CRCAUTOOFF=0 + // ^^->DC: 00=none, 01=manchester, 10=whitening +} + +// utility functions +#ifndef max +int max(int a, int b) +{ + if (a > b) + return a; + return b; +} +#endif + +#ifndef min +int min(int a, int b) +{ + if (a < b) + return a; + return b; +} +#endif + +#pragma endregion diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h new file mode 100644 index 00000000..abfff3c1 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h @@ -0,0 +1,91 @@ +#ifndef RFM69HCW_H +#define RFM69HCW_H + +#if defined(ARDUINO) +#define MSG_LEN 200 +#elif defined(TEENSYDUINO) +#define MSG_LEN 10 * 1024 +#elif defined(RASPBERRY_PI) +#define MSG_LEN 10 * 1024 +#endif + +#include "Radio.h" +#include "APRSMsg.h" +#include "RH_RF69.h" + +#define RADIO_BUFFER_SIZE 1024 +#define RADIO_FLAG_MORE_DATA 0b00000001 // custom flag to indicate more packets are still to be sent + +/* +Settings: +- double frequency in Mhz +- bool transmitter +- bool highBitrate +- RHGenericSPI *spi pointer to radiohead SPI object +- uint8_t cs CS pin +- uint8_t irq IRQ pin +- uint8_t rst RST pin +*/ +struct RadioSettings +{ + double frequency; + bool transmitter; + bool highBitrate; + RHGenericSPI *spi; + uint8_t cs; + uint8_t irq; + uint8_t rst; + int txPower = 20; +}; + + +class RFM69HCWNew : public Radio +{ +public: + RFM69HCWNew(const RadioSettings *s); + bool init() override; + bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) override; // designed to be used internally. cannot exceed 66 bytes including headers + const uint8_t *rx() override; + bool busy(); + bool enqueueSend(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. + bool enqueueSend(const char *message) override; // designed to be used externally. can exceed 66 bytes. + bool enqueueSend(const uint8_t *message, uint8_t len) override; // designed to be used externally. can exceed 66 bytes. + + bool dequeueReceive(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. + bool dequeueReceive(char *message) override; // designed to be used externally. can exceed 66 bytes. + bool dequeueReceive(uint8_t *message) override; // designed to be used externally. can exceed 66 bytes. + int RSSI() override; + void set300KBPSMode(); + bool update(); + + explicit operator bool() const { return initialized; } + + // increment the specified index, wrapping around if necessary + static void inc(int &i) { i = (i + 1) % RADIO_BUFFER_SIZE; } + +private: + RH_RF69 radio; + // all radios should have the same networkID + const uint8_t networkID = 1; + // default to the highest transmit power + const int txPower = 20; + // set by constructor + RadioSettings settings; + int thisAddr; + int toAddr; + bool avail; + int rssi; + bool initialized = false; + + // stores queue of messages, with the length of the message as the first byte of each. no delimiter. + // [6xxxxxx3xxx1x2xx] + // Done to allow for messages that are not ascii encoded. + uint8_t buffer[RADIO_BUFFER_SIZE]; + int bufHead = 0; + int bufTail = 0; + int remainingLength = 0; // how much message is left to send for transmitters + int orignalBufferTail = 0; // used to update the length of the message after recieving. + int maxDataLen = RH_RF69_MAX_MESSAGE_LEN; +}; + +#endif // RFM69HCW_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index 9902f6fa..1558d460 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -103,7 +103,7 @@ bool State::init() } if (radio) { - if (!radio->begin()) + if (!radio->init()) radio = nullptr; } setCsvHeader(); @@ -488,8 +488,16 @@ bool State::transmit() { char data[200]; snprintf(data, 200, "%f,%f,%i,%i,%i,%c,%i,%s", sensorOK(gps) ? gps->getPos().x() : 0, sensorOK(gps) ? gps->getPos().y() : 0, sensorOK(baro) ? (int)baro->getRelAltFt() : 0, (int)(baroVelocity * 3.28), (int)headingAngle, 'H', stageNumber, launchTimeOfDay); - bool b = radio->send(data, ENCT_TELEMETRY); - return b; + aprs.data.lat = sensorOK(gps) ? gps->getPos().x() : 0; + aprs.data.lng = sensorOK(gps) ? gps->getPos().y() : 0; + aprs.data.alt = sensorOK(baro) ? baro->getRelAltFt() : 0; + aprs.data.hdg = (int)headingAngle; + aprs.data.spd = (int)(baroVelocity * 3.28); + aprs.data.stage = stageNumber; + aprs.data.orientation = imu->getOrientation().toEuler(); + + radio->enqueueSend(&aprs); + return true; } extern unsigned long _heap_start; extern unsigned long _heap_end; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h index 2bb88a72..35bd6c78 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h @@ -12,6 +12,8 @@ #include "Radio.h" #include "RTC.h" #include "RecordData.h" +#include "APRSMsg.h" + constexpr char STAGES[][15] = {"Pre-Flight", "Boosting", "Coasting", "Drogue Descent", "Main Descent", "Post-Flight"}; class State { @@ -114,6 +116,10 @@ class State double *inputs; uint32_t FreeMem(); + // APRS + APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1"}; + + APRSMsg aprs = {header}; }; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 160e5681..6cf37858 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -4,17 +4,15 @@ #include "BNO055.h" #include "MAX_M10S.h" #include "DS3231.h" -#include "RFM69HCW.h" +#include "RFM69HCWNew.h" #include "RecordData.h" #include "BlinkBuzz.h" BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 -DS3231 rtc(); // I2C Address 0x68 -APRSConfig config = {"KC3UTM", "APRS", "WIDE1-1", '[', '/'}; RadioSettings settings = {433.775, true, false, &hardware_spi, 10, 31, 32}; -RFM69HCW radio = {settings, config}; +RFM69HCWNew radio(&settings); State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); @@ -103,23 +101,19 @@ void setup() } sendSDCardHeader(computer.getCsvHeader()); } -static bool more = false; static bool first = false; static bool second = false; void loop() { bb.update(); + radio.update(); double time = millis(); if (time - radioTimer >= 500) { - more = computer.transmit(); + computer.transmit(); radioTimer = time; } - if (radio.mode() != RHGenericDriver::RHModeTx && more) - { - more = !radio.sendBuffer(); - } if (time - last < 100) return; From 4d80987f4d3d89cf0c6135008578a721311d5d4b Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 15 May 2024 17:00:40 -0400 Subject: [PATCH 12/41] After VS22 --- .../Teensy-Based Avionics/include/Radio.h | 6 +- .../Teensy-Based Avionics/src/APRSMsg.cpp | 19 +- .../Code/Teensy-Based Avionics/src/APRSMsg.h | 16 +- .../Teensy-Based Avionics/src/APRSMsgOld.cpp | 372 ------------------ .../Teensy-Based Avionics/src/APRSMsgOld.h | 227 ----------- .../Teensy-Based Avionics/src/RFM69HCWNew.cpp | 56 +-- .../Teensy-Based Avionics/src/RFM69HCWNew.h | 28 +- 7 files changed, 56 insertions(+), 668 deletions(-) delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h index 2f46df68..64eba141 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h @@ -31,7 +31,7 @@ enum EncodingType class RadioMessage { public: - virtual const uint8_t *encode() = 0; // use stored variables to encode a message + virtual uint8_t *encode() = 0; // use stored variables to encode a message virtual bool decode(const uint8_t *message, int len) = 0; // use `message` to set stored variables virtual int length() const = 0; // return the length of the message virtual ~RadioMessage(){}; @@ -46,7 +46,7 @@ class Radio virtual ~Radio(){}; // Virtual descructor. Very important virtual bool init() = 0; virtual bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) = 0; // designed to be used internally. cannot exceed 66 bytes including headers - virtual const uint8_t *rx() = 0; + virtual bool rx(uint8_t *recvbuf, uint8_t *len) = 0; virtual int RSSI() = 0; virtual bool enqueueSend(const uint8_t *message, uint8_t len) = 0; virtual bool enqueueSend(const char *message) = 0; @@ -56,6 +56,4 @@ class Radio virtual bool dequeueReceive(uint8_t *message) = 0; }; - - #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index 527eab30..2953353b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -1,16 +1,13 @@ #include "APRSMsg.h" - #define MAX_ALLOWED_MSG_LEN 255 /* max length of 1 message supported by radio buffer */ - - APRSMsg::APRSMsg(APRSHeader &header) { this->header = header; } -const uint8_t *APRSMsg::encode() +uint8_t *APRSMsg::encode() { char *msg = new char[MAX_ALLOWED_MSG_LEN]; int c = encodeHeader(msg); @@ -20,7 +17,7 @@ const uint8_t *APRSMsg::encode() bool APRSMsg::decode(const uint8_t *message, int len) { - //message needs to be decoded and values reinstered into the header and data structs + // message needs to be decoded and values reinserted into the header and data structs int c = decodeHeader((char *)message, len); decodeData((char *)message, len, c); return false; @@ -74,19 +71,19 @@ void APRSMsg::encodeData(char *message, int cursor) */ // lat and lng - message[cursor++] = 'M'; // overlay + message[cursor++] = 'M'; // overlay encodeBase91(message, cursor, (int)380926 * (90 - data.lat), 4); // 380926 is the magic number from the APRS spec (page 38) encodeBase91(message, cursor, (int)190463 * (180 + data.lng), 4); // 190463 is the magic number from the APRS spec (page 38) - message[cursor++] = '^'; // end of lat and lng - message[cursor++] = ' '; // space to start 'Comment' section + message[cursor++] = '^'; // end of lat and lng + message[cursor++] = ' '; // space to start 'Comment' section // course, speed, altitude - encodeBase91(message, cursor, (int)(data.hdg * HDG_SCALE), 2); // (91^2/360) scale to fit in 2 base91 characters - encodeBase91(message, cursor, (int)(data.spd * SPD_SCALE), 2); // (91^2/1000) scale to fit in 2 base91 characters. 1000 knots is the assumed max speed. + encodeBase91(message, cursor, (int)(data.hdg * HDG_SCALE), 2); // (91^2/360) scale to fit in 2 base91 characters + encodeBase91(message, cursor, (int)(data.spd * SPD_SCALE), 2); // (91^2/1000) scale to fit in 2 base91 characters. 1000 knots is the assumed max speed. encodeBase91(message, cursor, (int)(data.alt * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. // stage and orientation - message[cursor++] = (char)(data.stage + (int)'0'); // stage is just written in plaintext. + message[cursor++] = (char)(data.stage + (int)'0'); // stage is just written in plaintext. encodeBase91(message, cursor, (int)(data.orientation.x() * ORIENTATION_SCALE), 2); // same as course encodeBase91(message, cursor, (int)(data.orientation.y() * ORIENTATION_SCALE), 2); // same as course encodeBase91(message, cursor, (int)(data.orientation.z() * ORIENTATION_SCALE), 2); // same as course diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h index 5eb8f32e..a8001939 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h @@ -16,8 +16,6 @@ #include "Radio.h" #include - - /* APRS Configuration - CALLSIGN @@ -54,7 +52,6 @@ struct APRSData imu::Vector<3> orientation; }; - class APRSMsg : public RadioMessage { public: @@ -62,13 +59,12 @@ class APRSMsg : public RadioMessage virtual ~APRSMsg(){}; bool decode(const uint8_t *message, int len) override; - const uint8_t *encode() override; + uint8_t *encode() override; int length() const override { return this->len; } APRSData data; APRSHeader header; private: - int encodeHeader(char *message) const; void encodeData(char *message, int cursor); @@ -78,13 +74,11 @@ class APRSMsg : public RadioMessage void encodeBase91(char *message, int &cursor, int value, int precision) const; void decodeBase91(const char *message, int &cursor, double &value, int precision) const; - //Scale factors for encoding/decoding ignoring lat/long - const double ALT_SCALE = (pow(91, 2) / 15000.0); // (91^2/15000) scale to fit in 2 base91 characters - const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters - const double HDG_SCALE = (pow(91, 2) / 360.0); // (91^2/360) scale to fit in 2 base91 characters + // Scale factors for encoding/decoding ignoring lat/long + const double ALT_SCALE = (pow(91, 2) / 15000.0); // (91^2/15000) scale to fit in 2 base91 characters + const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters + const double HDG_SCALE = (pow(91, 2) / 360.0); // (91^2/360) scale to fit in 2 base91 characters const double ORIENTATION_SCALE = (pow(91, 2) / 360.0); // same as course }; - - #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp deleted file mode 100644 index 8adb533d..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.cpp +++ /dev/null @@ -1,372 +0,0 @@ -// /* -// MIT License - -// Copyright (c) 2020 Peter Buchegger - -// Permission is hereby granted, free of charge, to any person obtaining a copy -// of this software and associated documentation files (the "Software"), to deal -// in the Software without restriction, including without limitation the rights -// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -// copies of the Software, and to permit persons to whom the Software is -// furnished to do so, subject to the following conditions: - -// The above copyright notice and this permission notice shall be included in all -// copies or substantial portions of the Software. - -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -// SOFTWARE. -// */ - -// #include "APRSMsg.h" - -// char *s_min_nn(uint32_t min_nnnnn, int high_precision); -// int numDigits(unsigned int num); - -// APRSMsg::APRSMsg() : _body() -// { -// } - -// APRSMsg::APRSMsg(APRSMsg &otherMsg) -// : _type(otherMsg.getType()), _body() -// { -// strcpy(_source, otherMsg.getSource()); -// strcpy(_destination, otherMsg.getDestination()); -// strcpy(_path, otherMsg.getPath()); -// strcpy(_rawBody, otherMsg.getRawBody()); -// _body.setData(otherMsg.getBody()->getData()); -// } - -// APRSMsg &APRSMsg::operator=(APRSMsg &otherMsg) -// { -// if (this != &otherMsg) -// { -// setSource(otherMsg.getSource()); -// setDestination(otherMsg.getDestination()); -// setPath(otherMsg.getPath()); -// _type = otherMsg.getType(); -// strcpy(_rawBody, otherMsg.getRawBody()); -// _body.setData(otherMsg.getBody()->getData()); -// } -// return *this; -// } - -// APRSMsg::~APRSMsg() -// { -// } - -// const char *APRSMsg::getSource() -// { -// return _source; -// } - -// void APRSMsg::setSource(const char source[8]) -// { -// strcpy(_source, source); -// } - -// const char *APRSMsg::getDestination() -// { -// return _destination; -// } - -// void APRSMsg::setDestination(const char destination[8]) -// { -// strcpy(_destination, destination); -// } - -// const char *APRSMsg::getPath() -// { -// return _path; -// } - -// void APRSMsg::setPath(const char path[10]) -// { -// strcpy(_path, path); -// } - -// APRSMessageType APRSMsg::getType() -// { -// return _type; -// } - -// const char *APRSMsg::getRawBody() -// { -// return _rawBody; -// } - -// APRSBody *APRSMsg::getBody() -// { -// return &_body; -// } - -// bool APRSMsg::decode(char *message) -// { -// int len = strlen(message); -// int posSrc = -1, posDest = -1, posPath = -1; -// for (int i = 0; i < len; i++) -// { -// if (message[i] == '>' && posSrc == -1) -// posSrc = i; -// if (message[i] == ',' && posDest == -1) -// posDest = i; -// if (message[i] == ':' && posPath == -1) -// posPath = i; -// } -// if (posSrc >= 8) -// return false; -// if (posDest - (posSrc + 1) >= 8) -// return false; -// if (posPath - (posDest + 1) >= 10) -// return false; - -// if (posSrc >= 0) -// { -// strncpy(_source, message, posSrc); -// _source[posSrc] = '\0'; -// } -// else -// { -// _source[0] = '\0'; -// } - -// if (posDest != -1 && posDest < posPath) -// { -// strncpy(_path, message + posDest + 1, posPath - (posDest + 1)); -// strncpy(_destination, message + posSrc + 1, posDest - (posSrc + 1)); -// _path[posPath - (posDest + 1)] = '\0'; -// _destination[posDest - (posSrc + 1)] = '\0'; -// } -// else -// { -// _path[0] = '\0'; -// if (posSrc >= 0 && posPath >= 0) -// { - -// strncpy(_destination, message + posSrc + 1, posPath - (posSrc + 1)); -// _destination[posPath - (posSrc + 1)] = '\0'; -// } -// else -// { -// _destination[0] = '\0'; -// } -// } -// strcpy(_rawBody, message + posPath + 1); -// _rawBody[strlen(message + posPath + 1)] = '\0'; -// _type = APRSMessageType(_rawBody[0]); -// _body.decode(_rawBody); -// return bool(_type); -// } - -// void APRSMsg::encode(char *message) -// { -// sprintf(message, "%s>%s", _source, _destination); -// if (strlen(_path) > 0) -// { -// sprintf(message + strlen(message), ",%s", _path); -// } -// sprintf(message + strlen(message), ":%s", _body.encode()); -// } - -// void APRSMsg::toString(char *str) -// { -// char body[87]; -// _body.toString(body); -// sprintf(str, "Source:%s,Destination:%s,Path:%s,Type:%s,%s", _source, _destination, _path, _type.toString(), body); -// } - -// APRSBody::APRSBody() -// { -// } - -// APRSBody::~APRSBody() -// { -// } - -// const char *APRSBody::getData() -// { -// return _data; -// } - -// void APRSBody::setData(const char data[80]) -// { -// strcpy(_data, data); -// } - -// bool APRSBody::decode(char *message) -// { -// strcpy(_data, message); -// return true; -// } - -// const char *APRSBody::encode() -// { -// return _data; -// } - -// void APRSBody::toString(char *str) -// { -// sprintf(str, "Data:%s", _data); -// } - -// // creates the latitude string for the APRS message based on whether the GPS coordinates are high precision -// void APRSMsg::formatLat(char *lat, bool hp) -// { -// bool negative = lat[0] == '-'; - -// int len = strlen(lat); -// int decimalPos = 0; -// // use for loop in case there is no decimal -// for (int i = 0; i < len; i++) -// { -// if (lat[i] == '.') -// { -// decimalPos = i; -// break; -// } -// } -// int decLen = strlen(lat + decimalPos + 1); -// int dec = atoi(lat + decimalPos + 1); - -// // make sure there are nine digits -// int missingDigits = 9 - decLen; -// if (missingDigits < 0) -// for (int i = 0; i < missingDigits * -1; i++) -// dec /= 10; -// if (missingDigits > 0) -// for (int i = 0; i < missingDigits; i++) -// dec *= 10; - -// // we like sprintf's float up-rounding. -// // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation -// // ;) -// sprintf(lat, "%02d%s%c", atoi(lat) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'S' : 'N'); -// } - -// // creates the longitude string for the APRS message based on whether the GPS coordinates are high precision -// void APRSMsg::formatLong(char *lng, bool hp) -// { -// bool negative = lng[0] == '-'; - -// int len = strlen(lng); -// int decimalPos = 0; -// // use for loop in case there is no decimal -// for (int i = 0; i < len; i++) -// { -// if (lng[i] == '.') -// { -// decimalPos = i; -// break; -// } -// } - -// int decLen = strlen(lng + decimalPos + 1); -// int dec = atoi(lng + decimalPos + 1); - -// // make sure there are nine digits -// int missingDigits = 9 - decLen; -// if (missingDigits < 0) -// for (int i = 0; i < missingDigits * -1; i++) -// dec /= 10; -// if (missingDigits > 0) -// for (int i = 0; i < missingDigits; i++) -// dec *= 10; - -// // we like sprintf's float up-rounding. -// // but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation -// // ;) -// sprintf(lng, "%02d%s%c", atoi(lng) * (negative ? -1 : 1), s_min_nn(dec, hp), negative ? 'W' : 'E'); -// } - -// // creates the dao at the end of aprs message based on latitude and longitude -// void APRSMsg::formatDao(char *lat, char *lng, char *dao) -// { -// // !DAO! extension, use Base91 format for best precision -// // /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest -// // integer https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm -// // http://www.aprs.org/aprs12/datum.txt - -// int len = strlen(lat); -// int decimalPos = 0; -// // use for loop in case there is no decimal -// for (int i = 0; i < len; i++) -// { -// if (lat[i] == '.') -// decimalPos = i; -// } -// sprintf(dao, "!w%s", s_min_nn((int)(lat + decimalPos + 1), 2)); - -// len = strlen(lng); -// decimalPos = 0; -// for (int i = 0; i < len; i++) -// { -// if (lng[i] == '.') -// decimalPos = i; -// } -// sprintf(dao + 3, "%s!", s_min_nn((int)(lng + decimalPos + 1), 2)); -// } - -// // adds a specified number of zeros to the begining of a number -// void APRSMsg::padding(unsigned int number, unsigned int width, char *output, int offset) -// { -// unsigned int numLen = numDigits(number); -// if (numLen > width) -// { -// width = numLen; -// } -// for (unsigned int i = 0; i < width - numLen; i++) -// { -// output[offset + i] = '0'; -// } -// sprintf(output + offset + width - numLen, "%u", number); -// } - -// // takes in decimal minutes and converts to MM.dddd -// char *s_min_nn(uint32_t min_nnnnn, int high_precision) -// { -// /* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth -// * degree (-> *= 6 -> nn.mmmmmm minutes) high_precision: 0: round at decimal -// * position 2. 1: round at decimal position 4. 2: return decimal position 3-4 -// * as base91 encoded char -// */ - -// static char buf[6]; - -// min_nnnnn = min_nnnnn * 0.006; - -// if (high_precision) -// { -// if ((min_nnnnn % 10) >= 5 && min_nnnnn < 6000000 - 5) -// { -// // round up. Avoid overflow (59.999999 should never become 60.0 or more) -// min_nnnnn = min_nnnnn + 5; -// } -// } -// else -// { -// if ((min_nnnnn % 1000) >= 500 && min_nnnnn < (6000000 - 500)) -// { -// // round up. Avoid overflow (59.9999 should never become 60.0 or more) -// min_nnnnn = min_nnnnn + 500; -// } -// } - -// if (high_precision < 2) -// sprintf(buf, "%02u.%02u", (unsigned int)((min_nnnnn / 100000) % 100), (unsigned int)((min_nnnnn / 1000) % 100)); -// else -// sprintf(buf, "%c", (char)((min_nnnnn % 1000) / 11) + 33); -// // Like to verify? type in python for i.e. RawDegrees billions 566688333: i = -// // 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33) -// return buf; -// } - -// int numDigits(unsigned int num) -// { -// if (num < 10) -// return 1; -// return 1 + numDigits(num / 10); -// } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h deleted file mode 100644 index f600f2e1..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsgOld.h +++ /dev/null @@ -1,227 +0,0 @@ -// /* -// MIT License - -// Copyright (c) 2020 Peter Buchegger - -// Permission is hereby granted, free of charge, to any person obtaining a copy -// of this software and associated documentation files (the "Software"), to deal -// in the Software without restriction, including without limitation the rights -// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -// copies of the Software, and to permit persons to whom the Software is -// furnished to do so, subject to the following conditions: - -// The above copyright notice and this permission notice shall be included in all -// copies or substantial portions of the Software. - -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -// SOFTWARE. -// */ - -// #ifndef APRSMSG_H -// #define APRSMSG_H - -// #if defined(ARDUINO) -// #include -// #elif defined(_WIN32) || defined(_WIN64) // Windows -// #include -// #include -// #include -// #elif defined(__unix__) // Linux -// // TODO -// #elif defined(__APPLE__) // OSX -// // TODO -// #endif - -// class APRSMessageType -// { -// public: -// enum Value : uint8_t -// { -// PositionWithoutTimestamp, // = and ! -// PositionWithTimestamp, // @ and / -// Status, // > -// Query, // ? -// Message, // : -// Weather, // _ -// Telemetry, // T -// CurrentMicEData, // ` -// // you can add more types ;) -// Error, -// }; - -// APRSMessageType() = default; -// // cppcheck-suppress noExplicitConstructor -// APRSMessageType(char type) -// { -// switch (type) -// { -// case '=': -// case '!': -// value = PositionWithoutTimestamp; -// break; -// case '@': -// case '/': -// value = PositionWithTimestamp; -// break; -// case '>': -// value = Status; -// break; -// case '?': -// value = Query; -// break; -// case ':': -// value = Message; -// break; -// case '_': -// value = Weather; -// break; -// case 'T': -// value = Telemetry; -// break; -// case '`': -// value = CurrentMicEData; -// break; -// default: -// value = Error; -// } -// } -// // cppcheck-suppress noExplicitConstructor -// constexpr APRSMessageType(Value aType) : value(aType) {} -// constexpr bool operator==(APRSMessageType a) const { return value == a.value; } -// constexpr bool operator!=(APRSMessageType a) const { return value != a.value; } -// explicit operator bool() const { return value != Error; } - -// const char *toString() const -// { -// switch (value) -// { -// case PositionWithoutTimestamp: -// return "Position Without Timestamp"; -// case PositionWithTimestamp: -// return "Position With Timestamp"; -// case Status: -// return "Status"; -// case Query: -// return "Query"; -// case Message: -// return "Message"; -// case Weather: -// return "Weather"; -// case Telemetry: -// return "Telemetry"; -// case CurrentMicEData: -// return "Current Mic-E Data"; -// default: -// return "Error"; -// } -// } - -// private: -// Value value = Error; -// }; - -// class APRSBody -// { -// public: -// APRSBody(); -// virtual ~APRSBody(); - -// const char *getData(); -// void setData(const char data[80]); - -// virtual bool decode(char *message); -// virtual const char *encode(); -// virtual void toString(char *str); - -// private: -// char _data[80]{0}; -// }; - -// class APRSMsg -// { -// public: -// APRSMsg(); -// APRSMsg(APRSMsg &otherMsg); -// APRSMsg &operator=(APRSMsg &otherMsg); -// virtual ~APRSMsg(); - -// const char *getSource(); -// void setSource(const char source[8]); - -// const char *getDestination(); -// void setDestination(const char destination[8]); - -// const char *getPath(); -// void setPath(const char path[10]); - -// APRSMessageType getType(); - -// const char *getRawBody(); -// APRSBody *getBody(); - -// virtual bool decode(char *message); -// virtual void encode(char *message); -// virtual void toString(char *str); - -// static void formatLat(char *lat, bool hp); -// static void formatLong(char *lng, bool hp); -// static void formatDao(char *lat, char *lng, char *dao); -// static void padding(unsigned int number, unsigned int width, char *output, int offset = 0); - -// private: -// char _source[8]{0}; -// char _destination[8]{0}; -// char _path[10]{0}; -// APRSMessageType _type; -// char _rawBody[80]{0}; -// APRSBody _body; -// }; - -// /* -// APRS Configuration -// - CALLSIGN -// - TOCALL -// - PATH -// - SYMBOL -// - OVERLAY -// */ -// struct APRSConfig -// { -// char CALLSIGN[8]; -// char TOCALL[8]; -// char PATH[10]; -// char SYMBOL; -// char OVERLAY; -// }; - -// /* -// APRS Telemetry Data -// - lat -// - lng -// - alt -// - spd -// - hdg -// - precision -// - stage -// - t0 -// - dao -// */ -// struct APRSData -// { -// char lat[16]; -// char lng[16]; -// char alt[10]; -// char spd[4]; -// char hdg[4]; -// char precision; -// char stage[3]; -// char t0[9]; -// char dao[6]; -// }; - -// #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp index 50727b56..7528b94b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp @@ -99,6 +99,11 @@ bool RFM69HCWNew::tx(const uint8_t *message, int len, int packetNum, bool lastPa radio.setHeaderId(packetNum); radio.setHeaderFlags(lastPacket ? 0 : RADIO_FLAG_MORE_DATA); + uint8_t temp[555]; + memcpy(temp, message, len); + temp[len] = '\0'; + printf("Len: %d - Message: %s\n", len, temp); + return radio.send((uint8_t *)message, len); } @@ -109,29 +114,20 @@ Note that the message may be incomplete, if the message is complete available() The received message will be truncated if it exceeds the maximum message length \return the received message with the length in the first byte or `nullptr` if no message is available */ -const uint8_t *RFM69HCWNew::rx() +bool RFM69HCWNew::rx(uint8_t *recvbuf, uint8_t *len) { if (!radio.available()) - return nullptr; + return false; - // Should be a message for us now - // Stores the length of the message in the first byte of the returned array - uint8_t receivedLen; - uint8_t receivedMsg[1 + maxDataLen]; - if (!radio.recv(1 + receivedMsg, &(receivedLen))) - return nullptr; + if (!radio.recv(recvbuf, len)) + return false; - receivedMsg[0] = receivedLen; rssi = radio.lastRssi(); - return receivedMsg; + return true; } - - #pragma region External Send and Receive - - bool RFM69HCWNew::enqueueSend(const uint8_t *message, uint8_t len) { // fill up the buffer with the message. buffer is a circular queue. @@ -145,7 +141,7 @@ bool RFM69HCWNew::enqueueSend(const uint8_t *message, uint8_t len) buffer[bufTail] = message[i]; bufTail = (bufTail + 1) % RADIO_BUFFER_SIZE; } - + printf("Length: %d\n", len); return true; } @@ -156,7 +152,9 @@ bool RFM69HCWNew::enqueueSend(const char *message) bool RFM69HCWNew::enqueueSend(RadioMessage *message) { - return enqueueSend(message->encode(), message->length()); + const uint8_t *encodedMessage = message->encode(); + int messageLength = message->length(); + return enqueueSend(encodedMessage, messageLength); } bool RFM69HCWNew::dequeueReceive(uint8_t *message) @@ -211,8 +209,6 @@ bool RFM69HCWNew::dequeueReceive(RadioMessage *message) #pragma endregion - - bool RFM69HCWNew::update() { if (busy()) // radio is busy, cannot send or receive @@ -228,39 +224,45 @@ bool RFM69HCWNew::update() if (remainingLength == 0) // start a new message { remainingLength = buffer[bufHead]; + int len = min(remainingLength, maxDataLen); inc(bufHead); - tx(&buffer[bufHead], min(remainingLength, maxDataLen), 0, remainingLength <= maxDataLen); + tx(&buffer[bufHead], len, 0, remainingLength <= maxDataLen); + bufHead += len % RADIO_BUFFER_SIZE; + remainingLength -= len; } else // continue the message { int len = min(remainingLength, maxDataLen); remainingLength -= len; tx(&buffer[bufHead], len, radio.headerId() + 1, remainingLength <= maxDataLen); + bufHead += len % RADIO_BUFFER_SIZE; } } else // receiver { - const uint8_t *msg = rx(); - if (msg == nullptr) + uint8_t msg[RH_RF69_MAX_MESSAGE_LEN]; + uint8_t len = RH_RF69_MAX_MESSAGE_LEN; + if (!rx(msg, &len)) return false; // store the message in the buffer if (radio.headerId() == 0) { // start of a new message + printf("new message\n"); orignalBufferTail = bufTail; - buffer[bufTail] = msg[0]; // store the length of the message + buffer[bufTail] = len; // store the length of the message inc(bufTail); - for (int i = 1; i <= msg[0]; i++) + for (int i = 1; i <= len; i++) { - buffer[bufTail] = msg[i]; + buffer[bufTail] = msg[i - 1]; inc(bufTail); } } else { - buffer[orignalBufferTail] += msg[0]; // update the length of the message - for (int i = 1; i <= msg[0]; i++) + buffer[orignalBufferTail] += len; // update the length of the message + for (int i = 1; i <= len; i++) { - buffer[bufTail] = msg[i]; + buffer[bufTail] = msg[i - 1]; inc(bufTail); } } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h index abfff3c1..6d2151bb 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h @@ -1,17 +1,9 @@ #ifndef RFM69HCW_H #define RFM69HCW_H -#if defined(ARDUINO) -#define MSG_LEN 200 -#elif defined(TEENSYDUINO) -#define MSG_LEN 10 * 1024 -#elif defined(RASPBERRY_PI) -#define MSG_LEN 10 * 1024 -#endif - +#include "RH_RF69.h" #include "Radio.h" #include "APRSMsg.h" -#include "RH_RF69.h" #define RADIO_BUFFER_SIZE 1024 #define RADIO_FLAG_MORE_DATA 0b00000001 // custom flag to indicate more packets are still to be sent @@ -38,6 +30,9 @@ struct RadioSettings int txPower = 20; }; +#ifndef RH_RF69_MAX_MESSAGE_LEN +#define RH_RF69_MAX_MESSAGE_LEN 66 +#endif // !RH_RF69_MAX_MESSAGE_LEN class RFM69HCWNew : public Radio { @@ -45,10 +40,10 @@ class RFM69HCWNew : public Radio RFM69HCWNew(const RadioSettings *s); bool init() override; bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) override; // designed to be used internally. cannot exceed 66 bytes including headers - const uint8_t *rx() override; + bool rx(uint8_t *recvbuf, uint8_t *len) override; bool busy(); - bool enqueueSend(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. - bool enqueueSend(const char *message) override; // designed to be used externally. can exceed 66 bytes. + bool enqueueSend(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. + bool enqueueSend(const char *message) override; // designed to be used externally. can exceed 66 bytes. bool enqueueSend(const uint8_t *message, uint8_t len) override; // designed to be used externally. can exceed 66 bytes. bool dequeueReceive(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. @@ -63,8 +58,10 @@ class RFM69HCWNew : public Radio // increment the specified index, wrapping around if necessary static void inc(int &i) { i = (i + 1) % RADIO_BUFFER_SIZE; } -private: + uint8_t buffer[RADIO_BUFFER_SIZE]; RH_RF69 radio; + +private: // all radios should have the same networkID const uint8_t networkID = 1; // default to the highest transmit power @@ -80,12 +77,11 @@ class RFM69HCWNew : public Radio // stores queue of messages, with the length of the message as the first byte of each. no delimiter. // [6xxxxxx3xxx1x2xx] // Done to allow for messages that are not ascii encoded. - uint8_t buffer[RADIO_BUFFER_SIZE]; int bufHead = 0; int bufTail = 0; - int remainingLength = 0; // how much message is left to send for transmitters + int remainingLength = 0; // how much message is left to send for transmitters int orignalBufferTail = 0; // used to update the length of the message after recieving. - int maxDataLen = RH_RF69_MAX_MESSAGE_LEN; + const int maxDataLen = RH_RF69_MAX_MESSAGE_LEN; }; #endif // RFM69HCW_H \ No newline at end of file From 4b1e095d84b5148be3cc94b72258fe7c8ab94cb1 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 15 May 2024 17:13:01 -0400 Subject: [PATCH 13/41] Ready to test --- .../Code/Teensy-Based Avionics/platformio.ini | 24 ++++++++++++--- .../src/GroundStationReceiver/main.cpp | 30 +++++++++++++++++++ .../Teensy-Based Avionics/src/RFM69HCWNew.cpp | 2 ++ .../Code/Teensy-Based Avionics/src/main.cpp | 6 ++-- 4 files changed, 55 insertions(+), 7 deletions(-) create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index 43e5628c..a184a3ba 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -15,7 +15,7 @@ platform = teensy board = teensy41 framework = arduino lib_extra_dirs = /lib/imumaths -build_src_filter = +<*> - + +build_src_filter = +<*> - + - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict lib_deps = @@ -33,7 +33,7 @@ platform = atmelavr board = uno framework = arduino lib_extra_dirs = /lib/imumaths -build_src_filter = +<*> - +build_src_filter = +<*> - - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict lib_deps = @@ -50,7 +50,7 @@ platform = teensy board = teensy41 framework = arduino lib_extra_dirs = /lib/imumaths -build_src_filter = +<*> - +build_src_filter = +<*> - - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict lib_deps = @@ -63,4 +63,20 @@ check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 - +[env:teensy41_GROUND_STATION_RECEIVER] +platform = teensy +board = teensy41 +framework = arduino +lib_extra_dirs = /lib/imumaths +build_src_filter = +<*> - - +build_flags = -Wno-unknown-pragmas +lib_compat_mode = strict +lib_deps = + adafruit/Adafruit BMP3XX Library@^2.1.2 + adafruit/RTClib @ ^2.1.1 + adafruit/Adafruit BNO055@^1.6.3 + sparkfun/SparkFun u-blox GNSS v3@^3.0.16 + https://github.com/DrewBrandt/BlinkBuzz.git +check_src_filters = -<*> + + + - +check_flags = + cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp new file mode 100644 index 00000000..dfcfa132 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -0,0 +1,30 @@ +#include "RFM69HCWNew.h" +#include + +APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1"}; +APRSMsg msg(header); +RadioSettings settings = {915.0, false, false, &hardware_spi, 10, 31, 32}; +RFM69HCWNew radio(&settings); +void setup() +{ + if(!radio.init()) + Serial.println("Radio failed to initialize"); + else + Serial.println("Radio initialized"); + + +} + +void loop() +{ + if(radio.update()) + { + APRSMsg *m; + if(radio.dequeueReceive(m)) + { + Serial.println("Received message:"); + printf("Header: %s>%s,%s\n", m->header.CALLSIGN, m->header.TOCALL, m->header.PATH); + printf("Data: lat: %f, lng: %f, alt: %f, spd: %f, hdg: %f, stage: %d, orientation: %f %f %f\n", m->data.lat, m->data.lng, m->data.alt, m->data.spd, m->data.hdg, m->data.stage, m->data.orientation[0], m->data.orientation[1], m->data.orientation[2]); + } + } +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp index 7528b94b..ea6498fc 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp @@ -266,6 +266,8 @@ bool RFM69HCWNew::update() inc(bufTail); } } + if(radio.headerFlags() & RADIO_FLAG_MORE_DATA) // more data is coming + return false; } return true; } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 6cf37858..5ca6ac83 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -11,7 +11,7 @@ BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 -RadioSettings settings = {433.775, true, false, &hardware_spi, 10, 31, 32}; +RadioSettings settings = {915.0, true, false, &hardware_spi, 10, 31, 32}; RFM69HCWNew radio(&settings); State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); @@ -47,7 +47,7 @@ void setup() pinMode(BUZZER, OUTPUT); // its very loud during testing bb.onoff(BUZZER, 100, 4, 100); recordLogData(INFO, "Initializing Avionics System. 5 second delay to prevent unnecessary file generation.", TO_USB); - delay(5000); + // delay(5000); pinMode(BMP_ADDR_PIN, OUTPUT); digitalWrite(BMP_ADDR_PIN, HIGH); @@ -109,7 +109,7 @@ void loop() radio.update(); double time = millis(); - if (time - radioTimer >= 500) + if (time - radioTimer >= 5000) { computer.transmit(); radioTimer = time; From d6e12b5fa79578bc16da963a71ad3f57bd7021e2 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 15 May 2024 18:42:36 -0400 Subject: [PATCH 14/41] test --- .../Teensy-Based Avionics/src/RFM69HCWNew.cpp | 26 ++++++++++++++----- .../Code/Teensy-Based Avionics/src/main.cpp | 9 +++---- 2 files changed, 24 insertions(+), 11 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp index ea6498fc..b941d7ba 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp @@ -142,6 +142,7 @@ bool RFM69HCWNew::enqueueSend(const uint8_t *message, uint8_t len) bufTail = (bufTail + 1) % RADIO_BUFFER_SIZE; } printf("Length: %d\n", len); + printf("BufHead: %d, BufTail: %d\n", bufHead, bufTail); return true; } @@ -224,19 +225,32 @@ bool RFM69HCWNew::update() if (remainingLength == 0) // start a new message { remainingLength = buffer[bufHead]; - int len = min(remainingLength, maxDataLen); + int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); inc(bufHead); - tx(&buffer[bufHead], len, 0, remainingLength <= maxDataLen); - bufHead += len % RADIO_BUFFER_SIZE; + uint8_t temp[RH_RF69_MAX_MESSAGE_LEN]; + //load buffer + for(int i = 0; i < len; i++) + { + temp[i] = buffer[bufHead]; + inc(bufHead); + } + tx(temp, len, 0, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); remainingLength -= len; } else // continue the message { - int len = min(remainingLength, maxDataLen); + int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); remainingLength -= len; - tx(&buffer[bufHead], len, radio.headerId() + 1, remainingLength <= maxDataLen); - bufHead += len % RADIO_BUFFER_SIZE; + uint8_t temp[RH_RF69_MAX_MESSAGE_LEN]; + // load buffer + for (int i = 0; i < len; i++) + { + temp[i] = buffer[bufHead]; + inc(bufHead); + } + tx(temp, len, radio.headerId() + 1, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); } + '�' } else // receiver { diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 5ca6ac83..5f177cd4 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -26,8 +26,8 @@ PSRAM *ram; static double last = 0; // for better timing than "delay(100)" // BlinkBuzz setup -int allowedPins[] = {LED_BUILTIN, BUZZER}; -BlinkBuzz bb(allowedPins, 2, true); +int allowedPins[] = {LED_BUILTIN}; +BlinkBuzz bb(allowedPins, 1, true); extern unsigned long _heap_start; extern unsigned long _heap_end; extern char *__brkval; @@ -44,7 +44,6 @@ void setup() { pinMode(LED_BUILTIN, OUTPUT); - pinMode(BUZZER, OUTPUT); // its very loud during testing bb.onoff(BUZZER, 100, 4, 100); recordLogData(INFO, "Initializing Avionics System. 5 second delay to prevent unnecessary file generation.", TO_USB); // delay(5000); @@ -109,7 +108,7 @@ void loop() radio.update(); double time = millis(); - if (time - radioTimer >= 5000) + if (time - radioTimer >= 1000) { computer.transmit(); radioTimer = time; @@ -119,7 +118,7 @@ void loop() last = time; computer.updateState(); - recordLogData(INFO, computer.getStateString(), TO_USB); + //recordLogData(INFO, computer.getStateString(), TO_USB); // RASPBERRY PI TURN ON if (time / 1000.0 > 810) { From 08f10b3f3591e61a9cd77680536fb2c53bc38b61 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 15 May 2024 18:42:52 -0400 Subject: [PATCH 15/41] test --- .../src/GroundStationReceiver/main.cpp | 12 ++++++------ .../Teensy-Based Avionics/src/RFM69HCWNew.cpp | 17 ++++++++++------- 2 files changed, 16 insertions(+), 13 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index dfcfa132..f1886aee 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -1,12 +1,13 @@ #include "RFM69HCWNew.h" #include -APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1"}; +APRSHeader header; APRSMsg msg(header); RadioSettings settings = {915.0, false, false, &hardware_spi, 10, 31, 32}; RFM69HCWNew radio(&settings); void setup() { + delay(2000); if(!radio.init()) Serial.println("Radio failed to initialize"); else @@ -19,12 +20,11 @@ void loop() { if(radio.update()) { - APRSMsg *m; - if(radio.dequeueReceive(m)) + if(radio.dequeueReceive(&msg)) { - Serial.println("Received message:"); - printf("Header: %s>%s,%s\n", m->header.CALLSIGN, m->header.TOCALL, m->header.PATH); - printf("Data: lat: %f, lng: %f, alt: %f, spd: %f, hdg: %f, stage: %d, orientation: %f %f %f\n", m->data.lat, m->data.lng, m->data.alt, m->data.spd, m->data.hdg, m->data.stage, m->data.orientation[0], m->data.orientation[1], m->data.orientation[2]); + printf("Received message (%d):", radio.RSSI()); + printf("\nHeader: %s>%s,%s:\n", msg.header.CALLSIGN, msg.header.TOCALL, msg.header.PATH); + printf("Data: %f, %f, %f, %f, %f, %d, %f, %f, %f\n", msg.data.lat, msg.data.lng, msg.data.alt, msg.data.spd, msg.data.hdg, msg.data.stage, msg.data.orientation.x(), msg.data.orientation.y(), msg.data.orientation.z()); } } } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp index ea6498fc..83e25cc0 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp @@ -116,9 +116,6 @@ The received message will be truncated if it exceeds the maximum message length */ bool RFM69HCWNew::rx(uint8_t *recvbuf, uint8_t *len) { - if (!radio.available()) - return false; - if (!radio.recv(recvbuf, len)) return false; @@ -169,6 +166,7 @@ bool RFM69HCWNew::dequeueReceive(uint8_t *message) for (int i = 0; i < len && bufHead != bufTail; i++) { message[i] = buffer[bufHead]; + printf("%c", message[i]); inc(bufHead); } return true; @@ -201,7 +199,6 @@ bool RFM69HCWNew::dequeueReceive(RadioMessage *message) uint8_t *msg = new uint8_t[len]; if (!dequeueReceive(msg)) return false; - message->decode(msg, len); delete[] msg; return true; @@ -242,8 +239,9 @@ bool RFM69HCWNew::update() { uint8_t msg[RH_RF69_MAX_MESSAGE_LEN]; uint8_t len = RH_RF69_MAX_MESSAGE_LEN; - if (!rx(msg, &len)) + if (!rx(msg, &len)){ return false; + } // store the message in the buffer if (radio.headerId() == 0) { // start of a new message @@ -256,9 +254,11 @@ bool RFM69HCWNew::update() buffer[bufTail] = msg[i - 1]; inc(bufTail); } + printf("Length: %d\n", len); } else { + printf("continued message\n"); buffer[orignalBufferTail] += len; // update the length of the message for (int i = 1; i <= len; i++) { @@ -266,9 +266,12 @@ bool RFM69HCWNew::update() inc(bufTail); } } - if(radio.headerFlags() & RADIO_FLAG_MORE_DATA) // more data is coming + if(radio.headerFlags() & RADIO_FLAG_MORE_DATA) {// more data is coming + printf("more data\n"); return false; + } } + printf("done\n"); return true; } @@ -280,7 +283,7 @@ bool RFM69HCWNew::update() bool RFM69HCWNew::busy() { RHGenericDriver::RHMode mode = this->radio.mode(); - if (mode == RHGenericDriver::RHModeTx || mode == RHGenericDriver::RHModeRx) + if (mode == RHGenericDriver::RHModeTx) return true; return false; } From 9ee3b4f7a382e0d0630b3ccd1351c87d38301465 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 00:17:23 -0400 Subject: [PATCH 16/41] Clean up and documentation --- .../Teensy-Based Avionics/include/Radio.h | 4 +- .../Teensy-Based Avionics/src/APRSMsg.cpp | 29 +- .../Code/Teensy-Based Avionics/src/APRSMsg.h | 14 +- .../src/GroundStationReceiver/main.cpp | 4 +- .../src/{RFM69HCWNew.cpp => RFM69HCW.cpp} | 247 ++++++++++-------- .../src/{RFM69HCWNew.h => RFM69HCW.h} | 13 +- .../Code/Teensy-Based Avionics/src/State.cpp | 4 +- .../Code/Teensy-Based Avionics/src/main.cpp | 4 +- 8 files changed, 177 insertions(+), 142 deletions(-) rename Spaceport/23-24/Code/Teensy-Based Avionics/src/{RFM69HCWNew.cpp => RFM69HCW.cpp} (51%) rename Spaceport/23-24/Code/Teensy-Based Avionics/src/{RFM69HCWNew.h => RFM69HCW.h} (92%) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h index 64eba141..5e7c80d1 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h @@ -31,11 +31,11 @@ enum EncodingType class RadioMessage { public: - virtual uint8_t *encode() = 0; // use stored variables to encode a message + virtual bool encode(uint8_t *message) = 0; // use stored variables to encode a message virtual bool decode(const uint8_t *message, int len) = 0; // use `message` to set stored variables virtual int length() const = 0; // return the length of the message virtual ~RadioMessage(){}; - + static constexpr int MAX_MESSAGE_LEN = 255; protected: uint8_t len; }; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index 2953353b..f6f34e0d 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -7,25 +7,24 @@ APRSMsg::APRSMsg(APRSHeader &header) this->header = header; } -uint8_t *APRSMsg::encode() +bool APRSMsg::encode(uint8_t *message) { - char *msg = new char[MAX_ALLOWED_MSG_LEN]; - int c = encodeHeader(msg); - encodeData(msg, c); - return (uint8_t *)msg; + int c = encodeHeader(message); + encodeData(message, c); + return true; } bool APRSMsg::decode(const uint8_t *message, int len) { // message needs to be decoded and values reinserted into the header and data structs - int c = decodeHeader((char *)message, len); - decodeData((char *)message, len, c); + int c = decodeHeader((uint8_t *)message, len); + decodeData((uint8_t *)message, len, c); return false; } #pragma region Encode Helpers -int APRSMsg::encodeHeader(char *message) const +int APRSMsg::encodeHeader(uint8_t *message) const { // format: CALLSIGN>TOCALL,PATH: int cursor = 0; @@ -47,7 +46,7 @@ int APRSMsg::encodeHeader(char *message) const return cursor; } -void APRSMsg::encodeData(char *message, int cursor) +void APRSMsg::encodeData(uint8_t *message, int cursor) { /* Small Aircraft symbol ( /' ) probably better than Jogger symbol ( /[ ) lol. I'm going to use the Overlayed Aircraft symbol ( \^ ) for now, with the overlay of 'M' for UMD ( M^ ). @@ -83,7 +82,7 @@ void APRSMsg::encodeData(char *message, int cursor) encodeBase91(message, cursor, (int)(data.alt * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. // stage and orientation - message[cursor++] = (char)(data.stage + (int)'0'); // stage is just written in plaintext. + message[cursor++] = (uint8_t)(data.stage + (int)'0'); // stage is just written in plaintext. encodeBase91(message, cursor, (int)(data.orientation.x() * ORIENTATION_SCALE), 2); // same as course encodeBase91(message, cursor, (int)(data.orientation.y() * ORIENTATION_SCALE), 2); // same as course encodeBase91(message, cursor, (int)(data.orientation.z() * ORIENTATION_SCALE), 2); // same as course @@ -95,7 +94,7 @@ void APRSMsg::encodeData(char *message, int cursor) #pragma region Decode Helpers -int APRSMsg::decodeHeader(const char *message, int len) +int APRSMsg::decodeHeader(const uint8_t *message, int len) { // format: CALLSIGN>TOCALL,PATH: int cursor = 0; @@ -120,7 +119,7 @@ int APRSMsg::decodeHeader(const char *message, int len) return cursor; } -void APRSMsg::decodeData(const char *message, int len, int cursor) +void APRSMsg::decodeData(const uint8_t *message, int len, int cursor) { // lat and lng cursor++; // skip overlay @@ -153,17 +152,17 @@ void APRSMsg::decodeData(const char *message, int len, int cursor) #pragma region Base91 Encoding -void APRSMsg::encodeBase91(char *message, int &cursor, int value, int precision) const +void APRSMsg::encodeBase91(uint8_t *message, int &cursor, int value, int precision) const { for (int i = precision - 1; i >= 0; i--) { int divisor = pow(91, i); - message[cursor++] = (char)((int)(value / divisor) + 33); + message[cursor++] = (uint8_t)((int)(value / divisor) + 33); value %= divisor; } } -void APRSMsg::decodeBase91(const char *message, int &cursor, double &value, int precision) const +void APRSMsg::decodeBase91(const uint8_t *message, int &cursor, double &value, int precision) const { value = 0; for (int i = 0; i < precision; i++) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h index a8001939..50f3fc30 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h @@ -59,20 +59,20 @@ class APRSMsg : public RadioMessage virtual ~APRSMsg(){}; bool decode(const uint8_t *message, int len) override; - uint8_t *encode() override; + bool encode(uint8_t *message) override; int length() const override { return this->len; } APRSData data; APRSHeader header; private: - int encodeHeader(char *message) const; - void encodeData(char *message, int cursor); + int encodeHeader(uint8_t *message) const; + void encodeData(uint8_t *message, int cursor); - int decodeHeader(const char *message, int len); - void decodeData(const char *message, int len, int cursor); + int decodeHeader(const uint8_t *message, int len); + void decodeData(const uint8_t *message, int len, int cursor); - void encodeBase91(char *message, int &cursor, int value, int precision) const; - void decodeBase91(const char *message, int &cursor, double &value, int precision) const; + void encodeBase91(uint8_t *message, int &cursor, int value, int precision) const; + void decodeBase91(const uint8_t *message, int &cursor, double &value, int precision) const; // Scale factors for encoding/decoding ignoring lat/long const double ALT_SCALE = (pow(91, 2) / 15000.0); // (91^2/15000) scale to fit in 2 base91 characters diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index f1886aee..53658a4b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -1,10 +1,10 @@ -#include "RFM69HCWNew.h" +#include "RFM69HCW.h" #include APRSHeader header; APRSMsg msg(header); RadioSettings settings = {915.0, false, false, &hardware_spi, 10, 31, 32}; -RFM69HCWNew radio(&settings); +RFM69HCW radio(&settings); void setup() { delay(2000); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp similarity index 51% rename from Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp rename to Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp index b2e7b54d..7ff5280d 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp @@ -1,4 +1,4 @@ -#include "RFM69HCWNew.h" +#include "RFM69HCW.h" #ifndef max int max(int a, int b); @@ -15,11 +15,10 @@ Constructor - highBitrate true for 300kbps, false for 4.8kbps - config with APRS settings */ -RFM69HCWNew::RFM69HCWNew(const RadioSettings *s) : radio(s->cs, s->irq, *s->spi) +RFM69HCW::RFM69HCW(const RadioSettings *s) : radio(s->cs, s->irq, *s->spi) { this->settings = *s; - this->avail = false; if (this->settings.transmitter) { @@ -38,7 +37,7 @@ RFM69HCWNew::RFM69HCWNew(const RadioSettings *s) : radio(s->cs, s->irq, *s->spi) /* Initializer to call in setup */ -bool RFM69HCWNew::init() +bool RFM69HCW::init() { // reset the radio pinMode(settings.rst, OUTPUT); @@ -86,35 +85,34 @@ bool RFM69HCWNew::init() /* Most basic transmission method, simply transmits the string without modification - \param message is the message to be transmitted must be less than maxDataLen + \param message is the message to be transmitted, must be shorter than RH_RF69_MAX_MESSAGE_LEN \param len optional length of message, required if message is not a null terminated string + \param packetNum optional packet number of the message + \param lastPacket optional is this the last packet of a larger message or the only packet? + \return `true` if the message was sent, `false` otherwise */ -bool RFM69HCWNew::tx(const uint8_t *message, int len, int packetNum, bool lastPacket) +bool RFM69HCW::tx(const uint8_t *message, int len, int packetNum, bool lastPacket) { // figure out how long the message should be if (len == -1) - { len = strlen((char *)message); - } + radio.setHeaderId(packetNum); radio.setHeaderFlags(lastPacket ? 0 : RADIO_FLAG_MORE_DATA); - uint8_t temp[555]; - memcpy(temp, message, len); - temp[len] = '\0'; - printf("Len: %d - Message: %s\n", len, temp); - return radio.send((uint8_t *)message, len); } /* -Receive function +Receive function - Most basic receiving method, simply checks for a message and returns it -Note that the message may be incomplete, if the message is complete available() will return true -The received message will be truncated if it exceeds the maximum message length -\return the received message with the length in the first byte or `nullptr` if no message is available +Note that the message may be incomplete, if the message is complete update() will return true +The received message will be truncated if it exceeds the maximum message length of the radio. Also updates the RSSI. + \param recvbuf the buffer to store the received message + \param len the length of the received message (updated by the function) + \return `true` if a message was received, `false` otherwise */ -bool RFM69HCWNew::rx(uint8_t *recvbuf, uint8_t *len) +bool RFM69HCW::rx(uint8_t *recvbuf, uint8_t *len) { if (!radio.recv(recvbuf, len)) return false; @@ -125,37 +123,63 @@ bool RFM69HCWNew::rx(uint8_t *recvbuf, uint8_t *len) #pragma region External Send and Receive -bool RFM69HCWNew::enqueueSend(const uint8_t *message, uint8_t len) +/* +Enqueue a message into the buffer + \param message the uint8_t[] to enqueue + \param len the length of the message + \return `true` if the message was enqueued, `false` otherwise +*/ +bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) { // fill up the buffer with the message. buffer is a circular queue. + int originalTail = bufTail; buffer[bufTail] = len; - bufTail = (bufTail + 1) % RADIO_BUFFER_SIZE; - for (int i = 0; i < len; i++) + inc(bufTail); + + for (int i = 0; i < len; i++) // same algorithm as copyToBuffer but with a length check { - if (bufTail == bufHead) // buffer is full + if (bufTail == bufHead) + { // buffer is full + bufTail = originalTail; // reset the tail (no message was added) return false; + } buffer[bufTail] = message[i]; - bufTail = (bufTail + 1) % RADIO_BUFFER_SIZE; + inc(bufTail); } - printf("Length: %d\n", len); - printf("BufHead: %d, BufTail: %d\n", bufHead, bufTail); return true; } -bool RFM69HCWNew::enqueueSend(const char *message) +/* +Enqueue a message into the buffer + \param message the null terminated string to enqueue + \return `true` if the message was enqueued, `false` otherwise +*/ +bool RFM69HCW::enqueueSend(const char *message) { return enqueueSend((uint8_t *)message, strlen(message)); } - -bool RFM69HCWNew::enqueueSend(RadioMessage *message) +/* +Encode the message and enqueue it in the buffer + \param message the RadioMessage to encode and enqueue + \return `true` if the message was encoded and enqueued, `false` otherwise +*/ +bool RFM69HCW::enqueueSend(RadioMessage *message) { - const uint8_t *encodedMessage = message->encode(); - int messageLength = message->length(); - return enqueueSend(encodedMessage, messageLength); + uint8_t encodedMessage[RadioMessage::MAX_MESSAGE_LEN]; + if (message->encode(encodedMessage)) + { + int messageLength = message->length(); + return enqueueSend(encodedMessage, messageLength); + } + return false; } - -bool RFM69HCWNew::dequeueReceive(uint8_t *message) +/* +Dequeue a message from the buffer and decode it into a uint8_t[]. + \param message the uint8_t[] to copy the recieved message into + \return `true` if a message was copied, `false` otherwise +*/ +bool RFM69HCW::dequeueReceive(uint8_t *message) { if (bufHead == bufTail) // buffer is empty return false; @@ -164,22 +188,22 @@ bool RFM69HCWNew::dequeueReceive(uint8_t *message) int len = buffer[bufHead]; inc(bufHead); // Empty the buffer up to the length of the expected message - for (int i = 0; i < len && bufHead != bufTail; i++) - { - message[i] = buffer[bufHead]; - printf("%c", message[i]); - inc(bufHead); - } + copyFromBuffer(message, len); return true; } -bool RFM69HCWNew::dequeueReceive(char *message) +/* +Dequeue a message from the buffer and decode it into a char[]. WIll break if the recieved message is not a null terminated string. + \param message the char[] to copy the recieved message into + \return `true` if a message was copied, `false` otherwise +*/ +bool RFM69HCW::dequeueReceive(char *message) { - if (bufHead == bufTail) + if (bufHead == bufTail) // buffer is empty return false; // Empty the buffer up to the first null terminator - inc(bufHead); // skip the length byte + inc(bufHead); // skip the length byte, should be null terminated int i = 0; for (; buffer[bufHead] != '\0' && bufHead != bufTail; i++) { @@ -191,102 +215,93 @@ bool RFM69HCWNew::dequeueReceive(char *message) return true; } -bool RFM69HCWNew::dequeueReceive(RadioMessage *message) +/* +Dequeue a message from the buffer and decode it into a RadioMessage + \param message the RadioMessage to give the encoded text to for decoding + \return `true` if a message was decoded, `false` if no message was decoded +*/ +bool RFM69HCW::dequeueReceive(RadioMessage *message) { - if (bufHead == bufTail) + if (bufHead == bufTail) // buffer is empty return false; uint8_t len = buffer[bufHead]; uint8_t *msg = new uint8_t[len]; - if (!dequeueReceive(msg)) - return false; - message->decode(msg, len); + bool worked = false; + if (dequeueReceive(msg)) // get the message from the buffer + if (message->decode(msg, len)) // decode the message + worked = true; + delete[] msg; - return true; + return worked; } #pragma endregion -bool RFM69HCWNew::update() +/* +Update function + - checks if the radio is busy + - if the radio is a transmitter, sends (partially sends, if it's too long) the next queued message in the buffer + - if the radio is a receiver, receives the next message and stores it in the buffer + \return TRANSMITTER: `true` if the message was sent, `false` if the message was not sent. + \return RECIEVER: `true` if the message was received in full, `false` if nothing received or message is incomplete. +*/ +bool RFM69HCW::update() { if (busy()) // radio is busy, cannot send or receive return false; + + // transmitter------------------------------------------------------ if (settings.transmitter) { - if (bufHead == bufTail) - { // buffer is empty, nothing to send + if (bufHead == bufTail) // buffer is empty, nothing to send + { remainingLength = 0; return false; } + // send the message + int packetNum; if (remainingLength == 0) // start a new message { - remainingLength = buffer[bufHead]; - int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); + remainingLength = buffer[bufHead]; // get the length of the message from the first byte of the message inc(bufHead); - uint8_t temp[RH_RF69_MAX_MESSAGE_LEN]; - //load buffer - for(int i = 0; i < len; i++) - { - temp[i] = buffer[bufHead]; - inc(bufHead); - } - tx(temp, len, 0, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); - remainingLength -= len; + packetNum = 0; } - else // continue the message - { - int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); - remainingLength -= len; - uint8_t temp[RH_RF69_MAX_MESSAGE_LEN]; - // load buffer - for (int i = 0; i < len; i++) - { - temp[i] = buffer[bufHead]; - inc(bufHead); - } - tx(temp, len, radio.headerId() + 1, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); - } - '�' + else + packetNum = radio.headerId() + 1; + + // load message to tx + int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); // how much of the message to send + uint8_t msgToTransmit[RH_RF69_MAX_MESSAGE_LEN]; + copyFromBuffer(msgToTransmit, len); + bool b = tx(msgToTransmit, len, packetNum, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); + remainingLength -= len; + return b; } - else // receiver + // receiver------------------------------------------------------ + else { uint8_t msg[RH_RF69_MAX_MESSAGE_LEN]; uint8_t len = RH_RF69_MAX_MESSAGE_LEN; - if (!rx(msg, &len)){ - return false; - } + if (!rx(msg, &len)) + return false; // no new message available + // store the message in the buffer - if (radio.headerId() == 0) - { // start of a new message - printf("new message\n"); + if (radio.headerId() == 0) // start of a new message + { orignalBufferTail = bufTail; buffer[bufTail] = len; // store the length of the message inc(bufTail); - for (int i = 1; i <= len; i++) - { - buffer[bufTail] = msg[i - 1]; - inc(bufTail); - } - printf("Length: %d\n", len); - } - else - { - printf("continued message\n"); - buffer[orignalBufferTail] += len; // update the length of the message - for (int i = 1; i <= len; i++) - { - buffer[bufTail] = msg[i - 1]; - inc(bufTail); - } } - if(radio.headerFlags() & RADIO_FLAG_MORE_DATA) {// more data is coming - printf("more data\n"); + else // continuing message + buffer[orignalBufferTail] += len; // update the total length of the message + + copyToBuffer(msg, len); + if (radio.headerFlags() & RADIO_FLAG_MORE_DATA) // more data is coming, should not process yet return false; - } } - printf("done\n"); - return true; + return true; // message was sent or received (in full) } #pragma region Helpers @@ -294,7 +309,7 @@ bool RFM69HCWNew::update() /* \return `true` if the radio is currently transmitting or receiving a message */ -bool RFM69HCWNew::busy() +bool RFM69HCW::busy() { RHGenericDriver::RHMode mode = this->radio.mode(); if (mode == RHGenericDriver::RHModeTx) @@ -304,13 +319,13 @@ bool RFM69HCWNew::busy() /* Returns the RSSI of the last message */ -int RFM69HCWNew::RSSI() +int RFM69HCW::RSSI() { return rssi; } // probably broken -void RFM69HCWNew::set300KBPSMode() +void RFM69HCW::set300KBPSMode() { this->radio.spiWrite(0x03, 0x00); // REG_BITRATEMSB: 300kbps (0x006B, see DS p20) this->radio.spiWrite(0x04, 0x6B); // REG_BITRATELSB: 300kbps (0x006B, see DS p20) @@ -342,4 +357,22 @@ int min(int a, int b) } #endif +void RFM69HCW::copyToBuffer(const uint8_t *message, int len) +{ + for (int i = 0; i < len; i++) + { + buffer[bufTail] = message[i]; + inc(bufTail); + } +} + +void RFM69HCW::copyFromBuffer(uint8_t *message, int len) +{ + for (int i = 0; i < len; i++) + { + message[i] = buffer[bufHead]; + inc(bufHead); + } +} + #pragma endregion diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h similarity index 92% rename from Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h rename to Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h index 6d2151bb..12c78202 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCWNew.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h @@ -34,14 +34,15 @@ struct RadioSettings #define RH_RF69_MAX_MESSAGE_LEN 66 #endif // !RH_RF69_MAX_MESSAGE_LEN -class RFM69HCWNew : public Radio +class RFM69HCW : public Radio { public: - RFM69HCWNew(const RadioSettings *s); + RFM69HCW(const RadioSettings *s); bool init() override; bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) override; // designed to be used internally. cannot exceed 66 bytes including headers bool rx(uint8_t *recvbuf, uint8_t *len) override; bool busy(); + bool enqueueSend(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. bool enqueueSend(const char *message) override; // designed to be used externally. can exceed 66 bytes. bool enqueueSend(const uint8_t *message, uint8_t len) override; // designed to be used externally. can exceed 66 bytes. @@ -49,6 +50,7 @@ class RFM69HCWNew : public Radio bool dequeueReceive(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. bool dequeueReceive(char *message) override; // designed to be used externally. can exceed 66 bytes. bool dequeueReceive(uint8_t *message) override; // designed to be used externally. can exceed 66 bytes. + int RSSI() override; void set300KBPSMode(); bool update(); @@ -58,6 +60,7 @@ class RFM69HCWNew : public Radio // increment the specified index, wrapping around if necessary static void inc(int &i) { i = (i + 1) % RADIO_BUFFER_SIZE; } + //public during debugging uint8_t buffer[RADIO_BUFFER_SIZE]; RH_RF69 radio; @@ -70,7 +73,6 @@ class RFM69HCWNew : public Radio RadioSettings settings; int thisAddr; int toAddr; - bool avail; int rssi; bool initialized = false; @@ -81,7 +83,10 @@ class RFM69HCWNew : public Radio int bufTail = 0; int remainingLength = 0; // how much message is left to send for transmitters int orignalBufferTail = 0; // used to update the length of the message after recieving. - const int maxDataLen = RH_RF69_MAX_MESSAGE_LEN; + + void copyToBuffer(const uint8_t *message, int len); + void copyFromBuffer(uint8_t *message, int len); + }; #endif // RFM69HCW_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index 1558d460..e90bc274 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -486,8 +486,6 @@ bool State::sensorOK(const Sensor *sensor) bool State::transmit() { - char data[200]; - snprintf(data, 200, "%f,%f,%i,%i,%i,%c,%i,%s", sensorOK(gps) ? gps->getPos().x() : 0, sensorOK(gps) ? gps->getPos().y() : 0, sensorOK(baro) ? (int)baro->getRelAltFt() : 0, (int)(baroVelocity * 3.28), (int)headingAngle, 'H', stageNumber, launchTimeOfDay); aprs.data.lat = sensorOK(gps) ? gps->getPos().x() : 0; aprs.data.lng = sensorOK(gps) ? gps->getPos().y() : 0; aprs.data.alt = sensorOK(baro) ? baro->getRelAltFt() : 0; @@ -495,7 +493,7 @@ bool State::transmit() aprs.data.spd = (int)(baroVelocity * 3.28); aprs.data.stage = stageNumber; aprs.data.orientation = imu->getOrientation().toEuler(); - + aprs.data.orientation.toDegrees(); radio->enqueueSend(&aprs); return true; } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 5f177cd4..10ddaef3 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -4,7 +4,7 @@ #include "BNO055.h" #include "MAX_M10S.h" #include "DS3231.h" -#include "RFM69HCWNew.h" +#include "RFM69HCW.h" #include "RecordData.h" #include "BlinkBuzz.h" @@ -12,7 +12,7 @@ BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 RadioSettings settings = {915.0, true, false, &hardware_spi, 10, 31, 32}; -RFM69HCWNew radio(&settings); +RFM69HCW radio(&settings); State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); From e64af2d485e0ffa03fbcc120d1772b0bf8a7e5fd Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 01:07:53 -0400 Subject: [PATCH 17/41] adjusted lib deps and added encoded serial ouput --- .../Code/Teensy-Based Avionics/platformio.ini | 8 +-- .../Teensy-Based Avionics/src/APRSMsg.cpp | 1 + .../EncodeAPRSForSerial.h | 59 +++++++++++++++++++ .../src/GroundStationReceiver/main.cpp | 16 ++--- 4 files changed, 70 insertions(+), 14 deletions(-) create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index a184a3ba..891b1c93 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -68,15 +68,11 @@ platform = teensy board = teensy41 framework = arduino lib_extra_dirs = /lib/imumaths -build_src_filter = +<*> - - +build_src_filter = -<*> + + + + + + + build_flags = -Wno-unknown-pragmas lib_compat_mode = strict lib_deps = - adafruit/Adafruit BMP3XX Library@^2.1.2 - adafruit/RTClib @ ^2.1.1 - adafruit/Adafruit BNO055@^1.6.3 - sparkfun/SparkFun u-blox GNSS v3@^3.0.16 - https://github.com/DrewBrandt/BlinkBuzz.git + adafruit/Adafruit BNO055@^1.6.3 ; For the imumaths library check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index f6f34e0d..e970a814 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -70,6 +70,7 @@ void APRSMsg::encodeData(uint8_t *message, int cursor) */ // lat and lng + message[cursor++] = '!'; // Message type (position without timestamp) message[cursor++] = 'M'; // overlay encodeBase91(message, cursor, (int)380926 * (90 - data.lat), 4); // 380926 is the magic number from the APRS spec (page 38) encodeBase91(message, cursor, (int)190463 * (180 + data.lng), 4); // 190463 is the magic number from the APRS spec (page 38) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h new file mode 100644 index 00000000..08ac9a96 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -0,0 +1,59 @@ +#ifndef ENCODE_APRS_FOR_SERIAL_H +#define ENCODE_APRS_FOR_SERIAL_H + +#include "APRSMsg.h" + +namespace aprsToSerial +{ + const char OVERLAY = '/'; + const char SYMBOL = '['; // Jogger symbol. I disagree with this usage. + + /* + * Encodes an APRS message into a string for serial transmission + * \param msg The APRS message to encode + * \param buffer The buffer to write the encoded message to + * \param buffer_size The size of the buffer + * \return void + */ + void encodeAPRSForSerial(const APRSMsg &msg, char *buffer, size_t buffer_size, int RSSI) + { + char prefix[8] = "s\r\n"; + char header[100]; + snprintf(header, 100, "Source:%s,Destination:%s,Path:%s,Type:%s,", msg.header.CALLSIGN, msg.header.TOCALL, msg.header.PATH, "Position Without Timestamp"); + char latLong[20]; + encodeLatLong(msg, latLong, 20); + char altitude[10]; + encodeAltitude(msg, altitude, 10); + + char suffix[10] = "e\r\n"; + // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx,RSSI:RSSI\r\ne\r\n + snprintf(buffer, buffer_size, "%s%sData:!%s[%03d/%03d/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); + } + + void encodeLatLong(const APRSMsg &msg, char *buffer, size_t buffer_size) + { + int lat_deg = (int)abs(msg.data.lat); + double lat_min = ((msg.data.lat - lat_deg) * 60); + char lat_dir = (msg.data.lat < 0) ? 'S' : 'N'; + + int long_deg = (int)abs(msg.data.lng); + double long_min = ((msg.data.lng - long_deg) * 60); + char long_dir = (msg.data.lng < 0) ? 'W' : 'E'; + + // format: DDMM.MM[NS][OVERLAY]DDDMM.MM[WE] + snprintf(buffer, buffer_size, "%02d%05.02f%c%c%03d%05.02f%c", lat_deg, lat_min, lat_dir, OVERLAY, long_deg, long_min, long_dir); + + } + + void encodeAltitude(const APRSMsg &msg, char *buffer, size_t buffer_size) + { + // format: A=DDDDDD + int alt = (int)msg.data.alt; + if(alt < 0) + snprintf(buffer, buffer_size, "A=%07d", alt); + else + snprintf(buffer, buffer_size, "A=%06d", alt); + } +} + +#endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index 53658a4b..5c4c42e6 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -1,4 +1,6 @@ #include "RFM69HCW.h" +#include "EncodeAPRSForSerial.h" +#include "Adafruit_BNO055.h" #include APRSHeader header; @@ -8,23 +10,21 @@ RFM69HCW radio(&settings); void setup() { delay(2000); - if(!radio.init()) + if (!radio.init()) Serial.println("Radio failed to initialize"); else Serial.println("Radio initialized"); - - } void loop() { - if(radio.update()) + if (radio.update()) { - if(radio.dequeueReceive(&msg)) + if (radio.dequeueReceive(&msg)) { - printf("Received message (%d):", radio.RSSI()); - printf("\nHeader: %s>%s,%s:\n", msg.header.CALLSIGN, msg.header.TOCALL, msg.header.PATH); - printf("Data: %f, %f, %f, %f, %f, %d, %f, %f, %f\n", msg.data.lat, msg.data.lng, msg.data.alt, msg.data.spd, msg.data.hdg, msg.data.stage, msg.data.orientation.x(), msg.data.orientation.y(), msg.data.orientation.z()); + char buffer[255]; + aprsToSerial::encodeAPRSForSerial(msg, buffer, 255, radio.RSSI()); + Serial.println(buffer); } } } \ No newline at end of file From ead404e6114090a5483cb6ca6e82bad4e52174da Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 01:08:53 -0400 Subject: [PATCH 18/41] Refactor EncodeAPRSForSerial.h to include symbol in data format --- .../src/GroundStationReceiver/EncodeAPRSForSerial.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index 08ac9a96..0d816f15 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -27,7 +27,7 @@ namespace aprsToSerial char suffix[10] = "e\r\n"; // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx,RSSI:RSSI\r\ne\r\n - snprintf(buffer, buffer_size, "%s%sData:!%s[%03d/%03d/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); + snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); } void encodeLatLong(const APRSMsg &msg, char *buffer, size_t buffer_size) From 23171897272bdbff371133384695d8d38386004f Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 02:08:36 -0400 Subject: [PATCH 19/41] chore: Update altitude scaling in APRSMsg.cpp and APRSMsg.h --- .../23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp | 4 ++-- .../23-24/Code/Teensy-Based Avionics/src/APRSMsg.h | 4 +++- .../23-24/Code/Teensy-Based Avionics/src/State.cpp | 12 +++++++++++- 3 files changed, 16 insertions(+), 4 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index e970a814..93823233 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -80,7 +80,7 @@ void APRSMsg::encodeData(uint8_t *message, int cursor) // course, speed, altitude encodeBase91(message, cursor, (int)(data.hdg * HDG_SCALE), 2); // (91^2/360) scale to fit in 2 base91 characters encodeBase91(message, cursor, (int)(data.spd * SPD_SCALE), 2); // (91^2/1000) scale to fit in 2 base91 characters. 1000 knots is the assumed max speed. - encodeBase91(message, cursor, (int)(data.alt * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. + encodeBase91(message, cursor, (int)((data.alt + ALT_OFFSET) * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. // stage and orientation message[cursor++] = (uint8_t)(data.stage + (int)'0'); // stage is just written in plaintext. @@ -137,7 +137,7 @@ void APRSMsg::decodeData(const uint8_t *message, int len, int cursor) decodeBase91(message, cursor, data.spd, 2); data.spd /= SPD_SCALE; decodeBase91(message, cursor, data.alt, 2); - data.alt /= ALT_SCALE; + data.alt = data.alt / ALT_SCALE - ALT_OFFSET; // stage and orientation data.stage = message[cursor++] - (int)'0'; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h index 50f3fc30..b6172cc8 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h @@ -75,10 +75,12 @@ class APRSMsg : public RadioMessage void decodeBase91(const uint8_t *message, int &cursor, double &value, int precision) const; // Scale factors for encoding/decoding ignoring lat/long - const double ALT_SCALE = (pow(91, 2) / 15000.0); // (91^2/15000) scale to fit in 2 base91 characters + const double ALT_SCALE = (pow(91, 2) / 16000.0); // (91^2/16000) scale to fit in 2 base91 characters const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters const double HDG_SCALE = (pow(91, 2) / 360.0); // (91^2/360) scale to fit in 2 base91 characters const double ORIENTATION_SCALE = (pow(91, 2) / 360.0); // same as course + + const int ALT_OFFSET = +1000; // range of -1000 to 15000 ft. }; #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index e90bc274..a314f64a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -490,11 +490,21 @@ bool State::transmit() aprs.data.lng = sensorOK(gps) ? gps->getPos().y() : 0; aprs.data.alt = sensorOK(baro) ? baro->getRelAltFt() : 0; aprs.data.hdg = (int)headingAngle; - aprs.data.spd = (int)(baroVelocity * 3.28); + aprs.data.spd = abs((int)(baroVelocity * 3.28)); aprs.data.stage = stageNumber; aprs.data.orientation = imu->getOrientation().toEuler(); aprs.data.orientation.toDegrees(); + for(int i = 0; i < 3; i++) + { + if(aprs.data.orientation[i] < 0) + aprs.data.orientation[i] += 360; + } radio->enqueueSend(&aprs); + uint8_t data[150]; + data[149] = '\0'; + aprs.encode(data); + printf("%s\n", data); + printf("Values: %f, %f, %.02f, %.02f, %.02f, %d, %d, %d, %d\n", aprs.data.lat, aprs.data.lng, aprs.data.hdg, aprs.data.spd, aprs.data.alt, aprs.data.stage, (int)aprs.data.orientation.z(), (int)aprs.data.orientation.y(), (int)aprs.data.orientation.x()); return true; } extern unsigned long _heap_start; From 3cf2e6666776c0169a413ff4b779ad1795fab943 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 02:09:28 -0400 Subject: [PATCH 20/41] Refactor APRSMsg.cpp to return true instead of false in the decode function --- Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp | 2 +- .../src/GroundStationReceiver/EncodeAPRSForSerial.h | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index e970a814..054d53b4 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -19,7 +19,7 @@ bool APRSMsg::decode(const uint8_t *message, int len) // message needs to be decoded and values reinserted into the header and data structs int c = decodeHeader((uint8_t *)message, len); decodeData((uint8_t *)message, len, c); - return false; + return true; } #pragma region Encode Helpers diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index 0d816f15..fe4bcdbb 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -8,6 +8,9 @@ namespace aprsToSerial const char OVERLAY = '/'; const char SYMBOL = '['; // Jogger symbol. I disagree with this usage. + void encodeLatLong(const APRSMsg &msg, char *buffer, size_t buffer_size); + void encodeAltitude(const APRSMsg &msg, char *buffer, size_t buffer_size); + /* * Encodes an APRS message into a string for serial transmission * \param msg The APRS message to encode @@ -27,7 +30,7 @@ namespace aprsToSerial char suffix[10] = "e\r\n"; // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx,RSSI:RSSI\r\ne\r\n - snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); + snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); } void encodeLatLong(const APRSMsg &msg, char *buffer, size_t buffer_size) From 0b5d540b3cad7a358402a77f624e67d45674c725 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 02:31:43 -0400 Subject: [PATCH 21/41] Refactor APRSMsg.cpp to skip overlay character during data decoding --- Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp | 1 + Spaceport/23-24/Code/Teensy-Based Avionics/src/MAX_M10S.cpp | 2 +- Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp | 4 ++-- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp index 6d3d777a..5b9b1700 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp @@ -123,6 +123,7 @@ int APRSMsg::decodeHeader(const uint8_t *message, int len) void APRSMsg::decodeData(const uint8_t *message, int len, int cursor) { // lat and lng + cursor++; // skip '!' cursor++; // skip overlay decodeBase91(message, cursor, data.lat, 4); data.lat = 90 - data.lat / 380926.0; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/MAX_M10S.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/MAX_M10S.cpp index e1883a67..63084f85 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/MAX_M10S.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/MAX_M10S.cpp @@ -70,7 +70,7 @@ void MAX_M10S::update() pos.x() = m10s.getLatitude() / 10000000.0; pos.y() = m10s.getLongitude() / 10000000.0; - heading = m10s.getHeading(); + heading = m10s.getHeading() / 100000.0; altitude = m10s.getAltitude() / 1000.0; fixQual = m10s.getSIV(); if (!hasFirstFix && fixQual >= 4) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index a314f64a..525e6b9b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -503,8 +503,8 @@ bool State::transmit() uint8_t data[150]; data[149] = '\0'; aprs.encode(data); - printf("%s\n", data); - printf("Values: %f, %f, %.02f, %.02f, %.02f, %d, %d, %d, %d\n", aprs.data.lat, aprs.data.lng, aprs.data.hdg, aprs.data.spd, aprs.data.alt, aprs.data.stage, (int)aprs.data.orientation.z(), (int)aprs.data.orientation.y(), (int)aprs.data.orientation.x()); + //printf("%s\n", data); + //printf("Values: %f, %f, %.02f, %.02f, %.02f, %d, %d, %d, %d\n", aprs.data.lat, aprs.data.lng, aprs.data.hdg, aprs.data.spd, aprs.data.alt, aprs.data.stage, (int)aprs.data.orientation.z(), (int)aprs.data.orientation.y(), (int)aprs.data.orientation.x()); return true; } extern unsigned long _heap_start; From f3d017f3b360d9a1f2af4c71efa2498dda47c08e Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 20:19:32 -0400 Subject: [PATCH 22/41] Absolutely massive rework of the radio system for two way radios --- .../Live Video/radio-interface/APRSMsg.h | 2 +- .../Live Video/radio-interface/RFM69HCW.cpp | 6 +- .../Code/Teensy-Based Avionics/platformio.ini | 2 +- .../Teensy-Based Avionics/src/APRSMsg.cpp | 176 --------- .../Code/Teensy-Based Avionics/src/APRSMsg.h | 86 ----- .../EncodeAPRSForSerial.h | 12 +- .../src/GroundStationReceiver/main.cpp | 29 +- .../Code/Teensy-Based Avionics/src/Pi.cpp | 37 ++ .../23-24/Code/Teensy-Based Avionics/src/Pi.h | 23 ++ .../src/Radio/APRS/APRSCmdMsg.cpp | 19 + .../src/Radio/APRS/APRSCmdMsg.h | 25 ++ .../src/Radio/APRS/APRSMsgBase.cpp | 97 +++++ .../src/Radio/APRS/APRSMsgBase.h | 72 ++++ .../src/Radio/APRS/APRSTelemMsg.cpp | 97 +++++ .../src/Radio/APRS/APRSTelemMsg.h | 40 +++ .../src/{ => Radio}/RFM69HCW.cpp | 213 +++++------ .../src/{ => Radio}/RFM69HCW.h | 68 ++-- .../src/{ => Radio}/RFM69Helper.h | 340 +++++++++--------- .../{include => src/Radio}/Radio.h | 44 +-- .../src/Radio/RadioMessage.cpp | 43 +++ .../src/Radio/RadioMessage.h | 24 ++ .../Code/Teensy-Based Avionics/src/State.cpp | 92 ++--- .../Code/Teensy-Based Avionics/src/State.h | 22 +- .../Code/Teensy-Based Avionics/src/main.cpp | 158 +++++--- 24 files changed, 998 insertions(+), 729 deletions(-) delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp delete mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.h create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h rename Spaceport/23-24/Code/Teensy-Based Avionics/src/{ => Radio}/RFM69HCW.cpp (60%) rename Spaceport/23-24/Code/Teensy-Based Avionics/src/{ => Radio}/RFM69HCW.h (66%) rename Spaceport/23-24/Code/Teensy-Based Avionics/src/{ => Radio}/RFM69Helper.h (94%) rename Spaceport/23-24/Code/Teensy-Based Avionics/{include => src/Radio}/Radio.h (54%) create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h diff --git a/Side_Projects/Live Video/radio-interface/APRSMsg.h b/Side_Projects/Live Video/radio-interface/APRSMsg.h index beb98909..0973dfd1 100644 --- a/Side_Projects/Live Video/radio-interface/APRSMsg.h +++ b/Side_Projects/Live Video/radio-interface/APRSMsg.h @@ -213,7 +213,7 @@ APRS Telemetry Data - t0 - dao */ -struct APRSData +struct APRSTelemData { char lat[16]; char lng[16]; diff --git a/Side_Projects/Live Video/radio-interface/RFM69HCW.cpp b/Side_Projects/Live Video/radio-interface/RFM69HCW.cpp index f0aa8433..ec243c4f 100644 --- a/Side_Projects/Live Video/radio-interface/RFM69HCW.cpp +++ b/Side_Projects/Live Video/radio-interface/RFM69HCW.cpp @@ -286,9 +286,9 @@ bool RFM69HCW::encode(char *message, EncodingType type, int len) return false; // holds the data to be assembled into the aprs body - APRSData data; + APRSTelemData data; - // find each value separated in order by a comma and put in the APRSData array + // find each value separated in order by a comma and put in the APRSTelemData array { char *currentVal = new char[this->msgLen]; int currentValIndex = 0; @@ -426,7 +426,7 @@ bool RFM69HCW::decode(char *message, EncodingType type, int len) char *bodyptr = body; strcpy(body, aprs.getBody()->getData()); // decode body - APRSData data; + APRSTelemData data; int i = 0; int len = strlen(body); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index 891b1c93..4cfd9683 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -68,7 +68,7 @@ platform = teensy board = teensy41 framework = arduino lib_extra_dirs = /lib/imumaths -build_src_filter = -<*> + + + + + + + +build_src_filter = -<*> + + + build_flags = -Wno-unknown-pragmas lib_compat_mode = strict lib_deps = diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp deleted file mode 100644 index 5b9b1700..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.cpp +++ /dev/null @@ -1,176 +0,0 @@ -#include "APRSMsg.h" - -#define MAX_ALLOWED_MSG_LEN 255 /* max length of 1 message supported by radio buffer */ - -APRSMsg::APRSMsg(APRSHeader &header) -{ - this->header = header; -} - -bool APRSMsg::encode(uint8_t *message) -{ - int c = encodeHeader(message); - encodeData(message, c); - return true; -} - -bool APRSMsg::decode(const uint8_t *message, int len) -{ - // message needs to be decoded and values reinserted into the header and data structs - int c = decodeHeader((uint8_t *)message, len); - decodeData((uint8_t *)message, len, c); - return true; -} - -#pragma region Encode Helpers - -int APRSMsg::encodeHeader(uint8_t *message) const -{ - // format: CALLSIGN>TOCALL,PATH: - int cursor = 0; - for (int i = 0; header.CALLSIGN[i] && i < 8; i++, cursor++) - { - message[cursor] = header.CALLSIGN[i]; - } - message[cursor++] = '>'; - for (int i = 0; header.TOCALL[i] && i < 8; i++, cursor++) - { - message[cursor] = header.TOCALL[i]; - } - message[cursor++] = ','; - for (int i = 0; header.PATH[i] && i < 10; i++, cursor++) - { - message[cursor] = header.PATH[i]; - } - message[cursor++] = ':'; // end of header - return cursor; -} - -void APRSMsg::encodeData(uint8_t *message, int cursor) -{ - /* Small Aircraft symbol ( /' ) probably better than Jogger symbol ( /[ ) lol. - I'm going to use the Overlayed Aircraft symbol ( \^ ) for now, with the overlay of 'M' for UMD ( M^ ). - Uses base91 encoding to compress message as much as possible. APRS messages are apparently supposed to be only 256 bytes. - - - takes the regular format of !DDMM.hhN/DDDMM.hhW^ALTSPD/HDG SSOrientation - - which expands to !(lat)/(lng)^altspd/hdg (stage #)(orientation) - - and compresses it to /YYYYXXXX^ ccssaasoooooo - - which expands to /(lat)(lng)^ (course)(speed)(altitude)(stage)(orientation [as euler angles]) - - specifically does not use the csT compressed format because we don't need T and want better accuracy on course angle. - for more information on APRS, see http://www.aprs.org/doc/APRS101.PDF - - - lat and lng are in decimal degrees. no need to convert to DMS. - course is in degrees, speed is in knots, altitude is in feet, stage is an integer, orientation is in degrees. - */ - - // lat and lng - message[cursor++] = '!'; // Message type (position without timestamp) - message[cursor++] = 'M'; // overlay - encodeBase91(message, cursor, (int)380926 * (90 - data.lat), 4); // 380926 is the magic number from the APRS spec (page 38) - encodeBase91(message, cursor, (int)190463 * (180 + data.lng), 4); // 190463 is the magic number from the APRS spec (page 38) - message[cursor++] = '^'; // end of lat and lng - message[cursor++] = ' '; // space to start 'Comment' section - - // course, speed, altitude - encodeBase91(message, cursor, (int)(data.hdg * HDG_SCALE), 2); // (91^2/360) scale to fit in 2 base91 characters - encodeBase91(message, cursor, (int)(data.spd * SPD_SCALE), 2); // (91^2/1000) scale to fit in 2 base91 characters. 1000 knots is the assumed max speed. - encodeBase91(message, cursor, (int)((data.alt + ALT_OFFSET) * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. - - // stage and orientation - message[cursor++] = (uint8_t)(data.stage + (int)'0'); // stage is just written in plaintext. - encodeBase91(message, cursor, (int)(data.orientation.x() * ORIENTATION_SCALE), 2); // same as course - encodeBase91(message, cursor, (int)(data.orientation.y() * ORIENTATION_SCALE), 2); // same as course - encodeBase91(message, cursor, (int)(data.orientation.z() * ORIENTATION_SCALE), 2); // same as course - - len = cursor; -} - -#pragma endregion - -#pragma region Decode Helpers - -int APRSMsg::decodeHeader(const uint8_t *message, int len) -{ - // format: CALLSIGN>TOCALL,PATH: - int cursor = 0; - for (int i = 0; message[cursor] != '>'; i++, cursor++) - { - header.CALLSIGN[i] = message[cursor]; - } - header.CALLSIGN[cursor] = '\0'; - cursor++; // skip '>' - for (int i = 0; message[cursor] != ','; i++, cursor++) - { - header.TOCALL[i] = message[cursor]; - } - header.TOCALL[cursor] = '\0'; - cursor++; // skip ',' - for (int i = 0; message[cursor] != ':'; i++, cursor++) - { - header.PATH[i] = message[cursor]; - } - header.PATH[cursor] = '\0'; - cursor++; // skip ':' - return cursor; -} - -void APRSMsg::decodeData(const uint8_t *message, int len, int cursor) -{ - // lat and lng - cursor++; // skip '!' - cursor++; // skip overlay - decodeBase91(message, cursor, data.lat, 4); - data.lat = 90 - data.lat / 380926.0; - decodeBase91(message, cursor, data.lng, 4); - data.lng = data.lng / 190463.0 - 180; - cursor++; // skip '^' - cursor++; // skip ' ' - - // course, speed, altitude - decodeBase91(message, cursor, data.hdg, 2); - data.hdg /= HDG_SCALE; - decodeBase91(message, cursor, data.spd, 2); - data.spd /= SPD_SCALE; - decodeBase91(message, cursor, data.alt, 2); - data.alt = data.alt / ALT_SCALE - ALT_OFFSET; - - // stage and orientation - data.stage = message[cursor++] - (int)'0'; - decodeBase91(message, cursor, data.orientation.x(), 2); - data.orientation.x() /= ORIENTATION_SCALE; - decodeBase91(message, cursor, data.orientation.y(), 2); - data.orientation.y() /= ORIENTATION_SCALE; - decodeBase91(message, cursor, data.orientation.z(), 2); - data.orientation.z() /= ORIENTATION_SCALE; -} - -#pragma endregion - -#pragma region Base91 Encoding - -void APRSMsg::encodeBase91(uint8_t *message, int &cursor, int value, int precision) const -{ - for (int i = precision - 1; i >= 0; i--) - { - int divisor = pow(91, i); - message[cursor++] = (uint8_t)((int)(value / divisor) + 33); - value %= divisor; - } -} - -void APRSMsg::decodeBase91(const uint8_t *message, int &cursor, double &value, int precision) const -{ - value = 0; - for (int i = 0; i < precision; i++) - { - value += (message[cursor++] - 33) * pow(91, precision - i - 1); - } -} - -#pragma endregion \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h deleted file mode 100644 index b6172cc8..00000000 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/APRSMsg.h +++ /dev/null @@ -1,86 +0,0 @@ -#ifndef APRSMSG_H -#define APRSMSG_H - -#if defined(ARDUINO) -#include -#elif defined(_WIN32) || defined(_WIN64) // Windows -#include -#include -#include -#elif defined(__unix__) // Linux -// TODO -#elif defined(__APPLE__) // OSX -// TODO -#endif - -#include "Radio.h" -#include - -/* -APRS Configuration -- CALLSIGN -- TOCALL -- PATH -- SYMBOL -- OVERLAY -*/ -struct APRSHeader -{ - char CALLSIGN[8]; - char TOCALL[8]; - char PATH[10]; -}; - -/* -APRS Telemetry Data -- lat -- lng -- alt -- spd -- hdg -- orientation -- stage -*/ -struct APRSData -{ - double lat; - double lng; - double alt; - double spd; - double hdg; - int stage; - imu::Vector<3> orientation; -}; - -class APRSMsg : public RadioMessage -{ -public: - APRSMsg(APRSHeader &header); - virtual ~APRSMsg(){}; - - bool decode(const uint8_t *message, int len) override; - bool encode(uint8_t *message) override; - int length() const override { return this->len; } - APRSData data; - APRSHeader header; - -private: - int encodeHeader(uint8_t *message) const; - void encodeData(uint8_t *message, int cursor); - - int decodeHeader(const uint8_t *message, int len); - void decodeData(const uint8_t *message, int len, int cursor); - - void encodeBase91(uint8_t *message, int &cursor, int value, int precision) const; - void decodeBase91(const uint8_t *message, int &cursor, double &value, int precision) const; - - // Scale factors for encoding/decoding ignoring lat/long - const double ALT_SCALE = (pow(91, 2) / 16000.0); // (91^2/16000) scale to fit in 2 base91 characters - const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters - const double HDG_SCALE = (pow(91, 2) / 360.0); // (91^2/360) scale to fit in 2 base91 characters - const double ORIENTATION_SCALE = (pow(91, 2) / 360.0); // same as course - - const int ALT_OFFSET = +1000; // range of -1000 to 15000 ft. -}; - -#endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index fe4bcdbb..45fd3de7 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -1,15 +1,15 @@ #ifndef ENCODE_APRS_FOR_SERIAL_H #define ENCODE_APRS_FOR_SERIAL_H -#include "APRSMsg.h" +#include "../Radio/APRS/APRSTelemMsg.h" namespace aprsToSerial { const char OVERLAY = '/'; const char SYMBOL = '['; // Jogger symbol. I disagree with this usage. - void encodeLatLong(const APRSMsg &msg, char *buffer, size_t buffer_size); - void encodeAltitude(const APRSMsg &msg, char *buffer, size_t buffer_size); + void encodeLatLong(const APRSTelemMsg &msg, char *buffer, size_t buffer_size); + void encodeAltitude(const APRSTelemMsg &msg, char *buffer, size_t buffer_size); /* * Encodes an APRS message into a string for serial transmission @@ -18,7 +18,7 @@ namespace aprsToSerial * \param buffer_size The size of the buffer * \return void */ - void encodeAPRSForSerial(const APRSMsg &msg, char *buffer, size_t buffer_size, int RSSI) + void encodeAPRSForSerial(const APRSTelemMsg &msg, char *buffer, size_t buffer_size, int RSSI) { char prefix[8] = "s\r\n"; char header[100]; @@ -33,7 +33,7 @@ namespace aprsToSerial snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); } - void encodeLatLong(const APRSMsg &msg, char *buffer, size_t buffer_size) + void encodeLatLong(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) { int lat_deg = (int)abs(msg.data.lat); double lat_min = ((msg.data.lat - lat_deg) * 60); @@ -48,7 +48,7 @@ namespace aprsToSerial } - void encodeAltitude(const APRSMsg &msg, char *buffer, size_t buffer_size) + void encodeAltitude(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) { // format: A=DDDDDD int alt = (int)msg.data.alt; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index 5c4c42e6..7006ded4 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -1,12 +1,16 @@ -#include "RFM69HCW.h" #include "EncodeAPRSForSerial.h" #include "Adafruit_BNO055.h" #include +#include "../Radio/RFM69HCW.h" +#include "../Radio/APRS/APRSCmdMsg.h" APRSHeader header; -APRSMsg msg(header); -RadioSettings settings = {915.0, false, false, &hardware_spi, 10, 31, 32}; +APRSTelemMsg msg(header); +APRSCmdMsg cmd(header); +RadioSettings settings = {915.0, 0x02, 0x01, &hardware_spi, 10, 31, 32}; RFM69HCW radio(&settings); + + void setup() { delay(2000); @@ -14,8 +18,14 @@ void setup() Serial.println("Radio failed to initialize"); else Serial.println("Radio initialized"); + cmd.data.MinutesUntilPowerOn = 0; + cmd.data.MinutesUntilDataRecording = 1; + cmd.data.MinutesUntilVideoStart = 2; + cmd.data.Launch = false; } + +int counter = 1; void loop() { if (radio.update()) @@ -26,5 +36,18 @@ void loop() aprsToSerial::encodeAPRSForSerial(msg, buffer, 255, radio.RSSI()); Serial.println(buffer); } + if(counter % 100 == 0) + { + radio.enqueueSend(&msg); + } + if(counter % 500 == 0) + { + cmd.data.Launch = !cmd.data.Launch; + radio.enqueueSend(&cmd); + } + counter++; + char *b = (char *)cmd.getArr(); + b[cmd.length()] = '\0'; + printf("Cmd: %s\n", b); } } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp new file mode 100644 index 00000000..da1e19e7 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp @@ -0,0 +1,37 @@ +#include "Pi.h" + +Pi::Pi(int pinControl, int pinVideo) +{ + this->pinControl = pinControl; + this->pinVideo = pinVideo; + pinMode(this->pinControl, OUTPUT); + pinMode(this->pinVideo, OUTPUT); + digitalWrite(this->pinVideo, HIGH); // Set video pin to high (off) by default + this->on = false; + this->recording = false; +} + +void Pi::setOn(bool on) +{ + digitalWrite(this->pinControl, on ? HIGH : LOW); + this->on = on; +} + +void Pi::setRecording(bool recording) +{ + if(this->recording == recording) return; // If the recording state is the same, do nothing + + bb.aonoff(BUZZER, 100, 3); // Buzz 3 times (100ms on, 100ms off) + digitalWrite(this->pinVideo, recording ? LOW : HIGH); + this->recording = recording; +} + +bool Pi::isOn() +{ + return this->on; +} + +bool Pi::isRecording() +{ + return this->recording; +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.h new file mode 100644 index 00000000..1f7bbfe6 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.h @@ -0,0 +1,23 @@ +#ifndef PI_H +#define PI_H + +#include +#include + +class Pi +{ +public: + Pi(int pinControl, int pinVideo); + void setOn(bool on); + void setRecording(bool recording); + bool isOn(); + bool isRecording(); + +private: + int pinControl; + int pinVideo; + bool on; + bool recording; +}; + +#endif // PI_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp new file mode 100644 index 00000000..44bc21c4 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp @@ -0,0 +1,19 @@ +#include "APRSCmdMsg.h" + +void APRSCmdMsg::encodeData(int cursor) +{ + snprintf((char *)string[cursor], RADIO_MESSAGE_BUFFER_SIZE - cursor, + ":%-09s:PWR:%d VID:%d DAT:%d L:%d", header.CALLSIGN, data.MinutesUntilPowerOn, data.MinutesUntilVideoStart, data.MinutesUntilDataRecording, data.Launch); +} +void APRSCmdMsg::decodeData(int cursor) +{ + sscanf((char *)string[cursor], ":%*9s:PWR:%d VID:%d DAT:%d L:%d", &data.MinutesUntilPowerOn, &data.MinutesUntilVideoStart, &data.MinutesUntilDataRecording, &data.Launch); +} + +APRSCmdMsg::APRSCmdMsg(APRSHeader &header) : APRSMsgBase(header) +{ + data.MinutesUntilPowerOn = 0; + data.MinutesUntilVideoStart = 0; + data.MinutesUntilDataRecording = 0; + data.Launch = false; +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h new file mode 100644 index 00000000..3c62529d --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h @@ -0,0 +1,25 @@ +#ifndef APRS_CMD_MSG_H +#define APRS_CMD_MSG_H + +#include "APRSMsgBase.h" + +struct APRSCmdData +{ + uint8_t MinutesUntilPowerOn; // Minutes until the Pi turns on - 0 means turn on now + uint8_t MinutesUntilVideoStart; // Minutes until the Pi starts recording video - 0 means start now + uint8_t MinutesUntilDataRecording; // Minutes until the FC starts recording data - 0 means start now + bool Launch; // Send the launch command to the FC - 0 means don't send +}; + +class APRSCmdMsg : public APRSMsgBase +{ +public: + APRSCmdData data; + APRSCmdMsg(APRSHeader &header); + +protected: + virtual void decodeData(int cursor) override; + virtual void encodeData(int cursor) override; +}; + +#endif // APRS_CMD_MSG_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp new file mode 100644 index 00000000..cc68926d --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp @@ -0,0 +1,97 @@ +#include "APRSMsgBase.h" + +#define MAX_ALLOWED_MSG_LEN 255 /* max length of 1 message supported by radio buffer */ + +APRSMsgBase::APRSMsgBase(APRSHeader &header) +{ + this->header = header; +} + +bool APRSMsgBase::encode() +{ + int c = encodeHeader(); + encodeData(c); + return true; +} + +bool APRSMsgBase::decode() +{ + // message needs to be decoded and values reinserted into the header and data structs + int c = decodeHeader(); + decodeData(c); + return true; +} + +#pragma region APRSMsgBase Header Encoding/Decoding + +int APRSMsgBase::encodeHeader() +{ + // format: CALLSIGN>TOCALL,PATH: + int cursor = 0; + for (int i = 0; header.CALLSIGN[i] && i < 8; i++, cursor++) + { + string[cursor] = header.CALLSIGN[i]; + } + string[cursor++] = '>'; + for (int i = 0; header.TOCALL[i] && i < 8; i++, cursor++) + { + string[cursor] = header.TOCALL[i]; + } + string[cursor++] = ','; + for (int i = 0; header.PATH[i] && i < 10; i++, cursor++) + { + string[cursor] = header.PATH[i]; + } + string[cursor++] = ':'; // end of header + return cursor; +} + +int APRSMsgBase::decodeHeader() +{ + // format: CALLSIGN>TOCALL,PATH: + int cursor = 0; + for (int i = 0; string[cursor] != '>'; i++, cursor++) + { + header.CALLSIGN[i] = string[cursor]; + } + header.CALLSIGN[cursor] = '\0'; + cursor++; // skip '>' + for (int i = 0; string[cursor] != ','; i++, cursor++) + { + header.TOCALL[i] = string[cursor]; + } + header.TOCALL[cursor] = '\0'; + cursor++; // skip ',' + for (int i = 0; string[cursor] != ':'; i++, cursor++) + { + header.PATH[i] = string[cursor]; + } + header.PATH[cursor] = '\0'; + cursor++; // skip ':' + return cursor; +} + +#pragma endregion + +#pragma region Base91 Encoding + +void APRSMsgBase::encodeBase91(uint8_t *message, int &cursor, int value, int precision) +{ + for (int i = precision - 1; i >= 0; i--) + { + int divisor = pow(91, i); + message[cursor++] = (uint8_t)((int)(value / divisor) + 33); + value %= divisor; + } +} + +void APRSMsgBase::decodeBase91(const uint8_t *message, int &cursor, double &value, int precision) +{ + value = 0; + for (int i = 0; i < precision; i++) + { + value += (message[cursor++] - 33) * pow(91, precision - i - 1); + } +} + +#pragma endregion \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h new file mode 100644 index 00000000..f54d63c4 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h @@ -0,0 +1,72 @@ +#ifndef APRSMSG_H +#define APRSMSG_H + +#if defined(ARDUINO) +#include +#elif defined(_WIN32) || defined(_WIN64) // Windows +#include +#include +#include +#elif defined(__unix__) // Linux +// TODO +#elif defined(__APPLE__) // OSX +// TODO +#endif + +#include "../Radio.h" +#include + +const uint8_t PI_ON = 0b00000001; // Pi is on +const uint8_t PI_VIDEO = 0b00000010; // Pi is recording video +const uint8_t RECORDING_DATA = 0b00000100; // FC is recording data + +/* +APRS Configuration +- CALLSIGN +- TOCALL +- PATH +- SYMBOL +- OVERLAY +*/ +struct APRSHeader +{ + char CALLSIGN[8]; + char TOCALL[8]; + char PATH[10]; + char SYMBOL; + char OVERLAY; +}; + +/* +APRS Telemetry Data +- lat +- lng +- alt +- spd +- hdg +- stage +- orientation +*/ + + +class APRSMsgBase : public RadioMessage +{ +public: + APRSMsgBase(APRSHeader &header); + virtual ~APRSMsgBase(){}; + + virtual bool decode() override; + virtual bool encode() override; + APRSHeader header; +protected: + virtual int encodeHeader(); + virtual int decodeHeader(); + virtual void encodeData(int cursor) = 0; + virtual void decodeData(int cursor) = 0; + void encodeBase91(uint8_t *message, int &cursor, int value, int precision); + void decodeBase91(const uint8_t *message, int &cursor, double &value, int precision); + +private: +}; + +#endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp new file mode 100644 index 00000000..5e864c2e --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp @@ -0,0 +1,97 @@ +#include "APRSTelemMsg.h" + +APRSTelemMsg::APRSTelemMsg(APRSHeader &header) : APRSMsgBase(header) +{ + data.lat = 0; + data.lng = 0; + data.alt = 0; + data.spd = 0; + data.hdg = 0; + data.stage = 0; + data.orientation = imu::Vector<3>(0, 0, 0); + data.statusFlags = 0; +} + +#pragma region Encode Helpers + +void APRSTelemMsg::encodeData(int cursor) +{ + /* Small Aircraft symbol ( /' ) probably better than Jogger symbol ( /[ ) lol. + I'm going to use the Overlayed Aircraft symbol ( \^ ) for now, with the overlay of 'M' for UMD ( M^ ). + Uses base91 encoding to compress message as much as possible. APRS messages are apparently supposed to be only 256 bytes. + + + takes the regular format of !DDMM.hhN/DDDMM.hhW^ALTSPD/HDG SSOrientationF + + which expands to !(lat)/(lng)^altspd/hdg (stage #)(orientation)(status flags) + + and compresses it to /YYYYXXXX^ ccssaasoooooof + + which expands to /(lat)(lng)^ (course)(speed)(altitude)(stage)(orientation [as euler angles])(status flags) + + specifically does not use the csT compressed format because we don't need T and want better accuracy on course angle. + for more information on APRS, see http://www.aprs.org/doc/APRS101.PDF + + + lat and lng are in decimal degrees. no need to convert to DMS. + course is in degrees, speed is in knots, altitude is in feet, stage is an integer, orientation is in degrees, Pi status is a byte of flags. + */ + + // lat and lng + string[cursor++] = '!'; // Message type (position without timestamp) + string[cursor++] = 'M'; // overlay + encodeBase91(string, cursor, (int)380926 * (90 - data.lat), 4); // 380926 is the magic number from the APRS spec (page 38) + encodeBase91(string, cursor, (int)190463 * (180 + data.lng), 4); // 190463 is the magic number from the APRS spec (page 38) + string[cursor++] = '^'; // end of lat and lng + string[cursor++] = ' '; // space to start 'Comment' section + + // course, speed, altitude + encodeBase91(string, cursor, (int)(data.hdg * HDG_SCALE), 2); // (91^2/360) scale to fit in 2 base91 characters + encodeBase91(string, cursor, (int)(data.spd * SPD_SCALE), 2); // (91^2/1000) scale to fit in 2 base91 characters. 1000 knots is the assumed max speed. + encodeBase91(string, cursor, (int)((data.alt + ALT_OFFSET) * ALT_SCALE), 2); // (91^2/15000) scale to fit in 2 base91 characters. 15000 feet is the assumed max altitude. + + // stage and orientation + string[cursor++] = (uint8_t)(data.stage + (int)'0'); // stage is just written in plaintext. + encodeBase91(string, cursor, (int)(data.orientation.x() * ORIENTATION_SCALE), 2); // same as course + encodeBase91(string, cursor, (int)(data.orientation.y() * ORIENTATION_SCALE), 2); // same as course + encodeBase91(string, cursor, (int)(data.orientation.z() * ORIENTATION_SCALE), 2); // same as course + string[cursor++] = (uint8_t)(data.statusFlags + 33); // all content is supposed to be printable ASCII characters, so we add 33 to the status flags to make sure it is. + len = cursor; +} + +#pragma endregion + +#pragma region Decode Helpers + +void APRSTelemMsg::decodeData(int cursor) +{ + // lat and lng + cursor++; // skip '!' + cursor++; // skip overlay + decodeBase91(string, cursor, data.lat, 4); + data.lat = 90 - data.lat / 380926.0; + decodeBase91(string, cursor, data.lng, 4); + data.lng = data.lng / 190463.0 - 180; + cursor++; // skip '^' + cursor++; // skip ' ' + + // course, speed, altitude + decodeBase91(string, cursor, data.hdg, 2); + data.hdg /= HDG_SCALE; + decodeBase91(string, cursor, data.spd, 2); + data.spd /= SPD_SCALE; + decodeBase91(string, cursor, data.alt, 2); + data.alt = data.alt / ALT_SCALE - ALT_OFFSET; + + // stage and orientation + data.stage = string[cursor++] - (int)'0'; + decodeBase91(string, cursor, data.orientation.x(), 2); + data.orientation.x() /= ORIENTATION_SCALE; + decodeBase91(string, cursor, data.orientation.y(), 2); + data.orientation.y() /= ORIENTATION_SCALE; + decodeBase91(string, cursor, data.orientation.z(), 2); + data.orientation.z() /= ORIENTATION_SCALE; + data.statusFlags = string[cursor++] - 33; +} + +#pragma endregion diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h new file mode 100644 index 00000000..96461000 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h @@ -0,0 +1,40 @@ +#ifndef APRS_TELEM_MSG_H +#define APRS_TELEM_MSG_H + +#include "APRSMsgBase.h" + + + +struct APRSTelemData +{ + double lat; + double lng; + double alt; + double spd; + double hdg; + int stage; + imu::Vector<3> orientation; + uint8_t statusFlags; +}; + +class APRSTelemMsg : public APRSMsgBase +{ +public: + APRSTelemData data; + APRSTelemMsg(APRSHeader &header); + +protected: + virtual void decodeData(int cursor) override; + virtual void encodeData(int cursor) override; +private: + void encodeStatus(uint8_t *string, int &cursor); + // Scale factors for encoding/decoding ignoring lat/long + const double ALT_SCALE = (pow(91, 2) / 16000.0); // (91^2/16000) scale to fit in 2 base91 characters + const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters + const double HDG_SCALE = (pow(91, 2) / 360.0); // (91^2/360) scale to fit in 2 base91 characters + const double ORIENTATION_SCALE = (pow(91, 2) / 360.0); // same as course + + const int ALT_OFFSET = +1000; // range of -1000 to 15000 ft. +}; + +#endif // APRS_TELEM_MSG_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp similarity index 60% rename from Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp rename to Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index 7ff5280d..ab0d4ace 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -19,19 +19,6 @@ RFM69HCW::RFM69HCW(const RadioSettings *s) : radio(s->cs, s->irq, *s->spi) { this->settings = *s; - - if (this->settings.transmitter) - { - // addresses for transmitters - this->thisAddr = 0x02; - this->toAddr = 0x01; - } - else - { - // addresses for receivers - this->thisAddr = 0x01; - this->toAddr = 0x02; - } } /* @@ -55,30 +42,30 @@ bool RFM69HCW::init() return false; // set transmit power - radio.setTxPower(txPower, true); + radio.setTxPower(settings.txPower, true); // always set FSK mode radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); // set headers - radio.setHeaderTo(toAddr); - radio.setHeaderFrom(thisAddr); - radio.setThisAddress(thisAddr); + radio.setHeaderTo(settings.toAddr); + radio.setHeaderFrom(settings.thisAddr); + radio.setThisAddress(settings.thisAddr); radio.setHeaderId(0); // configure unlimited packet length mode, don't do this for now // this->radio.spiWrite(0x37, 0b00000000); // Packet format (0x37) set to 00000000 (see manual for meaning of each bit) // this->radio.spiWrite(RH_RF69_REG_38_PAYLOADLENGTH, 0); // Payload length (0x38) set to 0 - if (this->settings.highBitrate) // Note: not working - { - // the default bitrate of 4.8kbps should be fine unless we want high bitrate for video - // set300KBPS(); - this->radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); - // remove as much overhead as possible - // this->radio.setPreambleLength(0); - // this->radio.setSyncWords(); - } + // if (this->settings.highBitrate) // Note: not working + // { + // // the default bitrate of 4.8kbps should be fine unless we want high bitrate for video + // // set300KBPS(); + // this->radio.setModemConfig(RH_RF69::FSK_Rb4_8Fd9_6); + // // remove as much overhead as possible + // // this->radio.setPreambleLength(0); + // // this->radio.setSyncWords(); + // } return initialized = true; } @@ -96,7 +83,7 @@ bool RFM69HCW::tx(const uint8_t *message, int len, int packetNum, bool lastPacke // figure out how long the message should be if (len == -1) len = strlen((char *)message); - + radio.setHeaderId(packetNum); radio.setHeaderFlags(lastPacket ? 0 : RADIO_FLAG_MORE_DATA); @@ -132,20 +119,20 @@ Enqueue a message into the buffer bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) { // fill up the buffer with the message. buffer is a circular queue. - int originalTail = bufTail; - buffer[bufTail] = len; - inc(bufTail); + int originalTail = sendBuffer.tail; + sendBuffer.data[sendBuffer.tail] = len; // store the length of the message + inc(sendBuffer.tail); for (int i = 0; i < len; i++) // same algorithm as copyToBuffer but with a length check { - if (bufTail == bufHead) - { // buffer is full - bufTail = originalTail; // reset the tail (no message was added) + if (sendBuffer.tail == sendBuffer.head) // buffer is full + { + sendBuffer.tail = originalTail; // reset the tail (no message was added) return false; } - buffer[bufTail] = message[i]; - inc(bufTail); + sendBuffer.data[sendBuffer.tail] = message[i]; + inc(sendBuffer.tail); } return true; } @@ -166,12 +153,8 @@ Encode the message and enqueue it in the buffer */ bool RFM69HCW::enqueueSend(RadioMessage *message) { - uint8_t encodedMessage[RadioMessage::MAX_MESSAGE_LEN]; - if (message->encode(encodedMessage)) - { - int messageLength = message->length(); - return enqueueSend(encodedMessage, messageLength); - } + if (message->encode()) + return enqueueSend(message->getArr(), message->length()); return false; } /* @@ -181,14 +164,14 @@ Dequeue a message from the buffer and decode it into a uint8_t[]. */ bool RFM69HCW::dequeueReceive(uint8_t *message) { - if (bufHead == bufTail) // buffer is empty + if (recvBuffer.head == recvBuffer.tail) // buffer is empty return false; // get the length of the message - int len = buffer[bufHead]; - inc(bufHead); + int len = recvBuffer.data[recvBuffer.head]; + inc(recvBuffer.head); // Empty the buffer up to the length of the expected message - copyFromBuffer(message, len); + copyFromBuffer(recvBuffer, message, len); return true; } @@ -199,16 +182,16 @@ Dequeue a message from the buffer and decode it into a char[]. WIll break if the */ bool RFM69HCW::dequeueReceive(char *message) { - if (bufHead == bufTail) // buffer is empty + if (recvBuffer.head == recvBuffer.tail) // buffer is empty return false; // Empty the buffer up to the first null terminator - inc(bufHead); // skip the length byte, should be null terminated + inc(recvBuffer.head); // skip the length byte, should be null terminated int i = 0; - for (; buffer[bufHead] != '\0' && bufHead != bufTail; i++) + for (; recvBuffer.data[recvBuffer.head] != '\0' && recvBuffer.head != recvBuffer.tail; i++) { - message[i] = buffer[bufHead]; - inc(bufHead); + message[i] = recvBuffer.data[recvBuffer.head]; + inc(recvBuffer.head); } message[i] = '\0'; @@ -222,15 +205,16 @@ Dequeue a message from the buffer and decode it into a RadioMessage */ bool RFM69HCW::dequeueReceive(RadioMessage *message) { - if (bufHead == bufTail) // buffer is empty + if (recvBuffer.head == recvBuffer.tail) // buffer is empty return false; - uint8_t len = buffer[bufHead]; + uint8_t len = recvBuffer.data[recvBuffer.head]; uint8_t *msg = new uint8_t[len]; bool worked = false; if (dequeueReceive(msg)) // get the message from the buffer - if (message->decode(msg, len)) // decode the message - worked = true; + if (message->setArr(msg, len)) // send the message to the RadioMessage + if (message->decode()) // decode the message + worked = true; delete[] msg; return worked; @@ -248,60 +232,56 @@ Update function */ bool RFM69HCW::update() { - if (busy()) // radio is busy, cannot send or receive + if (!initialized) + return false; + if (busy()) return false; - // transmitter------------------------------------------------------ - if (settings.transmitter) - { - if (bufHead == bufTail) // buffer is empty, nothing to send - { - remainingLength = 0; - return false; - } + uint8_t rcvLen = RH_RF69_MAX_MESSAGE_LEN; + uint8_t rcvBuf[RH_RF69_MAX_MESSAGE_LEN]; - // send the message - int packetNum; - if (remainingLength == 0) // start a new message - { - remainingLength = buffer[bufHead]; // get the length of the message from the first byte of the message - inc(bufHead); - packetNum = 0; - } - else - packetNum = radio.headerId() + 1; - - // load message to tx - int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); // how much of the message to send - uint8_t msgToTransmit[RH_RF69_MAX_MESSAGE_LEN]; - copyFromBuffer(msgToTransmit, len); - bool b = tx(msgToTransmit, len, packetNum, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); - remainingLength -= len; - return b; - } - // receiver------------------------------------------------------ - else + if (rx(rcvBuf, &rcvLen)) { - uint8_t msg[RH_RF69_MAX_MESSAGE_LEN]; - uint8_t len = RH_RF69_MAX_MESSAGE_LEN; - if (!rx(msg, &len)) - return false; // no new message available - // store the message in the buffer if (radio.headerId() == 0) // start of a new message { - orignalBufferTail = bufTail; - buffer[bufTail] = len; // store the length of the message - inc(bufTail); + orignalBufferTail = recvBuffer.tail; + recvBuffer.data[recvBuffer.tail] = rcvLen; // store the length of the message + inc(recvBuffer.tail); } - else // continuing message - buffer[orignalBufferTail] += len; // update the total length of the message + else // continuing message + recvBuffer.data[orignalBufferTail] += rcvLen; // update the total length of the message - copyToBuffer(msg, len); + copyToBuffer(recvBuffer, rcvBuf, rcvLen); if (radio.headerFlags() & RADIO_FLAG_MORE_DATA) // more data is coming, should not process yet return false; + return true; } - return true; // message was sent or received (in full) + + // transmit + if (sendBuffer.head == sendBuffer.tail) // buffer is empty, nothing to send + { + remainingLength = 0; + return false; + } + + int packetNum; + if (remainingLength == 0) // start a new message + { + remainingLength = sendBuffer.data[sendBuffer.head]; // get the length of the message from the first byte of the message + inc(sendBuffer.head); + packetNum = 0; + } + else + packetNum = radio.headerId() + 1; + + // load message to tx + int len = min(remainingLength, RH_RF69_MAX_MESSAGE_LEN); // how much of the message to send + uint8_t msgToTransmit[RH_RF69_MAX_MESSAGE_LEN]; + copyFromBuffer(sendBuffer, msgToTransmit, len); + tx(msgToTransmit, len, packetNum, remainingLength <= RH_RF69_MAX_MESSAGE_LEN); + remainingLength -= len; + return false; // always false for transmitter } #pragma region Helpers @@ -325,18 +305,18 @@ int RFM69HCW::RSSI() } // probably broken -void RFM69HCW::set300KBPSMode() -{ - this->radio.spiWrite(0x03, 0x00); // REG_BITRATEMSB: 300kbps (0x006B, see DS p20) - this->radio.spiWrite(0x04, 0x6B); // REG_BITRATELSB: 300kbps (0x006B, see DS p20) - this->radio.spiWrite(0x19, 0x40); // REG_RXBW: 500kHz - this->radio.spiWrite(0x1A, 0x80); // REG_AFCBW: 500kHz - this->radio.spiWrite(0x05, 0x13); // REG_FDEVMSB: 300khz (0x1333) - this->radio.spiWrite(0x06, 0x33); // REG_FDEVLSB: 300khz (0x1333) - this->radio.spiWrite(0x29, 240); // set REG_RSSITHRESH to -120dBm - this->radio.spiWrite(0x37, 0b10010000); // DC=WHITENING, CRCAUTOOFF=0 - // ^^->DC: 00=none, 01=manchester, 10=whitening -} +// void RFM69HCW::set300KBPSMode() +// { +// this->radio.spiWrite(0x03, 0x00); // REG_BITRATEMSB: 300kbps (0x006B, see DS p20) +// this->radio.spiWrite(0x04, 0x6B); // REG_BITRATELSB: 300kbps (0x006B, see DS p20) +// this->radio.spiWrite(0x19, 0x40); // REG_RXBW: 500kHz +// this->radio.spiWrite(0x1A, 0x80); // REG_AFCBW: 500kHz +// this->radio.spiWrite(0x05, 0x13); // REG_FDEVMSB: 300khz (0x1333) +// this->radio.spiWrite(0x06, 0x33); // REG_FDEVLSB: 300khz (0x1333) +// this->radio.spiWrite(0x29, 240); // set REG_RSSITHRESH to -120dBm +// this->radio.spiWrite(0x37, 0b10010000); // DC=WHITENING, CRCAUTOOFF=0 +// // ^^->DC: 00=none, 01=manchester, 10=whitening +// } // utility functions #ifndef max @@ -357,22 +337,25 @@ int min(int a, int b) } #endif -void RFM69HCW::copyToBuffer(const uint8_t *message, int len) +void RFM69HCW::copyToBuffer(buffer &buffer, const uint8_t *src, int len) { for (int i = 0; i < len; i++) { - buffer[bufTail] = message[i]; - inc(bufTail); + buffer.data[buffer.tail] = src[i]; + inc(buffer.tail); } } - -void RFM69HCW::copyFromBuffer(uint8_t *message, int len) +// pop is true by default. If pop is false, the buffer head will not be moved. +void RFM69HCW::copyFromBuffer(buffer &buffer, uint8_t *dest, int len, bool pop) { + int originalHead = buffer.head; for (int i = 0; i < len; i++) { - message[i] = buffer[bufHead]; - inc(bufHead); + dest[i] = buffer.data[buffer.head]; + inc(buffer.head); } + if (!pop) + buffer.head = originalHead; } #pragma endregion diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h similarity index 66% rename from Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h rename to Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h index 12c78202..6c18b84c 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69HCW.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h @@ -3,37 +3,22 @@ #include "RH_RF69.h" #include "Radio.h" -#include "APRSMsg.h" - -#define RADIO_BUFFER_SIZE 1024 -#define RADIO_FLAG_MORE_DATA 0b00000001 // custom flag to indicate more packets are still to be sent - -/* -Settings: -- double frequency in Mhz -- bool transmitter -- bool highBitrate -- RHGenericSPI *spi pointer to radiohead SPI object -- uint8_t cs CS pin -- uint8_t irq IRQ pin -- uint8_t rst RST pin -*/ -struct RadioSettings -{ - double frequency; - bool transmitter; - bool highBitrate; - RHGenericSPI *spi; - uint8_t cs; - uint8_t irq; - uint8_t rst; - int txPower = 20; -}; +#include "APRS/APRSMsgBase.h" + +const int TRANSCEIVER_MESSAGE_BUFFER_SIZE = 512; // length of the buffer underpinning the queue of messages to send or receive. Radio makes 2 buffers this size for sending and receiving. +#define RADIO_FLAG_MORE_DATA 0b00000001 // custom flag to indicate more packets are still to be sent #ifndef RH_RF69_MAX_MESSAGE_LEN #define RH_RF69_MAX_MESSAGE_LEN 66 #endif // !RH_RF69_MAX_MESSAGE_LEN +struct buffer +{ + uint8_t data[TRANSCEIVER_MESSAGE_BUFFER_SIZE]; + int head; + int tail; +}; + class RFM69HCW : public Radio { public: @@ -50,43 +35,38 @@ class RFM69HCW : public Radio bool dequeueReceive(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. bool dequeueReceive(char *message) override; // designed to be used externally. can exceed 66 bytes. bool dequeueReceive(uint8_t *message) override; // designed to be used externally. can exceed 66 bytes. - + int RSSI() override; - void set300KBPSMode(); - bool update(); + bool update() override; explicit operator bool() const { return initialized; } // increment the specified index, wrapping around if necessary - static void inc(int &i) { i = (i + 1) % RADIO_BUFFER_SIZE; } + static void inc(int &i) { i = (i + 1) % TRANSCEIVER_MESSAGE_BUFFER_SIZE; } + + // public during debugging - //public during debugging - uint8_t buffer[RADIO_BUFFER_SIZE]; + // stores queue of messages, with the length of the message as the first byte of each. no delimiter. + // [6xxxxxx3xxx1x2xx] + // Done to allow for messages that are not ascii encoded. + buffer sendBuffer; + buffer recvBuffer; RH_RF69 radio; private: // all radios should have the same networkID const uint8_t networkID = 1; - // default to the highest transmit power - const int txPower = 20; - // set by constructor - RadioSettings settings; + int thisAddr; int toAddr; int rssi; bool initialized = false; - // stores queue of messages, with the length of the message as the first byte of each. no delimiter. - // [6xxxxxx3xxx1x2xx] - // Done to allow for messages that are not ascii encoded. - int bufHead = 0; - int bufTail = 0; int remainingLength = 0; // how much message is left to send for transmitters int orignalBufferTail = 0; // used to update the length of the message after recieving. - void copyToBuffer(const uint8_t *message, int len); - void copyFromBuffer(uint8_t *message, int len); - + void copyToBuffer(buffer &buffer, const uint8_t *src, int len); + void copyFromBuffer(buffer &buffer, uint8_t *dest, int len, bool pop = true); }; #endif // RFM69HCW_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69Helper.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69Helper.h similarity index 94% rename from Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69Helper.h rename to Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69Helper.h index 486d1066..3e1a8463 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/RFM69Helper.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69Helper.h @@ -1,171 +1,171 @@ -#ifndef RFM69HELPER_H -#define RFM69HELPER_H - -#if defined(ARDUINO) -#include -#elif defined(_WIN32) || defined(_WIN64) // Windows - -#elif defined(__unix__) // Linux -// TODO -#elif defined(__APPLE__) // OSX -// TODO -#endif - -#ifndef ARDUINO -#include -#include -#include -#include -#include -#include - -#define SS 0 - -static uint64_t startTime = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); - -static uint32_t millis() -{ - return std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count() - startTime; -}; - -enum SPIDataMode -{ - SPI_MODE0 -}; - -enum SPIBitOrder -{ - MSBFIRST, - LSBFIRST -}; - -enum SPIClockDivider -{ - SPI_CLOCK_DIV2, - SPI_CLOCK_DIV8, - SPI_CLOCK_DIV16 -}; - -class SPISettings -{ -public: - SPISettings(){}; - SPISettings(uint32_t clock, uint8_t bitOrder, uint8_t dataMode) - { - this->clock = clock; - this->bitOrder = bitOrder; - this->dataMode = dataMode; - } - uint32_t clock = 4000000U; - uint8_t bitOrder = MSBFIRST; - uint8_t dataMode = SPI_MODE0; -}; - -// class SPIClass -// { -// public: -// SPIClass(); -// void begin(); - -// // with transaction -// void beginTransaction(SPISettings settings); -// void endTransaction(); - -// // non transaction -// void setDataMode(SPIDataMode dm); -// void setBitOrder(SPIBitOrder bo); -// void setClockDivider(SPIClockDivider cd); -// uint8_t transfer(uint8_t data); -// }; - -// SPIClass SPI; - -enum PinState : bool -{ - LOW, - HIGH -}; - -enum PinMode : bool -{ - INPUT, - OUTPUT -}; - -enum InterruptTrigger : bool -{ - FALLING, - RISING -}; - -// void digitalWrite(int pin, PinState state); -// void pinMode(int pin, PinMode mode); -// void attachInterrupt(uint8_t pin, void (*function)(), InterruptTrigger mode); -// void detachInterrupt(uint8_t pin); - -enum SerialPrintMode -{ - HEX, - BIN -}; - -class HardwareSerial -{ -public: - HardwareSerial(){}; - void print(const char *s) { std::cout << s; }; - void print(uint8_t num, SerialPrintMode m) - { - std::ios_base::fmtflags f(std::cout.flags()); - if (m == HEX) - { - std::cout << std::hex << num; - std::cout.flags(f); - } - if (m == BIN) - std::cout << std::bitset(num); - }; - void println() { std::cout << std::endl; }; - void println(const char *s) { std::cout << s << std::endl; }; - void println(uint8_t num, SerialPrintMode m) - { - print(num, m); - std::cout << std::endl; - }; -}; - -static HardwareSerial Serial = HardwareSerial(); - -#endif - -// add to RFM69.h -/* -#elif defined(_WIN32) || defined(_WIN64) // Windows -#define RF69_PLATFORM RF69_PLATFORM_WINDOWS -#else -*/ - -// TODO define the following -/* -digitalWrite -pinMode -SPIClass and necessary functions -SPI -HIGH -LOW -OUTPUT -millis -attachInterrupt -RISING - -SPI_MODE0 -MSBFIRST or SPI transaction - -SPI_CLOCK_DIV2 -detachInterrupt -Serial print and println - HEX - BIN -byte -*/ +#ifndef RFM69HELPER_H +#define RFM69HELPER_H + +#if defined(ARDUINO) +#include +#elif defined(_WIN32) || defined(_WIN64) // Windows + +#elif defined(__unix__) // Linux +// TODO +#elif defined(__APPLE__) // OSX +// TODO +#endif + +#ifndef ARDUINO +#include +#include +#include +#include +#include +#include + +#define SS 0 + +static uint64_t startTime = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); + +static uint32_t millis() +{ + return std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count() - startTime; +}; + +enum SPIDataMode +{ + SPI_MODE0 +}; + +enum SPIBitOrder +{ + MSBFIRST, + LSBFIRST +}; + +enum SPIClockDivider +{ + SPI_CLOCK_DIV2, + SPI_CLOCK_DIV8, + SPI_CLOCK_DIV16 +}; + +class SPISettings +{ +public: + SPISettings(){}; + SPISettings(uint32_t clock, uint8_t bitOrder, uint8_t dataMode) + { + this->clock = clock; + this->bitOrder = bitOrder; + this->dataMode = dataMode; + } + uint32_t clock = 4000000U; + uint8_t bitOrder = MSBFIRST; + uint8_t dataMode = SPI_MODE0; +}; + +// class SPIClass +// { +// public: +// SPIClass(); +// void begin(); + +// // with transaction +// void beginTransaction(SPISettings settings); +// void endTransaction(); + +// // non transaction +// void setDataMode(SPIDataMode dm); +// void setBitOrder(SPIBitOrder bo); +// void setClockDivider(SPIClockDivider cd); +// uint8_t transfer(uint8_t data); +// }; + +// SPIClass SPI; + +enum PinState : bool +{ + LOW, + HIGH +}; + +enum PinMode : bool +{ + INPUT, + OUTPUT +}; + +enum InterruptTrigger : bool +{ + FALLING, + RISING +}; + +// void digitalWrite(int pin, PinState state); +// void pinMode(int pin, PinMode mode); +// void attachInterrupt(uint8_t pin, void (*function)(), InterruptTrigger mode); +// void detachInterrupt(uint8_t pin); + +enum SerialPrintMode +{ + HEX, + BIN +}; + +class HardwareSerial +{ +public: + HardwareSerial(){}; + void print(const char *s) { std::cout << s; }; + void print(uint8_t num, SerialPrintMode m) + { + std::ios_base::fmtflags f(std::cout.flags()); + if (m == HEX) + { + std::cout << std::hex << num; + std::cout.flags(f); + } + if (m == BIN) + std::cout << std::bitset(num); + }; + void println() { std::cout << std::endl; }; + void println(const char *s) { std::cout << s << std::endl; }; + void println(uint8_t num, SerialPrintMode m) + { + print(num, m); + std::cout << std::endl; + }; +}; + +static HardwareSerial Serial = HardwareSerial(); + +#endif + +// add to RFM69.h +/* +#elif defined(_WIN32) || defined(_WIN64) // Windows +#define RF69_PLATFORM RF69_PLATFORM_WINDOWS +#else +*/ + +// TODO define the following +/* +digitalWrite +pinMode +SPIClass and necessary functions +SPI +HIGH +LOW +OUTPUT +millis +attachInterrupt +RISING + +SPI_MODE0 +MSBFIRST or SPI transaction + +SPI_CLOCK_DIV2 +detachInterrupt +Serial print and println + HEX + BIN +byte +*/ #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h similarity index 54% rename from Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h rename to Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h index 5e7c80d1..58d214ae 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/include/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h @@ -13,31 +13,27 @@ // TODO #endif +#include "RadioMessage.h" +#include "RadioHead.h" +#include "RHGenericSPI.h" /* -Types: -- ENCT_TELEMETRY: latitude,longitude,altitude,speed,heading,precision,stage,t0 <-> APRS message -- ENCT_VIDEO: char* filled with raw bytes <-> Raw byte array -- ENCT_GROUNDSTATION: Source:Value,Destination:Value,Path:Value,Type:Value,Body:Value <-> APRS message -- ENCT_NONE: no encoding is applied, same as using tx() +Settings: +- double frequency in Mhz +- RHGenericSPI *spi pointer to radiohead SPI object +- uint8_t cs CS pin +- uint8_t irq IRQ pin +- uint8_t rst RST pin */ -enum EncodingType +struct RadioSettings { - ENCT_TELEMETRY, - ENCT_VIDEO, - ENCT_GROUNDSTATION, - ENCT_NONE -}; - -class RadioMessage -{ -public: - virtual bool encode(uint8_t *message) = 0; // use stored variables to encode a message - virtual bool decode(const uint8_t *message, int len) = 0; // use `message` to set stored variables - virtual int length() const = 0; // return the length of the message - virtual ~RadioMessage(){}; - static constexpr int MAX_MESSAGE_LEN = 255; -protected: - uint8_t len; + double frequency; + uint8_t thisAddr; + uint8_t toAddr; + RHGenericSPI *spi; + uint8_t cs; + uint8_t irq; + uint8_t rst; + int txPower = 20; }; class Radio @@ -54,6 +50,10 @@ class Radio virtual bool dequeueReceive(RadioMessage *message) = 0; virtual bool dequeueReceive(char *message) = 0; virtual bool dequeueReceive(uint8_t *message) = 0; + virtual bool update() = 0; + +protected: + RadioSettings settings; }; #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp new file mode 100644 index 00000000..882f1a5b --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp @@ -0,0 +1,43 @@ +#include "RadioMessage.h" + +#include + +RadioMessage::RadioMessage() +{ + this->len = 0; +} + +/* +Copies a source array to the encoded message buffer + \param srcArr: the array to copy + \param len: the length of the source array + \return `false` if the length of the source array is greater than the buffer size, `true` otherwise +*/ +bool RadioMessage::setArr(const uint8_t *srcArr, int len) +{ + if (len > RADIO_MESSAGE_BUFFER_SIZE) + { + return false; + } + memcpy(this->string, srcArr, len); + this->len = len; + return true; +} + +/* +Copies the encoded message buffer to a destination array + \param destArr: the array to copy into + \param len: the length of the dest array + \return `false` if the length of the dest array is smaller than the buffer size, `true` otherwise +*/ +uint8_t *RadioMessage::getArr() +{ + return string; +} +/* +Returns the length of the encoded message +*/ +int RadioMessage::length() const +{ + return this->len; +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h new file mode 100644 index 00000000..39eac2dc --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h @@ -0,0 +1,24 @@ +#ifndef RADIO_MESSAGE_H +#define RADIO_MESSAGE_H + +#include + +const int RADIO_MESSAGE_BUFFER_SIZE = 255; // maximum length of an encoded `RadioMessage` in bytes. + +class RadioMessage +{ +public: + RadioMessage(); + virtual bool encode() = 0; // use stored variables to encode a message + virtual bool decode() = 0; // use `message` to set stored variables + virtual int length() const; // return the length of the message + virtual bool setArr(const uint8_t *srcArr, int len); // set the message to the given array + virtual uint8_t *getArr(); // get the message as an array + virtual ~RadioMessage(){}; + +protected: + uint8_t string[RADIO_MESSAGE_BUFFER_SIZE]; // buffer for the encoded message + uint8_t len; // length of the encoded message +}; + +#endif // RADIO_MESSAGE_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index 525e6b9b..2d28c304 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -32,6 +32,13 @@ State::State(bool useKalmanFilter, bool stateRecordsOwnFlightData) numSensors = 0; recordOwnFlightData = stateRecordsOwnFlightData; + + + /// + + recordOwnFlightData = false; // For radio testing. Will not record own data unless told to do so. + + /// for (int i = 0; i < NUM_MAX_SENSORS; i++) sensors[i] = nullptr; @@ -282,6 +289,9 @@ int State::getStageNum() { return stageNumber; } #pragma region Getters and Setters for Sensors +void State::setRecordOwnFlightData(bool value) { recordOwnFlightData = value; } +bool State::getRecordOwnFlightData() { return recordOwnFlightData; } + void State::setRadio(Radio *r) { radio = r; } Radio *State::getRadio() { return radio; } bool State::addSensor(Sensor *sensor, int sensorNum) @@ -374,36 +384,19 @@ void State::determineStage() // essentially, if we have either sensor and they meet launch threshold, launch. Otherwise, it will never detect a launch. { - bb.aonoff(33, 200); - setRecordMode(FLIGHT); - stageNumber = 1; - timeOfLaunch = timeAbsolute; - timePreviousStage = timeAbsolute; - timeSinceLaunch = 0; - strcpy(launchTimeOfDay, gps->getTimeOfDay()); recordLogData(INFO, "Launch detected."); - recordLogData(INFO, "Printing static data."); - for (int i = 0; i < NUM_MAX_SENSORS; i++) - { - if (sensorOK(sensors[i])) - { - char logData[200]; - snprintf(logData, 200, "%s: %s", sensors[i]->getName(), sensors[i]->getStaticDataString()); - recordLogData(INFO, logData); - sensors[i]->setBiasCorrectionMode(false); - } - } + launch(); } // TODO: Add checks for each sensor being ok and decide what to do if they aren't. else if (stageNumber == 1 && abs(acceleration.z()) < 10) { - bb.aonoff(33, 200, 2); + bb.aonoff(BUZZER, 200, 2); timePreviousStage = timeAbsolute; stageNumber = 2; recordLogData(INFO, "Coasting detected."); } else if (stageNumber == 2 && baroVelocity <= 0 && timeSinceLaunch > 5) { - bb.aonoff(33, 200, 3); + bb.aonoff(BUZZER, 200, 3); char logData[100]; snprintf(logData, 100, "Apogee detected at %.2f m.", position.z()); recordLogData(INFO, logData); @@ -413,14 +406,14 @@ void State::determineStage() } else if (stageNumber == 3 && baro->getRelAltFt() < 1000 && timeSinceLaunch > 10) { - bb.aonoff(33, 200, 4); + bb.aonoff(BUZZER, 200, 4); stageNumber = 4; timePreviousStage = timeAbsolute; recordLogData(INFO, "Main parachute conditions detected."); } else if (stageNumber == 4 && baroVelocity > -1 && baro->getRelAltFt() < 66 && timeSinceLaunch > 15) { - bb.aonoff(33, 200, 5); + bb.aonoff(BUZZER, 200, 5); timePreviousStage = timeAbsolute; stageNumber = 5; recordLogData(INFO, "Landing detected. Waiting for 5 seconds to dump data."); @@ -434,7 +427,28 @@ void State::determineStage() } } } - +void State::launch() +{ + recordOwnFlightData = true; // just in case this wasnt already set + bb.aonoff(BUZZER, 200); + setRecordMode(FLIGHT); + stageNumber = 1; + timeOfLaunch = timeAbsolute; + timePreviousStage = timeAbsolute; + timeSinceLaunch = 0; + strcpy(launchTimeOfDay, gps->getTimeOfDay()); + recordLogData(INFO, "Printing static data."); + for (int i = 0; i < NUM_MAX_SENSORS; i++) + { + if (sensorOK(sensors[i])) + { + char logData[200]; + snprintf(logData, 200, "%s: %s", sensors[i]->getName(), sensors[i]->getStaticDataString()); + recordLogData(INFO, logData); + sensors[i]->setBiasCorrectionMode(false); + } + } +} void State::setCsvString(char *dest, const char *start, int startSize, bool header) { int numCategories = numSensors + 1; @@ -484,29 +498,23 @@ bool State::sensorOK(const Sensor *sensor) #pragma endregion -bool State::transmit() +void State::fillAPRSData(APRSTelemData &data) { - aprs.data.lat = sensorOK(gps) ? gps->getPos().x() : 0; - aprs.data.lng = sensorOK(gps) ? gps->getPos().y() : 0; - aprs.data.alt = sensorOK(baro) ? baro->getRelAltFt() : 0; - aprs.data.hdg = (int)headingAngle; - aprs.data.spd = abs((int)(baroVelocity * 3.28)); - aprs.data.stage = stageNumber; - aprs.data.orientation = imu->getOrientation().toEuler(); - aprs.data.orientation.toDegrees(); - for(int i = 0; i < 3; i++) + data.lat = sensorOK(gps) ? gps->getPos().x() : 0; + data.lng = sensorOK(gps) ? gps->getPos().y() : 0; + data.alt = sensorOK(baro) ? baro->getRelAltFt() : 0; + data.hdg = (int)headingAngle; + data.spd = abs((int)(baroVelocity * 3.28)); + data.stage = stageNumber; + data.orientation = imu->getOrientation().toEuler(); + data.orientation.toDegrees(); + for (int i = 0; i < 3; i++) { - if(aprs.data.orientation[i] < 0) - aprs.data.orientation[i] += 360; + if (data.orientation[i] < 0) + data.orientation[i] += 360; } - radio->enqueueSend(&aprs); - uint8_t data[150]; - data[149] = '\0'; - aprs.encode(data); - //printf("%s\n", data); - //printf("Values: %f, %f, %.02f, %.02f, %.02f, %d, %d, %d, %d\n", aprs.data.lat, aprs.data.lng, aprs.data.hdg, aprs.data.spd, aprs.data.alt, aprs.data.stage, (int)aprs.data.orientation.z(), (int)aprs.data.orientation.y(), (int)aprs.data.orientation.x()); - return true; } + extern unsigned long _heap_start; extern unsigned long _heap_end; extern char *__brkval; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h index 35bd6c78..0e56e276 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h @@ -9,12 +9,14 @@ #include "GPS.h" #include "IMU.h" #include "LightSensor.h" -#include "Radio.h" +#include "Radio/Radio.h" #include "RTC.h" #include "RecordData.h" -#include "APRSMsg.h" +#include "Radio/APRS/APRSTelemMsg.h" constexpr char STAGES[][15] = {"Pre-Flight", "Boosting", "Coasting", "Drogue Descent", "Main Descent", "Post-Flight"}; + +extern APRSHeader header; class State { public: @@ -45,12 +47,15 @@ class State char *getCsvHeader(); char *getStateString(); // This contains only the portions that define what the state thinks the rocket looks like. - bool transmit(); + void fillAPRSData(APRSTelemData &data); + void setRecordOwnFlightData(bool val); + bool getRecordOwnFlightData(); + void launch(); double timeAbsolute; // in s since uC turned on private: int lastTimeAbsolute; - static constexpr int NUM_MAX_SENSORS = 3; // update with the max number of expected sensors. + static constexpr int NUM_MAX_SENSORS = 3; // update with the max number of expected sensors. SensorType SENSOR_ORDER[NUM_MAX_SENSORS] = {BAROMETER_, GPS_, IMU_}; // make this array the same length as NUM_MAX_SENSORS and fill it. // example if you have more than one of the same sensor type: // constexpr SensorType SENSOR_ORDER[] = {BAROMETER_, BAROMETER_, GPS_, IMU_}; or @@ -101,11 +106,11 @@ class State imu::Quaternion orientation; // in quaternion double baroVelocity; // in m/s double baroOldAltitude; // in m - double headingAngle; // in degrees + double headingAngle; // in degrees char launchTimeOfDay[9]; - //Kalman Filter settings + // Kalman Filter settings bool useKF; LinearKalmanFilter *kfilter; // time pos x y z vel x y z acc x y z @@ -117,10 +122,7 @@ class State uint32_t FreeMem(); // APRS - APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1"}; - - APRSMsg aprs = {header}; - + APRSTelemData data; }; #endif diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 10ddaef3..22471c23 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -4,30 +4,45 @@ #include "BNO055.h" #include "MAX_M10S.h" #include "DS3231.h" -#include "RFM69HCW.h" +#include "Radio/RFM69HCW.h" +#include "Radio/APRS/APRSCmdMsg.h" +#include "Radio/APRS/APRSTelemMsg.h" #include "RecordData.h" #include "BlinkBuzz.h" +#include "Pi.h" + +#define BMP_ADDR_PIN 36 +#define RPI_PWR 0 +#define RPI_VIDEO 1 BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 -RadioSettings settings = {915.0, true, false, &hardware_spi, 10, 31, 32}; + +RadioSettings settings = {915.0, 0x01, 0x02, &hardware_spi, 10, 31, 32}; RFM69HCW radio(&settings); +APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '^', 'M'}; +APRSCmdData currentCmdData; +APRSCmdMsg cmd(header); +APRSTelemMsg telem(header); +int timeSinceLastCmd = 0; +const int CMD_TIMEOUT_SEC = 10; // 10 seconds +void processCurrentCmdData(double time); + + State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); - +Pi rpi(RPI_PWR, RPI_VIDEO); PSRAM *ram; -#define BUZZER 33 -#define BMP_ADDR_PIN 36 -#define RPI_PWR 0 -#define RPI_VIDEO 1 - static double last = 0; // for better timing than "delay(100)" // BlinkBuzz setup +int BUZZER = 33; int allowedPins[] = {LED_BUILTIN}; BlinkBuzz bb(allowedPins, 1, true); + +// Free memory debug function extern unsigned long _heap_start; extern unsigned long _heap_end; extern char *__brkval; @@ -39,25 +54,17 @@ void FreeMem() Serial.print(" "); free(heapTop); } +// Free memory debug function void setup() { - pinMode(LED_BUILTIN, OUTPUT); bb.onoff(BUZZER, 100, 4, 100); recordLogData(INFO, "Initializing Avionics System. 5 second delay to prevent unnecessary file generation.", TO_USB); // delay(5000); pinMode(BMP_ADDR_PIN, OUTPUT); digitalWrite(BMP_ADDR_PIN, HIGH); - - pinMode(RPI_PWR, OUTPUT); // RASPBERRY PI TURN ON - pinMode(RPI_VIDEO, OUTPUT); // RASPBERRY PI TURN ON - - digitalWrite(RPI_PWR, LOW); - digitalWrite(RPI_VIDEO, HIGH); - - bb.onoff(LED_BUILTIN, 100); ram = new PSRAM(); // init after the SD card for better data logging. // The SD card MUST be initialized first to allow proper data logging. @@ -100,51 +107,102 @@ void setup() } sendSDCardHeader(computer.getCsvHeader()); } -static bool first = false; -static bool second = false; + void loop() { - bb.update(); - radio.update(); double time = millis(); - - if (time - radioTimer >= 1000) + bb.update(); + if (radio.update()) // if there is a message to be read { - computer.transmit(); - radioTimer = time; + APRSCmdData old = cmd.data; + if (radio.dequeueReceive(&cmd)) + { + char log[100]; + if (cmd.data.Launch != old.Launch) + { + snprintf(log, 100, "Launch Command Changed to %d.", cmd.data.Launch); + recordLogData(INFO, log); + currentCmdData.Launch = cmd.data.Launch; + } + if (cmd.data.MinutesUntilPowerOn != old.MinutesUntilPowerOn) + { + snprintf(log, 100, "Power On Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilPowerOn, (int)(currentCmdData.MinutesUntilPowerOn - time) / 60000); + recordLogData(INFO, log); + currentCmdData.MinutesUntilPowerOn = cmd.data.MinutesUntilPowerOn * 60 * 1000 + time; + } + if (cmd.data.MinutesUntilVideoStart != old.MinutesUntilVideoStart) + { + snprintf(log, 100, "Video Start Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilVideoStart, (int)(currentCmdData.MinutesUntilVideoStart - time) / 60000); + recordLogData(INFO, log); + currentCmdData.MinutesUntilVideoStart = cmd.data.MinutesUntilVideoStart * 60 * 1000 + time; + } + if (cmd.data.MinutesUntilDataRecording != old.MinutesUntilDataRecording) + { + snprintf(log, 100, "Data Recording Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilDataRecording, (int)(currentCmdData.MinutesUntilDataRecording - time) / 60000); + recordLogData(INFO, log); + currentCmdData.MinutesUntilDataRecording = cmd.data.MinutesUntilDataRecording * 60 * 1000 + time; + } + } } + processCurrentCmdData(time); + if (time - last < 100) return; last = time; computer.updateState(); - //recordLogData(INFO, computer.getStateString(), TO_USB); - // RASPBERRY PI TURN ON - if (time / 1000.0 > 810) + // recordLogData(INFO, computer.getStateString(), TO_USB); + + if (time - radioTimer >= 1000) { - digitalWrite(RPI_PWR, HIGH); - if (!first) - { - bb.aonoff(BUZZER, 100, 2); - first = true; - } + computer.fillAPRSData(telem.data); + + if (rpi.isOn()) + telem.data.statusFlags |= RPI_PWR; + else + telem.data.statusFlags &= ~RPI_PWR; + + if (rpi.isRecording()) + telem.data.statusFlags |= RPI_VIDEO; + else + telem.data.statusFlags &= ~RPI_VIDEO; + + if (computer.getRecordOwnFlightData()) + telem.data.statusFlags |= RECORDING_DATA; + else + telem.data.statusFlags &= ~RECORDING_DATA; + + radio.enqueueSend(&telem); + } + + // RASPBERRY PI TURN ON/VIDEO + if ((time / 1000.0 > 810 && time - timeSinceLastCmd > CMD_TIMEOUT_SEC * 1000) || computer.getStageNum() >= 1) + rpi.setOn(true); + if ((computer.getStageNum() >= 1 || time - timeSinceLastCmd > CMD_TIMEOUT_SEC * 1000) && rpi.isOn()) + rpi.setRecording(true); +} + +void processCurrentCmdData(double time) +{ + if (currentCmdData.Launch) + { + recordLogData(INFO, "Launch Command Received. Launching Rocket."); + computer.launch(); } - if (computer.getStageNum() >= 1) + + if (time > currentCmdData.MinutesUntilPowerOn) { - digitalWrite(RPI_VIDEO, LOW); - if (!second) - { - bb.aonoff(BUZZER, 100, 3); - second = true; - } + recordLogData(INFO, "Power On Radio Time Reached. Turning on Raspberry Pi."); + rpi.setOn(true); + } + if (time > currentCmdData.MinutesUntilVideoStart) + { + recordLogData(INFO, "Video Start Time Reached. Starting Video Recording."); + rpi.setRecording(true); + } + if (time > currentCmdData.MinutesUntilDataRecording) + { + recordLogData(INFO, "Data Recording Time Reached. Starting Data Recording."); + computer.setRecordOwnFlightData(true); } - // if (time / 1000.0 > 180) - // { - // digitalWrite(RPI_VIDEO, LOW); - // if (!second) - // { - // bb.aonoff(BUZZER, 100, 3); - // second = true; - // } - // } } From 89e6bfd914b960735c39a1a9d13a7e5a1e205266 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 23:11:29 -0400 Subject: [PATCH 23/41] Working Version from Desktop --- .../src/Radio/APRS/APRSCmdMsg.cpp | 10 ++++---- .../src/Radio/APRS/APRSCmdMsg.h | 6 ++--- .../src/Radio/RFM69HCW.cpp | 1 - .../Code/Teensy-Based Avionics/src/State.cpp | 6 ++--- .../Code/Teensy-Based Avionics/src/main.cpp | 23 ++++++++++--------- 5 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp index 44bc21c4..85a5f3e1 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp @@ -2,18 +2,18 @@ void APRSCmdMsg::encodeData(int cursor) { - snprintf((char *)string[cursor], RADIO_MESSAGE_BUFFER_SIZE - cursor, + snprintf((char *)&string[cursor], RADIO_MESSAGE_BUFFER_SIZE - cursor, ":%-09s:PWR:%d VID:%d DAT:%d L:%d", header.CALLSIGN, data.MinutesUntilPowerOn, data.MinutesUntilVideoStart, data.MinutesUntilDataRecording, data.Launch); } void APRSCmdMsg::decodeData(int cursor) { - sscanf((char *)string[cursor], ":%*9s:PWR:%d VID:%d DAT:%d L:%d", &data.MinutesUntilPowerOn, &data.MinutesUntilVideoStart, &data.MinutesUntilDataRecording, &data.Launch); + sscanf((char *)&string[cursor + 11], "PWR:%d VID:%d DAT:%d L:%d", &data.MinutesUntilPowerOn, &data.MinutesUntilVideoStart, &data.MinutesUntilDataRecording, &data.Launch); } APRSCmdMsg::APRSCmdMsg(APRSHeader &header) : APRSMsgBase(header) { - data.MinutesUntilPowerOn = 0; - data.MinutesUntilVideoStart = 0; - data.MinutesUntilDataRecording = 0; + data.MinutesUntilPowerOn = -1; + data.MinutesUntilVideoStart = -1; + data.MinutesUntilDataRecording = -1; data.Launch = false; } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h index 3c62529d..169e05b0 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h @@ -5,9 +5,9 @@ struct APRSCmdData { - uint8_t MinutesUntilPowerOn; // Minutes until the Pi turns on - 0 means turn on now - uint8_t MinutesUntilVideoStart; // Minutes until the Pi starts recording video - 0 means start now - uint8_t MinutesUntilDataRecording; // Minutes until the FC starts recording data - 0 means start now + int MinutesUntilPowerOn; // Minutes until the Pi turns on - 0 means turn on now + int MinutesUntilVideoStart; // Minutes until the Pi starts recording video - 0 means start now + int MinutesUntilDataRecording; // Minutes until the FC starts recording data - 0 means start now bool Launch; // Send the launch command to the FC - 0 means don't send }; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index ab0d4ace..e7d0388a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -264,7 +264,6 @@ bool RFM69HCW::update() remainingLength = 0; return false; } - int packetNum; if (remainingLength == 0) // start a new message { diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index 2d28c304..afe97ac0 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -416,12 +416,12 @@ void State::determineStage() bb.aonoff(BUZZER, 200, 5); timePreviousStage = timeAbsolute; stageNumber = 5; - recordLogData(INFO, "Landing detected. Waiting for 5 seconds to dump data."); + recordLogData(INFO, "Landing detected. Waiting for 30 seconds to dump data."); } - else if (stageNumber == 5 && timeSinceLaunch > 20) + else if (stageNumber == 5 && timeSinceLaunch > 15) { if (landingCounter++ >= 300) - { // roughly 5 seconds of data after landing + { // roughly 30 seconds of data after landing setRecordMode(GROUND); recordLogData(INFO, "Dumped data after landing."); } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 22471c23..cdccef5a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -22,14 +22,13 @@ MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 RadioSettings settings = {915.0, 0x01, 0x02, &hardware_spi, 10, 31, 32}; RFM69HCW radio(&settings); APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '^', 'M'}; -APRSCmdData currentCmdData; +APRSCmdData currentCmdData = {800000, 800000, 800000, false}; APRSCmdMsg cmd(header); APRSTelemMsg telem(header); -int timeSinceLastCmd = 0; -const int CMD_TIMEOUT_SEC = 10; // 10 seconds +int timeOfLastCmd = 0; +const int CMD_TIMEOUT_SEC = 100; // 10 seconds void processCurrentCmdData(double time); - State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); Pi rpi(RPI_PWR, RPI_VIDEO); @@ -114,6 +113,7 @@ void loop() bb.update(); if (radio.update()) // if there is a message to be read { + timeOfLastCmd = time; APRSCmdData old = cmd.data; if (radio.dequeueReceive(&cmd)) { @@ -173,34 +173,35 @@ void loop() telem.data.statusFlags &= ~RECORDING_DATA; radio.enqueueSend(&telem); + radioTimer = time; } // RASPBERRY PI TURN ON/VIDEO - if ((time / 1000.0 > 810 && time - timeSinceLastCmd > CMD_TIMEOUT_SEC * 1000) || computer.getStageNum() >= 1) + if ((time / 1000.0 > 810 && time - timeOfLastCmd > CMD_TIMEOUT_SEC * 1000) || computer.getStageNum() >= 1) rpi.setOn(true); - if ((computer.getStageNum() >= 1 || time - timeSinceLastCmd > CMD_TIMEOUT_SEC * 1000) && rpi.isOn()) + if ((computer.getStageNum() >= 1 || time - timeOfLastCmd > CMD_TIMEOUT_SEC * 1000) && rpi.isOn()) rpi.setRecording(true); } void processCurrentCmdData(double time) { - if (currentCmdData.Launch) + if (currentCmdData.Launch && computer.getStageNum() == 0) { recordLogData(INFO, "Launch Command Received. Launching Rocket."); computer.launch(); } - if (time > currentCmdData.MinutesUntilPowerOn) + if (time > currentCmdData.MinutesUntilPowerOn && !rpi.isOn()) { - recordLogData(INFO, "Power On Radio Time Reached. Turning on Raspberry Pi."); + recordLogData(INFO, "Power On RPI Time Reached. Turning on Raspberry Pi."); rpi.setOn(true); } - if (time > currentCmdData.MinutesUntilVideoStart) + if (time > currentCmdData.MinutesUntilVideoStart && !rpi.isRecording()) { recordLogData(INFO, "Video Start Time Reached. Starting Video Recording."); rpi.setRecording(true); } - if (time > currentCmdData.MinutesUntilDataRecording) + if (time > currentCmdData.MinutesUntilDataRecording && !computer.getRecordOwnFlightData()) { recordLogData(INFO, "Data Recording Time Reached. Starting Data Recording."); computer.setRecordOwnFlightData(true); From 2bba3bbdf6d2a0769672d5f3461868f790fb55d9 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 23:11:56 -0400 Subject: [PATCH 24/41] Working Version From Laptop --- .../src/GroundStationReceiver/main.cpp | 11 ++++------- .../src/Radio/APRS/APRSCmdMsg.cpp | 7 ++++--- .../Teensy-Based Avionics/src/Radio/RFM69HCW.cpp | 13 ++++++++++--- 3 files changed, 18 insertions(+), 13 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index 7006ded4..cb8d8fa2 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -4,7 +4,7 @@ #include "../Radio/RFM69HCW.h" #include "../Radio/APRS/APRSCmdMsg.h" -APRSHeader header; +APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '/', 'o'}; APRSTelemMsg msg(header); APRSCmdMsg cmd(header); RadioSettings settings = {915.0, 0x02, 0x01, &hardware_spi, 10, 31, 32}; @@ -36,18 +36,15 @@ void loop() aprsToSerial::encodeAPRSForSerial(msg, buffer, 255, radio.RSSI()); Serial.println(buffer); } - if(counter % 100 == 0) + if(counter % 50 == 0) { - radio.enqueueSend(&msg); + radio.enqueueSend(&cmd); } - if(counter % 500 == 0) + if(counter % 190 == 0) { cmd.data.Launch = !cmd.data.Launch; radio.enqueueSend(&cmd); } - counter++; char *b = (char *)cmd.getArr(); - b[cmd.length()] = '\0'; - printf("Cmd: %s\n", b); } } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp index 44bc21c4..cfa35999 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp @@ -2,12 +2,13 @@ void APRSCmdMsg::encodeData(int cursor) { - snprintf((char *)string[cursor], RADIO_MESSAGE_BUFFER_SIZE - cursor, - ":%-09s:PWR:%d VID:%d DAT:%d L:%d", header.CALLSIGN, data.MinutesUntilPowerOn, data.MinutesUntilVideoStart, data.MinutesUntilDataRecording, data.Launch); + snprintf((char *)&string[cursor], RADIO_MESSAGE_BUFFER_SIZE - cursor, + ":%-9s:PWR:%d VID:%d DAT:%d L:%d", header.CALLSIGN, data.MinutesUntilPowerOn, data.MinutesUntilVideoStart, data.MinutesUntilDataRecording, data.Launch); + len = strlen((char *)string); } void APRSCmdMsg::decodeData(int cursor) { - sscanf((char *)string[cursor], ":%*9s:PWR:%d VID:%d DAT:%d L:%d", &data.MinutesUntilPowerOn, &data.MinutesUntilVideoStart, &data.MinutesUntilDataRecording, &data.Launch); + sscanf((char *)&string[cursor], ":%*9s:PWR:%d VID:%d DAT:%d L:%d", &data.MinutesUntilPowerOn, &data.MinutesUntilVideoStart, &data.MinutesUntilDataRecording, &data.Launch); } APRSCmdMsg::APRSCmdMsg(APRSHeader &header) : APRSMsgBase(header) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index ab0d4ace..f6d7612f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -86,7 +86,11 @@ bool RFM69HCW::tx(const uint8_t *message, int len, int packetNum, bool lastPacke radio.setHeaderId(packetNum); radio.setHeaderFlags(lastPacket ? 0 : RADIO_FLAG_MORE_DATA); - + char msg[len + 1]; + for (int i = 0; i < len; i++) + msg[i] = message[i]; + msg[len] = '\0'; + printf("tx: %s\n", msg); return radio.send((uint8_t *)message, len); } @@ -118,6 +122,7 @@ Enqueue a message into the buffer */ bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) { + printf("enqueueSend2\n"); // fill up the buffer with the message. buffer is a circular queue. int originalTail = sendBuffer.tail; sendBuffer.data[sendBuffer.tail] = len; // store the length of the message @@ -134,6 +139,7 @@ bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) sendBuffer.data[sendBuffer.tail] = message[i]; inc(sendBuffer.tail); } + printf("len: %d\n", len); return true; } @@ -153,8 +159,10 @@ Encode the message and enqueue it in the buffer */ bool RFM69HCW::enqueueSend(RadioMessage *message) { + printf("enqueueSend\n"); if (message->encode()) return enqueueSend(message->getArr(), message->length()); + printf("enqueueSend failed\n"); return false; } /* @@ -257,14 +265,13 @@ bool RFM69HCW::update() return false; return true; } - // transmit if (sendBuffer.head == sendBuffer.tail) // buffer is empty, nothing to send { remainingLength = 0; return false; } - + printf("update\n"); int packetNum; if (remainingLength == 0) // start a new message { From 518de14a7bf3fc8dd3978a3b9493bffe90c0e718 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 23:19:16 -0400 Subject: [PATCH 25/41] Fix CSV header --- Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index afe97ac0..1df96151 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -113,11 +113,10 @@ bool State::init() if (!radio->init()) radio = nullptr; } - setCsvHeader(); if (useKF) kfilter = initializeFilter(); numSensors = good; - + setCsvHeader(); return good == tryNumSensors; } From c39d213440813b91651e5bafdf8155c4b36ec0d3 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 23:45:14 -0400 Subject: [PATCH 26/41] Cleanup of State code --- .../lib/RecordData/RecordData.cpp | 3 - .../Code/Teensy-Based Avionics/src/State.cpp | 169 +++++++++--------- 2 files changed, 80 insertions(+), 92 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp index 4fd1761e..fb24046f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp @@ -32,9 +32,6 @@ void recordLogData(double timeStamp, LogType type, const char *data, Dest dest) if (dest == BOTH || dest == TO_USB) { - // if (!Serial){ - // Serial.begin(9600); - // } Serial.print(logPrefix); Serial.println(data); } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index 1df96151..9a4eb924 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -7,15 +7,12 @@ State::State(bool useKalmanFilter, bool stateRecordsOwnFlightData) lastTimeAbsolute = 0; timeAbsolute = millis(); timePreviousStage = 0; - position.x() = 0; - position.y() = 0; - position.z() = 0; - velocity.x() = 0; - velocity.y() = 0; - velocity.z() = 0; - acceleration.x() = 0; - acceleration.y() = 0; - acceleration.z() = 0; + + position = imu::Vector<3>(0, 0, 0); + velocity = imu::Vector<3>(0, 0, 0); + acceleration = imu::Vector<3>(0, 0, 0); + orientation = imu::Quaternion(0, 0, 0, 1); + apogee = 0; stageNumber = 0; baroOldAltitude = 0; @@ -33,12 +30,12 @@ State::State(bool useKalmanFilter, bool stateRecordsOwnFlightData) numSensors = 0; recordOwnFlightData = stateRecordsOwnFlightData; - /// - recordOwnFlightData = false; // For radio testing. Will not record own data unless told to do so. + recordOwnFlightData = false; // For radio testing. Will not record own data unless told to do so or if it detects a launch. /// + for (int i = 0; i < NUM_MAX_SENSORS; i++) sensors[i] = nullptr; @@ -75,36 +72,28 @@ State::~State() bool State::init() { - char *logData = new char[100]; + char logData[100]; int good = 0, tryNumSensors = 0; for (int i = 0; i < NUM_MAX_SENSORS; i++) { - if (sensors[i]) + if (sensors[i]) // not nullptr { tryNumSensors++; if (sensors[i]->initialize()) { good++; - strcpy(logData, sensors[i]->getTypeString()); // This is a lot for just some logging... - strcat(logData, " ["); - strcat(logData, sensors[i]->getName()); - strcat(logData, "] initialized."); + snprintf(logData, 100, "%s [%s] initialized.", sensors[i]->getTypeString(), sensors[i]->getName()); recordLogData(INFO, logData); } else { - strcpy(logData, sensors[i]->getTypeString()); - strcat(logData, " ["); - strcat(logData, sensors[i]->getName()); - strcat(logData, "] failed to initialize."); + snprintf(logData, 100, "%s [%s] failed to initialize.", sensors[i]->getTypeString(), sensors[i]->getName()); recordLogData(ERROR, logData); } } else { - strcpy(logData, "Sensor ["); - strcat(logData, SENSOR_NAMES[i]); - strcat(logData, "] was not added via addSensor()."); + snprintf(logData, 100, "Sensor [%s] was not added via addSensor().", SENSOR_NAMES[i]); recordLogData(ERROR, logData); } } @@ -148,10 +137,10 @@ void State::updateState(double newTimeAbsolute) return; lastTimeAbsolute = timeAbsolute; - if (newTimeAbsolute != -1) - timeAbsolute = newTimeAbsolute; - else + if (newTimeAbsolute == -1) timeAbsolute = millis() / 1000.0; + else + timeAbsolute = newTimeAbsolute; updateSensors(); if (kfilter && sensorOK(gps) && gps->getHasFirstFix() && stageNumber > 0) @@ -192,7 +181,7 @@ void State::updateState(double newTimeAbsolute) if (sensorOK(baro)) { - baroVelocity = (baro->getRelAltM() - baroOldAltitude) / (millis() / 1000.0 - timeAbsolute); + baroVelocity = (baro->getRelAltM() - baroOldAltitude) / (timeAbsolute - lastTimeAbsolute); baroOldAltitude = baro->getRelAltM(); } } @@ -206,9 +195,9 @@ void State::updateState(double newTimeAbsolute) } if (sensorOK(baro)) { - velocity.z() = (baro->getRelAltM() - baroOldAltitude) / (millis() / 1000.0 - lastTimeAbsolute); + velocity.z() = (baro->getRelAltM() - baroOldAltitude) / (timeAbsolute - lastTimeAbsolute); position.z() = baro->getRelAltM(); - baroVelocity = (baro->getRelAltM() - baroOldAltitude) / (millis() / 1000.0 - lastTimeAbsolute); + baroVelocity = (baro->getRelAltM() - baroOldAltitude) / (timeAbsolute - lastTimeAbsolute); baroOldAltitude = baro->getRelAltM(); } if (sensorOK(imu)) @@ -218,26 +207,24 @@ void State::updateState(double newTimeAbsolute) } } - if (stageNumber == 0) - timeSinceLaunch = 0; - else - timeSinceLaunch = timeAbsolute - timeOfLaunch; - determineAccelerationMagnitude(); determineStage(); + if (stageNumber > 0) + { timeSincePreviousStage = timeAbsolute - timePreviousStage; + timeSinceLaunch = timeAbsolute - timeOfLaunch; + } + if (stageNumber < 3) apogee = position.z(); // backup case to dump data (25 minutes) - if (stageNumber > 0 && timeSinceLaunch > 1500 && stageNumber < 5) + if (stageNumber > 0 && timeSinceLaunch > 25 * 60 && stageNumber < 5) { stageNumber = 5; setRecordMode(GROUND); - digitalWrite(LED_BUILTIN, HIGH); - delay(500); - digitalWrite(LED_BUILTIN, LOW); + bb.aonoff(LED, 5000); recordLogData(WARNING, "Dumping data after 25 minutes."); } setDataString(); @@ -245,6 +232,8 @@ void State::updateState(double newTimeAbsolute) recordFlightData(dataString); } +#pragma region CSV Operations + void State::setCsvHeader() { char csvHeaderStart[] = "Time,Stage,PX,PY,PZ,VX,VY,VZ,AX,AY,AZ,"; @@ -284,12 +273,54 @@ char *State::getStateString() char *State::getDataString() { return dataString; } char *State::getCsvHeader() { return csvHeader; } -int State::getStageNum() { return stageNumber; } -#pragma region Getters and Setters for Sensors +void State::setCsvString(char *dest, const char *start, int startSize, bool header) +{ + int numCategories = numSensors + 1; + const char **str = new const char *[numCategories]; + str[0] = start; + int cursor = 1; + delete[] dest; + //---Determine required size for string + int size = startSize + 1; // includes '\0' at end of string for the end of dataString to use + for (int i = 0; i < NUM_MAX_SENSORS; i++) + { + if (sensorOK(sensors[i])) + { + str[cursor] = header ? sensors[i]->getCsvHeader() : sensors[i]->getDataString(); + size += strlen(str[cursor++]); + } + } + dest = new char[size]; + if (header) + csvHeader = dest; + else + dataString = dest; + //---Fill data String + int j = 0; + for (int i = 0; i < numCategories; i++) + { + for (int k = 0; str[i][k] != '\0'; j++, k++) + { // append all the data strings onto the main string + + dest[j] = str[i][k]; + } + if (i >= 1 && !header) + { + delete[] str[i]; // delete all the heap arrays. + } + } + delete[] str; + dest[j - 1] = '\0'; // all strings have ',' at end so this gets rid of that and terminates it a character early. +} + +#pragma endregion // CSV Operations + +#pragma region Getters and Setters void State::setRecordOwnFlightData(bool value) { recordOwnFlightData = value; } bool State::getRecordOwnFlightData() { return recordOwnFlightData; } +int State::getStageNum() { return stageNumber; } void State::setRadio(Radio *r) { radio = r; } Radio *State::getRadio() { return radio; } @@ -323,7 +354,8 @@ Sensor *State::getSensor(SensorType type, int sensorNum) Barometer *State::getBaro() { return baro; } GPS *State::getGPS() { return gps; } IMU *State::getIMU() { return imu; } -#pragma endregion + +#pragma endregion // Getters and Setters #pragma region Helper Functions @@ -367,18 +399,18 @@ bool State::applySensorType(int i, int sensorNum) void State::determineAccelerationMagnitude() { - accelerationMagnitude = sqrt((acceleration.x() * acceleration.x()) + (acceleration.y() * acceleration.y()) + (acceleration.z() * acceleration.z())); + accelerationMagnitude = acceleration.magnitude(); } void State::determineStage() { if (stageNumber == 0 && (sensorOK(imu) || sensorOK(baro)) && - (sensorOK(imu) ? abs(imu->getAcceleration().z()) > 25 : true) && + (sensorOK(imu) ? accelerationMagnitude > 25 : true) && (sensorOK(baro) ? baro->getRelAltFt() > 60 : true)) // if we are in preflight AND // we have either the IMU OR the barometer AND - // imu is ok AND the z acceleration is greater than 29 ft/s^2 OR imu is not ok AND + // imu is ok AND the accel Magnitude is greater than 25 ft/s^2 OR imu is not ok AND // barometer is ok AND the relative altitude is greater than 30 ft OR baro is not ok // essentially, if we have either sensor and they meet launch threshold, launch. Otherwise, it will never detect a launch. @@ -386,7 +418,7 @@ void State::determineStage() recordLogData(INFO, "Launch detected."); launch(); } // TODO: Add checks for each sensor being ok and decide what to do if they aren't. - else if (stageNumber == 1 && abs(acceleration.z()) < 10) + else if (stageNumber == 1 && accelerationMagnitude < 10) { bb.aonoff(BUZZER, 200, 2); timePreviousStage = timeAbsolute; @@ -432,8 +464,7 @@ void State::launch() bb.aonoff(BUZZER, 200); setRecordMode(FLIGHT); stageNumber = 1; - timeOfLaunch = timeAbsolute; - timePreviousStage = timeAbsolute; + timeOfLaunch = timePreviousStage = timeAbsolute; timeSinceLaunch = 0; strcpy(launchTimeOfDay, gps->getTimeOfDay()); recordLogData(INFO, "Printing static data."); @@ -448,45 +479,6 @@ void State::launch() } } } -void State::setCsvString(char *dest, const char *start, int startSize, bool header) -{ - int numCategories = numSensors + 1; - const char **str = new const char *[numCategories]; - str[0] = start; - int cursor = 1; - delete[] dest; - //---Determine required size for string - int size = startSize + 1; // includes '\0' at end of string for the end of dataString to use - for (int i = 0; i < NUM_MAX_SENSORS; i++) - { - if (sensorOK(sensors[i])) - { - str[cursor] = header ? sensors[i]->getCsvHeader() : sensors[i]->getDataString(); - size += strlen(str[cursor++]); - } - } - dest = new char[size]; - if (header) - csvHeader = dest; - else - dataString = dest; - //---Fill data String - int j = 0; - for (int i = 0; i < numCategories; i++) - { - for (int k = 0; str[i][k] != '\0'; j++, k++) - { // append all the data strings onto the main string - - dest[j] = str[i][k]; - } - if (i >= 1 && !header) - { - delete[] str[i]; // delete all the heap arrays. - } - } - delete[] str; - dest[j - 1] = '\0'; // all strings have ',' at end so this gets rid of that and terminates it a character early. -} bool State::sensorOK(const Sensor *sensor) { @@ -495,8 +487,6 @@ bool State::sensorOK(const Sensor *sensor) return false; } -#pragma endregion - void State::fillAPRSData(APRSTelemData &data) { data.lat = sensorOK(gps) ? gps->getPos().x() : 0; @@ -513,6 +503,7 @@ void State::fillAPRSData(APRSTelemData &data) data.orientation[i] += 360; } } +#pragma endregion // Helper Functions extern unsigned long _heap_start; extern unsigned long _heap_end; From f87ea92a40bfee8f170db0d524d67824b2a44492 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Thu, 16 May 2024 23:54:49 -0400 Subject: [PATCH 27/41] GroundStation code cleaned up --- .../GroundStationReceiver/EncodeAPRSForSerial.h | 17 +++++++++++++---- .../src/GroundStationReceiver/main.cpp | 13 +++++++------ .../src/Radio/APRS/APRSMsgBase.h | 4 +--- .../src/Radio/APRS/APRSTelemMsg.h | 4 +++- 4 files changed, 24 insertions(+), 14 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index 45fd3de7..5b1ed2fd 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -10,7 +10,7 @@ namespace aprsToSerial void encodeLatLong(const APRSTelemMsg &msg, char *buffer, size_t buffer_size); void encodeAltitude(const APRSTelemMsg &msg, char *buffer, size_t buffer_size); - + void encodeFlags(const APRSTelemMsg &msg, char *buffer, size_t buffer_size); /* * Encodes an APRS message into a string for serial transmission * \param msg The APRS message to encode @@ -27,10 +27,11 @@ namespace aprsToSerial encodeLatLong(msg, latLong, 20); char altitude[10]; encodeAltitude(msg, altitude, 10); - + char flags[5]; + encodeFlags(msg, flags, 5); char suffix[10] = "e\r\n"; - // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx,RSSI:RSSI\r\ne\r\n - snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), RSSI, suffix); + // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx/fff,RSSI:RSSI\r\ne\r\n + snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d/%s,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), flags, RSSI, suffix); } void encodeLatLong(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) @@ -57,6 +58,14 @@ namespace aprsToSerial else snprintf(buffer, buffer_size, "A=%06d", alt); } + + void encodeFlags(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) + { + char f1 = (msg.data.statusFlags & PI_ON) ? '1' : '0'; + char f2 = (msg.data.statusFlags & PI_VIDEO) ? '1' : '0'; + char f3 = (msg.data.statusFlags & RECORDING_DATA) ? '1' : '0'; + snprintf(buffer, buffer_size, "%c%c%c", f1, f2, f3); + } } #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index cb8d8fa2..e6357473 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -13,11 +13,13 @@ RFM69HCW radio(&settings); void setup() { - delay(2000); + delay(2000); // Delay to allow the serial monitor to connect if (!radio.init()) Serial.println("Radio failed to initialize"); else Serial.println("Radio initialized"); + + // Test Case for Demo Purposes cmd.data.MinutesUntilPowerOn = 0; cmd.data.MinutesUntilDataRecording = 1; cmd.data.MinutesUntilVideoStart = 2; @@ -36,15 +38,14 @@ void loop() aprsToSerial::encodeAPRSForSerial(msg, buffer, 255, radio.RSSI()); Serial.println(buffer); } - if(counter % 50 == 0) - { + if(counter % 50 == 0) // Send a command every 50x a message is received (or every 25 seconds) radio.enqueueSend(&cmd); - } - if(counter % 190 == 0) + + if(counter == 190) // Send a command after 190x a message is received (or after 95 seconds) to launch the rocket { cmd.data.Launch = !cmd.data.Launch; radio.enqueueSend(&cmd); } - char *b = (char *)cmd.getArr(); + counter++; } } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h index f54d63c4..556d82d0 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h @@ -16,9 +16,7 @@ #include "../Radio.h" #include -const uint8_t PI_ON = 0b00000001; // Pi is on -const uint8_t PI_VIDEO = 0b00000010; // Pi is recording video -const uint8_t RECORDING_DATA = 0b00000100; // FC is recording data + /* APRS Configuration diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h index 96461000..49e88103 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h @@ -3,7 +3,9 @@ #include "APRSMsgBase.h" - +const uint8_t PI_ON = 0b00000001; // Pi is on +const uint8_t PI_VIDEO = 0b00000010; // Pi is recording video +const uint8_t RECORDING_DATA = 0b00000100; // FC is recording data struct APRSTelemData { From 95aa16b299fe2a49d0359b8efc38f46eebee6ac1 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Fri, 17 May 2024 00:56:50 -0400 Subject: [PATCH 28/41] Code cleanup and documentation --- .../EncodeAPRSForSerial.h | 42 ++++++- .../Code/Teensy-Based Avionics/src/Pi.cpp | 19 +-- .../src/Radio/APRS/APRSCmdMsg.cpp | 31 +++-- .../src/Radio/APRS/APRSCmdMsg.h | 14 +-- .../src/Radio/APRS/APRSMsgBase.cpp | 27 ++-- .../src/Radio/APRS/APRSMsgBase.h | 39 ++---- .../src/Radio/APRS/APRSTelemMsg.cpp | 17 +-- .../src/Radio/APRS/APRSTelemMsg.h | 14 +-- .../src/Radio/RFM69HCW.cpp | 119 +++++++++--------- .../src/Radio/RFM69HCW.h | 14 +-- .../Teensy-Based Avionics/src/Radio/Radio.h | 41 +++--- .../src/Radio/RadioMessage.cpp | 6 +- .../src/Radio/RadioMessage.h | 9 +- 13 files changed, 203 insertions(+), 189 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index 5b1ed2fd..debcd07d 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -21,17 +21,41 @@ namespace aprsToSerial void encodeAPRSForSerial(const APRSTelemMsg &msg, char *buffer, size_t buffer_size, int RSSI) { char prefix[8] = "s\r\n"; + char header[100]; - snprintf(header, 100, "Source:%s,Destination:%s,Path:%s,Type:%s,", msg.header.CALLSIGN, msg.header.TOCALL, msg.header.PATH, "Position Without Timestamp"); + snprintf(header, 100, + "Source:%s,Destination:%s,Path:%s,Type:%s,", + msg.header.CALLSIGN, + msg.header.TOCALL, + msg.header.PATH, + "Position Without Timestamp"); + char latLong[20]; encodeLatLong(msg, latLong, 20); + char altitude[10]; encodeAltitude(msg, altitude, 10); + char flags[5]; encodeFlags(msg, flags, 5); + char suffix[10] = "e\r\n"; // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx/fff,RSSI:RSSI\r\ne\r\n - snprintf(buffer, buffer_size, "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d/%s,RSSI:%03d\r\n%s", prefix, header, latLong, SYMBOL, (int)msg.data.hdg, (int)msg.data.spd, altitude, msg.data.stage, (int)msg.data.orientation.z(), (int)msg.data.orientation.y(), (int)msg.data.orientation.x(), flags, RSSI, suffix); + snprintf(buffer, buffer_size, + "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d/%s,RSSI:%03d\r\n%s", + prefix, + header, + latLong, + SYMBOL, + (int)msg.data.hdg, + (int)msg.data.spd, + altitude, msg.data.stage, + (int)msg.data.orientation.z(), + (int)msg.data.orientation.y(), + (int)msg.data.orientation.x(), + flags, + RSSI, + suffix); } void encodeLatLong(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) @@ -45,20 +69,28 @@ namespace aprsToSerial char long_dir = (msg.data.lng < 0) ? 'W' : 'E'; // format: DDMM.MM[NS][OVERLAY]DDDMM.MM[WE] - snprintf(buffer, buffer_size, "%02d%05.02f%c%c%03d%05.02f%c", lat_deg, lat_min, lat_dir, OVERLAY, long_deg, long_min, long_dir); - + snprintf(buffer, buffer_size, + "%02d%05.02f%c%c%03d%05.02f%c", + lat_deg, + lat_min, + lat_dir, + OVERLAY, + long_deg, + long_min, + long_dir); } void encodeAltitude(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) { // format: A=DDDDDD int alt = (int)msg.data.alt; - if(alt < 0) + if (alt < 0) snprintf(buffer, buffer_size, "A=%07d", alt); else snprintf(buffer, buffer_size, "A=%06d", alt); } + // print status flags as plain text void encodeFlags(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) { char f1 = (msg.data.statusFlags & PI_ON) ? '1' : '0'; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp index da1e19e7..19b8258b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Pi.cpp @@ -4,11 +4,14 @@ Pi::Pi(int pinControl, int pinVideo) { this->pinControl = pinControl; this->pinVideo = pinVideo; - pinMode(this->pinControl, OUTPUT); - pinMode(this->pinVideo, OUTPUT); - digitalWrite(this->pinVideo, HIGH); // Set video pin to high (off) by default - this->on = false; - this->recording = false; + + pinMode(pinControl, OUTPUT); + pinMode(pinVideo, OUTPUT); + + digitalWrite(pinVideo, HIGH); // Set video pin to high (off) by default + + on = false; + recording = false; } void Pi::setOn(bool on) @@ -22,16 +25,16 @@ void Pi::setRecording(bool recording) if(this->recording == recording) return; // If the recording state is the same, do nothing bb.aonoff(BUZZER, 100, 3); // Buzz 3 times (100ms on, 100ms off) - digitalWrite(this->pinVideo, recording ? LOW : HIGH); + digitalWrite(pinVideo, recording ? LOW : HIGH); this->recording = recording; } bool Pi::isOn() { - return this->on; + return on; } bool Pi::isRecording() { - return this->recording; + return recording; } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp index 15c55118..b8f87642 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.cpp @@ -1,20 +1,31 @@ #include "APRSCmdMsg.h" +APRSCmdMsg::APRSCmdMsg(APRSHeader header) : APRSMsgBase(header) +{ + data.MinutesUntilPowerOn = -1; + data.MinutesUntilVideoStart = -1; + data.MinutesUntilDataRecording = -1; // -1 so that we know if the value was set or not + data.Launch = false; +} + void APRSCmdMsg::encodeData(int cursor) { snprintf((char *)&string[cursor], RADIO_MESSAGE_BUFFER_SIZE - cursor, - ":%-9s:PWR:%d VID:%d DAT:%d L:%d", header.CALLSIGN, data.MinutesUntilPowerOn, data.MinutesUntilVideoStart, data.MinutesUntilDataRecording, data.Launch); + ":%-9s:PWR:%d VID:%d DAT:%d L:%d", + header.CALLSIGN, + data.MinutesUntilPowerOn, + data.MinutesUntilVideoStart, + data.MinutesUntilDataRecording, + data.Launch); len = strlen((char *)string); } -void APRSCmdMsg::decodeData(int cursor) -{ - sscanf((char *)&string[cursor + 11], "PWR:%d VID:%d DAT:%d L:%d", &data.MinutesUntilPowerOn, &data.MinutesUntilVideoStart, &data.MinutesUntilDataRecording, &data.Launch); -} -APRSCmdMsg::APRSCmdMsg(APRSHeader &header) : APRSMsgBase(header) +void APRSCmdMsg::decodeData(int cursor) { - data.MinutesUntilPowerOn = -1; - data.MinutesUntilVideoStart = -1; - data.MinutesUntilDataRecording = -1; - data.Launch = false; + sscanf((char *)&string[cursor + 11], // ignore the :TO_FIELD: part + "PWR:%d VID:%d DAT:%d L:%d", + &data.MinutesUntilPowerOn, + &data.MinutesUntilVideoStart, + &data.MinutesUntilDataRecording, + &data.Launch); } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h index 169e05b0..0aacf074 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSCmdMsg.h @@ -3,23 +3,23 @@ #include "APRSMsgBase.h" -struct APRSCmdData +struct APRSCmdData final { int MinutesUntilPowerOn; // Minutes until the Pi turns on - 0 means turn on now int MinutesUntilVideoStart; // Minutes until the Pi starts recording video - 0 means start now int MinutesUntilDataRecording; // Minutes until the FC starts recording data - 0 means start now - bool Launch; // Send the launch command to the FC - 0 means don't send + bool Launch; // Send the launch command to the FC - 0 means don't send }; -class APRSCmdMsg : public APRSMsgBase +class APRSCmdMsg final : public APRSMsgBase { public: + APRSCmdMsg(APRSHeader header); APRSCmdData data; - APRSCmdMsg(APRSHeader &header); protected: - virtual void decodeData(int cursor) override; - virtual void encodeData(int cursor) override; -}; + void decodeData(int cursor) override; + void encodeData(int cursor) override; +} ; #endif // APRS_CMD_MSG_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp index cc68926d..e5cfa9a2 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.cpp @@ -1,8 +1,7 @@ #include "APRSMsgBase.h" -#define MAX_ALLOWED_MSG_LEN 255 /* max length of 1 message supported by radio buffer */ -APRSMsgBase::APRSMsgBase(APRSHeader &header) +APRSMsgBase::APRSMsgBase(APRSHeader header) { this->header = header; } @@ -28,20 +27,20 @@ int APRSMsgBase::encodeHeader() { // format: CALLSIGN>TOCALL,PATH: int cursor = 0; + for (int i = 0; header.CALLSIGN[i] && i < 8; i++, cursor++) - { string[cursor] = header.CALLSIGN[i]; - } + string[cursor++] = '>'; + for (int i = 0; header.TOCALL[i] && i < 8; i++, cursor++) - { string[cursor] = header.TOCALL[i]; - } + string[cursor++] = ','; + for (int i = 0; header.PATH[i] && i < 10; i++, cursor++) - { string[cursor] = header.PATH[i]; - } + string[cursor++] = ':'; // end of header return cursor; } @@ -50,23 +49,23 @@ int APRSMsgBase::decodeHeader() { // format: CALLSIGN>TOCALL,PATH: int cursor = 0; + for (int i = 0; string[cursor] != '>'; i++, cursor++) - { header.CALLSIGN[i] = string[cursor]; - } header.CALLSIGN[cursor] = '\0'; + cursor++; // skip '>' + for (int i = 0; string[cursor] != ','; i++, cursor++) - { header.TOCALL[i] = string[cursor]; - } header.TOCALL[cursor] = '\0'; + cursor++; // skip ',' + for (int i = 0; string[cursor] != ':'; i++, cursor++) - { header.PATH[i] = string[cursor]; - } header.PATH[cursor] = '\0'; + cursor++; // skip ':' return cursor; } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h index 556d82d0..a5e7d0f0 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSMsgBase.h @@ -1,5 +1,5 @@ -#ifndef APRSMSG_H -#define APRSMSG_H +#ifndef APRS_MSG_BASE_H +#define APRS_MSG_BASE_H #if defined(ARDUINO) #include @@ -13,20 +13,9 @@ // TODO #endif -#include "../Radio.h" -#include +#include "../RadioMessage.h" - - -/* -APRS Configuration -- CALLSIGN -- TOCALL -- PATH -- SYMBOL -- OVERLAY -*/ -struct APRSHeader +struct APRSHeader final { char CALLSIGN[8]; char TOCALL[8]; @@ -35,36 +24,24 @@ struct APRSHeader char OVERLAY; }; -/* -APRS Telemetry Data -- lat -- lng -- alt -- spd -- hdg -- stage -- orientation -*/ - - class APRSMsgBase : public RadioMessage { public: - APRSMsgBase(APRSHeader &header); + APRSMsgBase(APRSHeader header); virtual ~APRSMsgBase(){}; virtual bool decode() override; virtual bool encode() override; APRSHeader header; + protected: - virtual int encodeHeader(); - virtual int decodeHeader(); + int encodeHeader(); + int decodeHeader(); virtual void encodeData(int cursor) = 0; virtual void decodeData(int cursor) = 0; void encodeBase91(uint8_t *message, int &cursor, int value, int precision); void decodeBase91(const uint8_t *message, int &cursor, double &value, int precision); -private: }; #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp index 5e864c2e..6721a11e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.cpp @@ -1,6 +1,6 @@ #include "APRSTelemMsg.h" -APRSTelemMsg::APRSTelemMsg(APRSHeader &header) : APRSMsgBase(header) +APRSTelemMsg::APRSTelemMsg(APRSHeader header) : APRSMsgBase(header) { data.lat = 0; data.lng = 0; @@ -12,16 +12,13 @@ APRSTelemMsg::APRSTelemMsg(APRSHeader &header) : APRSMsgBase(header) data.statusFlags = 0; } -#pragma region Encode Helpers - void APRSTelemMsg::encodeData(int cursor) { /* Small Aircraft symbol ( /' ) probably better than Jogger symbol ( /[ ) lol. I'm going to use the Overlayed Aircraft symbol ( \^ ) for now, with the overlay of 'M' for UMD ( M^ ). Uses base91 encoding to compress message as much as possible. APRS messages are apparently supposed to be only 256 bytes. - - takes the regular format of !DDMM.hhN/DDDMM.hhW^ALTSPD/HDG SSOrientationF + Takes the regular format of !DDMM.hhN/DDDMM.hhW^ALTSPD/HDG SSOrientationF which expands to !(lat)/(lng)^altspd/hdg (stage #)(orientation)(status flags) @@ -29,7 +26,7 @@ void APRSTelemMsg::encodeData(int cursor) which expands to /(lat)(lng)^ (course)(speed)(altitude)(stage)(orientation [as euler angles])(status flags) - specifically does not use the csT compressed format because we don't need T and want better accuracy on course angle. + Specifically does not use the csT compressed format because we don't need T and want better accuracy on course angle. for more information on APRS, see http://www.aprs.org/doc/APRS101.PDF @@ -59,12 +56,10 @@ void APRSTelemMsg::encodeData(int cursor) len = cursor; } -#pragma endregion - -#pragma region Decode Helpers - void APRSTelemMsg::decodeData(int cursor) { + // format is /YYYYXXXX^ ccssaasoooooof + // lat and lng cursor++; // skip '!' cursor++; // skip overlay @@ -93,5 +88,3 @@ void APRSTelemMsg::decodeData(int cursor) data.orientation.z() /= ORIENTATION_SCALE; data.statusFlags = string[cursor++] - 33; } - -#pragma endregion diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h index 49e88103..2558ee0e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/APRS/APRSTelemMsg.h @@ -2,12 +2,13 @@ #define APRS_TELEM_MSG_H #include "APRSMsgBase.h" +#include const uint8_t PI_ON = 0b00000001; // Pi is on const uint8_t PI_VIDEO = 0b00000010; // Pi is recording video const uint8_t RECORDING_DATA = 0b00000100; // FC is recording data -struct APRSTelemData +struct APRSTelemData final { double lat; double lng; @@ -19,17 +20,16 @@ struct APRSTelemData uint8_t statusFlags; }; -class APRSTelemMsg : public APRSMsgBase +class APRSTelemMsg final : public APRSMsgBase { public: + APRSTelemMsg(APRSHeader header); APRSTelemData data; - APRSTelemMsg(APRSHeader &header); -protected: - virtual void decodeData(int cursor) override; - virtual void encodeData(int cursor) override; private: - void encodeStatus(uint8_t *string, int &cursor); + void decodeData(int cursor) override; + void encodeData(int cursor) override; + // Scale factors for encoding/decoding ignoring lat/long const double ALT_SCALE = (pow(91, 2) / 16000.0); // (91^2/16000) scale to fit in 2 base91 characters const double SPD_SCALE = (pow(91, 2) / 1000.0); // (91^2/1000) scale to fit in 2 base91 characters diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index 4704bf7a..3110bd96 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -17,8 +17,7 @@ Constructor */ RFM69HCW::RFM69HCW(const RadioSettings *s) : radio(s->cs, s->irq, *s->spi) { - - this->settings = *s; + settings = *s; } /* @@ -74,7 +73,7 @@ bool RFM69HCW::init() Most basic transmission method, simply transmits the string without modification \param message is the message to be transmitted, must be shorter than RH_RF69_MAX_MESSAGE_LEN \param len optional length of message, required if message is not a null terminated string - \param packetNum optional packet number of the message + \param packetNum optional packet number of the message, given to the receiver to reassemble the message \param lastPacket optional is this the last packet of a larger message or the only packet? \return `true` if the message was sent, `false` otherwise */ @@ -86,12 +85,8 @@ bool RFM69HCW::tx(const uint8_t *message, int len, int packetNum, bool lastPacke radio.setHeaderId(packetNum); radio.setHeaderFlags(lastPacket ? 0 : RADIO_FLAG_MORE_DATA); - char msg[len + 1]; - for (int i = 0; i < len; i++) - msg[i] = message[i]; - msg[len] = '\0'; - printf("tx: %s\n", msg); - return radio.send((uint8_t *)message, len); + + return radio.send(message, len); } /* @@ -122,24 +117,22 @@ Enqueue a message into the buffer */ bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) { - printf("enqueueSend2\n"); + // determine if the message is too long to fit without the tail running into the head + if (sendBuffer.tail >= sendBuffer.head) + { + if (TRANSCEIVER_MESSAGE_BUFFER_SIZE - sendBuffer.tail + sendBuffer.head < len + 1) // +1 for the length byte + return false; + } + else if (sendBuffer.head - sendBuffer.tail < len + 1) // +1 for the length byte + return false; + // fill up the buffer with the message. buffer is a circular queue. int originalTail = sendBuffer.tail; - sendBuffer.data[sendBuffer.tail] = len; // store the length of the message + sendBuffer.data[sendBuffer.tail] = len; // store the length of the message in the first byte inc(sendBuffer.tail); - for (int i = 0; i < len; i++) // same algorithm as copyToBuffer but with a length check - { - if (sendBuffer.tail == sendBuffer.head) // buffer is full - { - sendBuffer.tail = originalTail; // reset the tail (no message was added) - return false; - } + copyToBuffer(sendBuffer, message, len); - sendBuffer.data[sendBuffer.tail] = message[i]; - inc(sendBuffer.tail); - } - printf("len: %d\n", len); return true; } @@ -152,6 +145,7 @@ bool RFM69HCW::enqueueSend(const char *message) { return enqueueSend((uint8_t *)message, strlen(message)); } + /* Encode the message and enqueue it in the buffer \param message the RadioMessage to encode and enqueue @@ -159,12 +153,12 @@ Encode the message and enqueue it in the buffer */ bool RFM69HCW::enqueueSend(RadioMessage *message) { - printf("enqueueSend\n"); if (message->encode()) return enqueueSend(message->getArr(), message->length()); - printf("enqueueSend failed\n"); + return false; } + /* Dequeue a message from the buffer and decode it into a uint8_t[]. \param message the uint8_t[] to copy the recieved message into @@ -196,7 +190,7 @@ bool RFM69HCW::dequeueReceive(char *message) // Empty the buffer up to the first null terminator inc(recvBuffer.head); // skip the length byte, should be null terminated int i = 0; - for (; recvBuffer.data[recvBuffer.head] != '\0' && recvBuffer.head != recvBuffer.tail; i++) + for (; recvBuffer.data[recvBuffer.head] != '\0' && recvBuffer.head != recvBuffer.tail - 1; i++) // same algo as copyFromBuffer but uses a null terminator { message[i] = recvBuffer.data[recvBuffer.head]; inc(recvBuffer.head); @@ -218,6 +212,7 @@ bool RFM69HCW::dequeueReceive(RadioMessage *message) uint8_t len = recvBuffer.data[recvBuffer.head]; uint8_t *msg = new uint8_t[len]; + bool worked = false; if (dequeueReceive(msg)) // get the message from the buffer if (message->setArr(msg, len)) // send the message to the RadioMessage @@ -233,10 +228,9 @@ bool RFM69HCW::dequeueReceive(RadioMessage *message) /* Update function - checks if the radio is busy - - if the radio is a transmitter, sends (partially sends, if it's too long) the next queued message in the buffer - - if the radio is a receiver, receives the next message and stores it in the buffer - \return TRANSMITTER: `true` if the message was sent, `false` if the message was not sent. - \return RECIEVER: `true` if the message was received in full, `false` if nothing received or message is incomplete. + - if the radio has received a message, it will store the message in the buffer, Will not transmit while a full message has been only partially received. + - if not receiving and the radio has a message to send, it will send a part of the message up to the max length the radio can handle. + \return `true` if the radio has received a full message, `false` otherwise (always false for transmiting) */ bool RFM69HCW::update() { @@ -246,23 +240,28 @@ bool RFM69HCW::update() return false; uint8_t rcvLen = RH_RF69_MAX_MESSAGE_LEN; - uint8_t rcvBuf[RH_RF69_MAX_MESSAGE_LEN]; + uint8_t rcvBuf[rcvLen]; if (rx(rcvBuf, &rcvLen)) { - // store the message in the buffer - if (radio.headerId() == 0) // start of a new message + // start of a new message + if (radio.headerId() == 0) { orignalBufferTail = recvBuffer.tail; recvBuffer.data[recvBuffer.tail] = rcvLen; // store the length of the message inc(recvBuffer.tail); } - else // continuing message + // continuing message + else recvBuffer.data[orignalBufferTail] += rcvLen; // update the total length of the message + // store the message in the buffer copyToBuffer(recvBuffer, rcvBuf, rcvLen); - if (radio.headerFlags() & RADIO_FLAG_MORE_DATA) // more data is coming, should not process yet + + // more data is coming, should not process yet. TODO: Add a timeout to prevent infinite loop + if (radio.headerFlags() & RADIO_FLAG_MORE_DATA) return false; + return true; } // transmit @@ -271,13 +270,17 @@ bool RFM69HCW::update() remainingLength = 0; return false; } + int packetNum; - if (remainingLength == 0) // start a new message + + // start a new message + if (remainingLength == 0) { remainingLength = sendBuffer.data[sendBuffer.head]; // get the length of the message from the first byte of the message inc(sendBuffer.head); packetNum = 0; } + // continue the message else packetNum = radio.headerId() + 1; @@ -293,7 +296,7 @@ bool RFM69HCW::update() #pragma region Helpers /* -\return `true` if the radio is currently transmitting or receiving a message +\return `true` if the radio is currently transmitting a message */ bool RFM69HCW::busy() { @@ -310,6 +313,29 @@ int RFM69HCW::RSSI() return rssi; } +void RFM69HCW::copyToBuffer(buffer &buffer, const uint8_t *src, int len) +{ + for (int i = 0; i < len; i++) + { + buffer.data[buffer.tail] = src[i]; + inc(buffer.tail); + } +} + +// pop is true by default. If pop is false, the buffer head will not be moved. +void RFM69HCW::copyFromBuffer(buffer &buffer, uint8_t *dest, int len, bool pop) +{ + int originalHead = buffer.head; + for (int i = 0; i < len; i++) + { + dest[i] = buffer.data[buffer.head]; + inc(buffer.head); + } + + if (!pop) + buffer.head = originalHead; +} + // probably broken // void RFM69HCW::set300KBPSMode() // { @@ -343,25 +369,4 @@ int min(int a, int b) } #endif -void RFM69HCW::copyToBuffer(buffer &buffer, const uint8_t *src, int len) -{ - for (int i = 0; i < len; i++) - { - buffer.data[buffer.tail] = src[i]; - inc(buffer.tail); - } -} -// pop is true by default. If pop is false, the buffer head will not be moved. -void RFM69HCW::copyFromBuffer(buffer &buffer, uint8_t *dest, int len, bool pop) -{ - int originalHead = buffer.head; - for (int i = 0; i < len; i++) - { - dest[i] = buffer.data[buffer.head]; - inc(buffer.head); - } - if (!pop) - buffer.head = originalHead; -} - #pragma endregion diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h index 6c18b84c..d55a2125 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.h @@ -3,7 +3,6 @@ #include "RH_RF69.h" #include "Radio.h" -#include "APRS/APRSMsgBase.h" const int TRANSCEIVER_MESSAGE_BUFFER_SIZE = 512; // length of the buffer underpinning the queue of messages to send or receive. Radio makes 2 buffers this size for sending and receiving. #define RADIO_FLAG_MORE_DATA 0b00000001 // custom flag to indicate more packets are still to be sent @@ -12,21 +11,22 @@ const int TRANSCEIVER_MESSAGE_BUFFER_SIZE = 512; // length of the buffer underpi #define RH_RF69_MAX_MESSAGE_LEN 66 #endif // !RH_RF69_MAX_MESSAGE_LEN -struct buffer +struct buffer final { uint8_t data[TRANSCEIVER_MESSAGE_BUFFER_SIZE]; int head; int tail; }; -class RFM69HCW : public Radio +class RFM69HCW final : public Radio { public: RFM69HCW(const RadioSettings *s); + bool init() override; + bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) override; // designed to be used internally. cannot exceed 66 bytes including headers bool rx(uint8_t *recvbuf, uint8_t *len) override; - bool busy(); bool enqueueSend(RadioMessage *message) override; // designed to be used externally. can exceed 66 bytes. bool enqueueSend(const char *message) override; // designed to be used externally. can exceed 66 bytes. @@ -38,14 +38,13 @@ class RFM69HCW : public Radio int RSSI() override; bool update() override; + bool busy(); - explicit operator bool() const { return initialized; } // increment the specified index, wrapping around if necessary static void inc(int &i) { i = (i + 1) % TRANSCEIVER_MESSAGE_BUFFER_SIZE; } // public during debugging - // stores queue of messages, with the length of the message as the first byte of each. no delimiter. // [6xxxxxx3xxx1x2xx] // Done to allow for messages that are not ascii encoded. @@ -57,10 +56,7 @@ class RFM69HCW : public Radio // all radios should have the same networkID const uint8_t networkID = 1; - int thisAddr; - int toAddr; int rssi; - bool initialized = false; int remainingLength = 0; // how much message is left to send for transmitters int orignalBufferTail = 0; // used to update the length of the message after recieving. diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h index 58d214ae..891da86a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h @@ -14,46 +14,45 @@ #endif #include "RadioMessage.h" -#include "RadioHead.h" -#include "RHGenericSPI.h" -/* -Settings: -- double frequency in Mhz -- RHGenericSPI *spi pointer to radiohead SPI object -- uint8_t cs CS pin -- uint8_t irq IRQ pin -- uint8_t rst RST pin -*/ -struct RadioSettings +#include "RHGenericSPI.h" //PIO doesn't like RadioHead without this + +struct RadioSettings final { - double frequency; - uint8_t thisAddr; - uint8_t toAddr; - RHGenericSPI *spi; - uint8_t cs; - uint8_t irq; - uint8_t rst; - int txPower = 20; + double frequency; // in Mhz + uint8_t thisAddr; // RadioHead address of this device + uint8_t toAddr; // RadioHead address of the device to send to + RHGenericSPI *spi; // RadioHead SPI object + uint8_t cs; // Chip Select pin + uint8_t irq; // Interrupt Request pin + uint8_t rst; // Reset pin + int txPower = 20; // in dBm }; class Radio { public: - virtual ~Radio(){}; // Virtual descructor. Very important + virtual ~Radio(){}; virtual bool init() = 0; + virtual bool tx(const uint8_t *message, int len = -1, int packetNum = 0, bool lastPacket = true) = 0; // designed to be used internally. cannot exceed 66 bytes including headers virtual bool rx(uint8_t *recvbuf, uint8_t *len) = 0; + virtual int RSSI() = 0; + virtual bool enqueueSend(const uint8_t *message, uint8_t len) = 0; virtual bool enqueueSend(const char *message) = 0; virtual bool enqueueSend(RadioMessage *message) = 0; + virtual bool dequeueReceive(RadioMessage *message) = 0; virtual bool dequeueReceive(char *message) = 0; virtual bool dequeueReceive(uint8_t *message) = 0; - virtual bool update() = 0; + + virtual explicit operator bool() const { return initialized; } + virtual bool update() = 0; // should be called in the main loop protected: RadioSettings settings; + bool initialized = false; }; #endif // RADIO_H \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp index 882f1a5b..b4669621 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.cpp @@ -1,6 +1,5 @@ #include "RadioMessage.h" -#include RadioMessage::RadioMessage() { @@ -16,9 +15,8 @@ Copies a source array to the encoded message buffer bool RadioMessage::setArr(const uint8_t *srcArr, int len) { if (len > RADIO_MESSAGE_BUFFER_SIZE) - { return false; - } + memcpy(this->string, srcArr, len); this->len = len; return true; @@ -39,5 +37,5 @@ Returns the length of the encoded message */ int RadioMessage::length() const { - return this->len; + return len; } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h index 39eac2dc..f918c9db 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioMessage.h @@ -1,6 +1,7 @@ #ifndef RADIO_MESSAGE_H #define RADIO_MESSAGE_H +#include #include const int RADIO_MESSAGE_BUFFER_SIZE = 255; // maximum length of an encoded `RadioMessage` in bytes. @@ -10,15 +11,15 @@ class RadioMessage public: RadioMessage(); virtual bool encode() = 0; // use stored variables to encode a message - virtual bool decode() = 0; // use `message` to set stored variables + virtual bool decode() = 0; // use `string` to set stored variables virtual int length() const; // return the length of the message - virtual bool setArr(const uint8_t *srcArr, int len); // set the message to the given array - virtual uint8_t *getArr(); // get the message as an array + virtual bool setArr(const uint8_t *srcArr, int len); // set the string to the given array + virtual uint8_t *getArr(); // get the string as an array virtual ~RadioMessage(){}; protected: uint8_t string[RADIO_MESSAGE_BUFFER_SIZE]; // buffer for the encoded message - uint8_t len; // length of the encoded message + uint8_t len; // length of the encoded message. modified by encode() }; #endif // RADIO_MESSAGE_H \ No newline at end of file From 18563b259b3e84b8b3f037168ac116e0c05c7c9e Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Fri, 17 May 2024 01:04:42 -0400 Subject: [PATCH 29/41] Compile Fixes --- .../23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp | 1 - Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp | 3 ++- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index 3110bd96..810f254f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -127,7 +127,6 @@ bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) return false; // fill up the buffer with the message. buffer is a circular queue. - int originalTail = sendBuffer.tail; sendBuffer.data[sendBuffer.tail] = len; // store the length of the message in the first byte inc(sendBuffer.tail); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index cdccef5a..a69c0bd2 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -38,7 +38,8 @@ static double last = 0; // for better timing than "delay(100)" // BlinkBuzz setup int BUZZER = 33; -int allowedPins[] = {LED_BUILTIN}; +int LED = LED_BUILTIN; +int allowedPins[] = {LED}; BlinkBuzz bb(allowedPins, 1, true); // Free memory debug function From 5b265a67b4664dc9d4ad47d1dcc4fa6cd83e28a6 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Fri, 17 May 2024 01:40:18 -0400 Subject: [PATCH 30/41] Added a RadioHandler to clean up the main file a bit --- .../Teensy-Based Avionics/src/Radio/Radio.h | 2 +- .../src/Radio/RadioHandler.h | 66 ++++++++++++++ .../Code/Teensy-Based Avionics/src/main.cpp | 86 ++++--------------- 3 files changed, 82 insertions(+), 72 deletions(-) create mode 100644 Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h index 891da86a..b7423f8f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/Radio.h @@ -25,7 +25,7 @@ struct RadioSettings final uint8_t cs; // Chip Select pin uint8_t irq; // Interrupt Request pin uint8_t rst; // Reset pin - int txPower = 20; // in dBm + int txPower = 12; // in dBm }; class Radio diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h new file mode 100644 index 00000000..a1b98992 --- /dev/null +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h @@ -0,0 +1,66 @@ +#include "RFM69HCW.h" +#include "APRS/APRSCmdMsg.h" +#include "APRS/APRSTelemMsg.h" + +#include +#include + +#include "../Pi.h" +#include "../State.h" + +namespace radioHandler +{ + void processCmdData(APRSCmdMsg &cmd, APRSCmdData &old, APRSCmdData ¤tCmdData, int time) + { + char log[100]; + if (cmd.data.Launch != old.Launch) + { + snprintf(log, 100, "Launch Command Changed to %d.", cmd.data.Launch); + recordLogData(INFO, log); + currentCmdData.Launch = cmd.data.Launch; + } + if (cmd.data.MinutesUntilPowerOn != old.MinutesUntilPowerOn) + { + snprintf(log, 100, "Power On Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilPowerOn, (int)(currentCmdData.MinutesUntilPowerOn - time) / 60000); + recordLogData(INFO, log); + currentCmdData.MinutesUntilPowerOn = cmd.data.MinutesUntilPowerOn * 60 * 1000 + time; + } + if (cmd.data.MinutesUntilVideoStart != old.MinutesUntilVideoStart) + { + snprintf(log, 100, "Video Start Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilVideoStart, (int)(currentCmdData.MinutesUntilVideoStart - time) / 60000); + recordLogData(INFO, log); + currentCmdData.MinutesUntilVideoStart = cmd.data.MinutesUntilVideoStart * 60 * 1000 + time; + } + if (cmd.data.MinutesUntilDataRecording != old.MinutesUntilDataRecording) + { + snprintf(log, 100, "Data Recording Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilDataRecording, (int)(currentCmdData.MinutesUntilDataRecording - time) / 60000); + recordLogData(INFO, log); + currentCmdData.MinutesUntilDataRecording = cmd.data.MinutesUntilDataRecording * 60 * 1000 + time; + } + } + + void processCurrentCmdData(APRSCmdData ¤tCmdData, State &computer, Pi &rpi, int time) + { + if (currentCmdData.Launch && computer.getStageNum() == 0) + { + recordLogData(INFO, "Launch Command Received. Launching Rocket."); + computer.launch(); + } + + if (time > currentCmdData.MinutesUntilPowerOn && !rpi.isOn()) + { + recordLogData(INFO, "Power On RPI Time Reached. Turning on Raspberry Pi."); + rpi.setOn(true); + } + if (time > currentCmdData.MinutesUntilVideoStart && !rpi.isRecording()) + { + recordLogData(INFO, "Video Start Time Reached. Starting Video Recording."); + rpi.setRecording(true); + } + if (time > currentCmdData.MinutesUntilDataRecording && !computer.getRecordOwnFlightData()) + { + recordLogData(INFO, "Data Recording Time Reached. Starting Data Recording."); + computer.setRecordOwnFlightData(true); + } + } +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index a69c0bd2..02636335 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -1,15 +1,14 @@ #include #include "State.h" + #include "BMP390.h" #include "BNO055.h" #include "MAX_M10S.h" -#include "DS3231.h" -#include "Radio/RFM69HCW.h" -#include "Radio/APRS/APRSCmdMsg.h" -#include "Radio/APRS/APRSTelemMsg.h" + #include "RecordData.h" -#include "BlinkBuzz.h" +#include #include "Pi.h" +#include "Radio/RadioHandler.h" #define BMP_ADDR_PIN 36 #define RPI_PWR 0 @@ -112,41 +111,18 @@ void loop() { double time = millis(); bb.update(); + + // Update the Radio if (radio.update()) // if there is a message to be read { timeOfLastCmd = time; APRSCmdData old = cmd.data; if (radio.dequeueReceive(&cmd)) - { - char log[100]; - if (cmd.data.Launch != old.Launch) - { - snprintf(log, 100, "Launch Command Changed to %d.", cmd.data.Launch); - recordLogData(INFO, log); - currentCmdData.Launch = cmd.data.Launch; - } - if (cmd.data.MinutesUntilPowerOn != old.MinutesUntilPowerOn) - { - snprintf(log, 100, "Power On Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilPowerOn, (int)(currentCmdData.MinutesUntilPowerOn - time) / 60000); - recordLogData(INFO, log); - currentCmdData.MinutesUntilPowerOn = cmd.data.MinutesUntilPowerOn * 60 * 1000 + time; - } - if (cmd.data.MinutesUntilVideoStart != old.MinutesUntilVideoStart) - { - snprintf(log, 100, "Video Start Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilVideoStart, (int)(currentCmdData.MinutesUntilVideoStart - time) / 60000); - recordLogData(INFO, log); - currentCmdData.MinutesUntilVideoStart = cmd.data.MinutesUntilVideoStart * 60 * 1000 + time; - } - if (cmd.data.MinutesUntilDataRecording != old.MinutesUntilDataRecording) - { - snprintf(log, 100, "Data Recording Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilDataRecording, (int)(currentCmdData.MinutesUntilDataRecording - time) / 60000); - recordLogData(INFO, log); - currentCmdData.MinutesUntilDataRecording = cmd.data.MinutesUntilDataRecording * 60 * 1000 + time; - } - } + radioHandler::processCmdData(cmd, old, currentCmdData, time); } - processCurrentCmdData(time); + radioHandler::processCurrentCmdData(currentCmdData, computer, rpi, time); + // Update the state of the rocket if (time - last < 100) return; @@ -154,57 +130,25 @@ void loop() computer.updateState(); // recordLogData(INFO, computer.getStateString(), TO_USB); + // Send Telemetry Data if (time - radioTimer >= 1000) { computer.fillAPRSData(telem.data); - if (rpi.isOn()) - telem.data.statusFlags |= RPI_PWR; - else - telem.data.statusFlags &= ~RPI_PWR; - - if (rpi.isRecording()) - telem.data.statusFlags |= RPI_VIDEO; - else - telem.data.statusFlags &= ~RPI_VIDEO; - - if (computer.getRecordOwnFlightData()) - telem.data.statusFlags |= RECORDING_DATA; - else - telem.data.statusFlags &= ~RECORDING_DATA; + int status = PI_ON * rpi.isOn() + + PI_VIDEO * rpi.isRecording() + + RECORDING_DATA * computer.getRecordOwnFlightData(); + telem.data.statusFlags = status; radio.enqueueSend(&telem); radioTimer = time; } - // RASPBERRY PI TURN ON/VIDEO + // RASPBERRY PI TURN ON/VIDEO BACKUP if ((time / 1000.0 > 810 && time - timeOfLastCmd > CMD_TIMEOUT_SEC * 1000) || computer.getStageNum() >= 1) rpi.setOn(true); if ((computer.getStageNum() >= 1 || time - timeOfLastCmd > CMD_TIMEOUT_SEC * 1000) && rpi.isOn()) rpi.setRecording(true); } -void processCurrentCmdData(double time) -{ - if (currentCmdData.Launch && computer.getStageNum() == 0) - { - recordLogData(INFO, "Launch Command Received. Launching Rocket."); - computer.launch(); - } - if (time > currentCmdData.MinutesUntilPowerOn && !rpi.isOn()) - { - recordLogData(INFO, "Power On RPI Time Reached. Turning on Raspberry Pi."); - rpi.setOn(true); - } - if (time > currentCmdData.MinutesUntilVideoStart && !rpi.isRecording()) - { - recordLogData(INFO, "Video Start Time Reached. Starting Video Recording."); - rpi.setRecording(true); - } - if (time > currentCmdData.MinutesUntilDataRecording && !computer.getRecordOwnFlightData()) - { - recordLogData(INFO, "Data Recording Time Reached. Starting Data Recording."); - computer.setRecordOwnFlightData(true); - } -} From 10189e974884521271fb0e9cd5341f7d59046797 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Fri, 17 May 2024 01:57:40 -0400 Subject: [PATCH 31/41] Fix \0 char in Log file --- .../Teensy-Based Avionics/lib/RecordData/psram.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/psram.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/psram.cpp index 33ab8c50..db600569 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/psram.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/psram.cpp @@ -15,7 +15,7 @@ bool PSRAM::init() { uint8_t size = external_psram_size; memBegin = cursorStart = reinterpret_cast(0x70000000); - memEnd = cursorEnd = memBegin + (size * 1048576); + memEnd = cursorEnd = memBegin + (size * 1048576) - 1; if (size > 0) { @@ -73,7 +73,7 @@ bool PSRAM::dumpFlightData() bool PSRAM::dumpLogData() { // more complicated because data is stored in reverse order if (!isSDReady() || !ready){ - bb.aonoff(33, 200); + bb.aonoff(BUZZER, 200); return false; } @@ -83,11 +83,11 @@ bool PSRAM::dumpLogData() logFile = sd.open(logFileName, FILE_WRITE); if (!logFile){ - bb.aonoff(33, 200, 3); + bb.aonoff(BUZZER, 200, 3); return false; } - while (writeCursor >= cursorEnd) + while (writeCursor > cursorEnd) { for (i = 0; i < 2048; i++) @@ -106,7 +106,7 @@ bool PSRAM::dumpLogData() logFile.close(); cursorEnd = memEnd; dumped = true; - bb.aonoff(33, 200, 5); + bb.aonoff(BUZZER, 200, 5); return true; } From 6cbec44d0e00802d863d2e201f6404c90e7fe8ff Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Fri, 17 May 2024 14:51:53 -0400 Subject: [PATCH 32/41] update BlinkBuzz dep ver --- Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index 4cfd9683..1792013a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -23,7 +23,7 @@ lib_deps = adafruit/RTClib @ ^2.1.1 adafruit/Adafruit BNO055@^1.6.3 sparkfun/SparkFun u-blox GNSS v3@^3.0.16 - https://github.com/DrewBrandt/BlinkBuzz.git + https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 @@ -58,7 +58,7 @@ lib_deps = adafruit/RTClib @ ^2.1.1 adafruit/Adafruit BNO055@^1.6.3 sparkfun/SparkFun u-blox GNSS v3@^3.0.16 - https://github.com/DrewBrandt/BlinkBuzz.git + https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 From d5ee48ce016b93a603fbf4bd8013ace73675d4ce Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Sat, 8 Jun 2024 16:41:31 -0400 Subject: [PATCH 33/41] nothing is working --- .../lib/RecordData/RecordData.cpp | 33 +++++ .../lib/RecordData/RecordData.h | 13 ++ .../lib/RecordData/sdCard.cpp | 23 ++- .../lib/RecordData/sdCard.h | 8 +- .../Code/Teensy-Based Avionics/platformio.ini | 41 +++--- .../Code/Teensy-Based Avionics/src/BNO055.cpp | 133 +++++++++++++----- .../Code/Teensy-Based Avionics/src/BNO055.h | 12 +- .../Code/Teensy-Based Avionics/src/main.cpp | 47 +++++-- 8 files changed, 232 insertions(+), 78 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp index fb24046f..956d75e6 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp @@ -65,3 +65,36 @@ void setRecordMode(Mode m) } mode = m; } + +bool readCalibrationData(char *data, int len) +{ + if (isSDReady()) + { + calibFile = sd.open(calibFileName, FILE_READ); + if (calibFile) + { + int i = calibFile.read(data, len); + if(i > 0) + data[i] = '\0'; + calibFile.close(); + return i > 0; // most basic check to see if the file was read. + } + } + return false; +} + +bool writeCalibrationData(char *data) +{ + if (isSDReady()) + { + sd.remove(calibFileName); + calibFile = sd.open(calibFileName, FILE_WRITE); + if (calibFile) + { + calibFile.print(data); + calibFile.close(); + return true; + } + } + return false; +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h index efdb80e5..f3af1bb4 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h @@ -13,19 +13,32 @@ enum LogType WARNING, INFO }; + enum Dest { BOTH, TO_USB, TO_FILE }; + enum Mode { FLIGHT, GROUND }; + +struct BnoCalibData{ + float accelOffset[3]; + float accelRadius; + float gyroOffset[3]; + float magOffset[3]; + float magRadius; +}; + void recordFlightData(char *data); //0 is preflight, 5 is postflight. void recordLogData(LogType type, const char *data, Dest dest = BOTH); void recordLogData(double timeStamp, LogType type, const char *data, Dest dest = BOTH); void setRecordMode(Mode mode);//Will enable or disable the PSRAM based on the mode. If mode is GROUND, PSRAM will be disabled and all data in PSRAM will be written to the SD card. If mode is FLIGHT, PSRAM will be enabled. +bool readCalibrationData(char *data, int len); //Reads the calibration data from the SD card and stores it in 'data'. +bool writeCalibrationData(char *data); //Writes the calibration data to the SD card. #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp index 7814a4bd..86521eb8 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp @@ -3,9 +3,10 @@ static constexpr int NAME_SIZE = 24; // SdFs sd; // FsFile logFile; // File object to use for logging -char logFileName[NAME_SIZE]; // Name of the log file -char flightDataFileName[NAME_SIZE]; // Name of the flight data file -bool sdReady = false; // Whether the SD card has been initialized +char logFileName[NAME_SIZE]; // Name of the log file +char flightDataFileName[NAME_SIZE]; // Name of the flight data file +char calibFileName[] = "bno_calib.txt"; // Name of the calibration file +bool sdReady = false; // Whether the SD card has been initialized // SD_FAT_TYPE = 0 for SdFat/File as defined in SdFatConfig.h, // 1 for FAT16/FAT32, 2 for exFAT, 3 for FAT16/FAT32 and exFAT. @@ -55,6 +56,7 @@ ExFile flightDataFile; SdFs sd; FsFile logFile; FsFile flightDataFile; +FsFile calibFile; #else // SD_FAT_TYPE #error Invalid SD_FAT_TYPE #endif // SD_FAT_TYPE @@ -80,21 +82,29 @@ bool setupSDCard() snprintf(flightDataFileName, NAME_SIZE, "%d_FlightData.csv", fileNo); // will overwrite the previous file if it exists #pragma GCC diagnostic pop - // Setup files + // Set up files logFile = sd.open(logFileName, FILE_WRITE); if (logFile) { logFile.close(); rdy++; } + flightDataFile = sd.open(flightDataFileName, FILE_WRITE); if (flightDataFile) { flightDataFile.close(); rdy++; } + + calibFile = sd.open(calibFileName, FILE_WRITE); + if (calibFile) + { + calibFile.close(); + rdy++; + } } - sdReady = rdy == 2; + sdReady = rdy == 3; return sdReady; } @@ -114,4 +124,5 @@ void sendSDCardHeader(const char *csvHeader) bool isSDReady() { return sdReady; -} \ No newline at end of file +} + diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h index fd82ada0..9836b1fd 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h @@ -7,11 +7,13 @@ extern SdFs sd; extern FsFile logFile; extern FsFile flightDataFile; +extern FsFile calibFile; extern char logFileName[]; extern char flightDataFileName[]; +extern char calibFileName[]; -bool setupSDCard(); // Initializes the sensor -bool isSDReady(); // Returns whether the sensor is initialized -void sendSDCardHeader(const char *csvHeader); // Sends the header to the SD card +bool setupSDCard(); // Initializes the card +bool isSDReady(); // Returns whether the card is initialized +void sendSDCardHeader(const char *csvHeader); // Sends the header to the SD card for the csv file. #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index 1792013a..b242041d 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -10,6 +10,14 @@ [platformio] default_envs = teensy41 +[common] +lib_deps_external = + adafruit/Adafruit BMP3XX Library@^2.1.2 + adafruit/RTClib @ ^2.1.1 + adafruit/Adafruit BNO055@^1.6.3 + sparkfun/SparkFun u-blox GNSS v3@^3.0.16 + https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 + [env:teensy41] platform = teensy board = teensy41 @@ -18,12 +26,7 @@ lib_extra_dirs = /lib/imumaths build_src_filter = +<*> - + - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict -lib_deps = - adafruit/Adafruit BMP3XX Library@^2.1.2 - adafruit/RTClib @ ^2.1.1 - adafruit/Adafruit BNO055@^1.6.3 - sparkfun/SparkFun u-blox GNSS v3@^3.0.16 - https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 +lib_deps = ${common.lib_deps_external} check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 @@ -36,16 +39,12 @@ lib_extra_dirs = /lib/imumaths build_src_filter = +<*> - - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict -lib_deps = - adafruit/Adafruit BMP3XX Library@^2.1.2 - adafruit/RTClib @ ^2.1.1 - adafruit/Adafruit BNO055@^1.6.3 - sparkfun/SparkFun u-blox GNSS v3@^3.0.16 +lib_deps = ${common.lib_deps_external} check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 -[env:teensy41_TEST_STATE] +[env:teensy41_test_state] platform = teensy board = teensy41 framework = arduino @@ -53,17 +52,12 @@ lib_extra_dirs = /lib/imumaths build_src_filter = +<*> - - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict -lib_deps = - adafruit/Adafruit BMP3XX Library@^2.1.2 - adafruit/RTClib @ ^2.1.1 - adafruit/Adafruit BNO055@^1.6.3 - sparkfun/SparkFun u-blox GNSS v3@^3.0.16 - https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 +lib_deps = ${common.lib_deps_external} check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 -[env:teensy41_GROUND_STATION_RECEIVER] +[env:teensy41_ground_reciever] platform = teensy board = teensy41 framework = arduino @@ -75,4 +69,11 @@ lib_deps = adafruit/Adafruit BNO055@^1.6.3 ; For the imumaths library check_src_filters = -<*> + + + - check_flags = - cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 \ No newline at end of file + cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 + +[env:teensy41_calibrate] +platform = teensy +board = teensy41 +framework = arduino +lib_extra_dirs = /lib/imumaths +build_src_filter = -<*> + + + \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp index 6a2e078f..03a9bc0c 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp @@ -1,27 +1,56 @@ #include "BNO055.h" -BNO055::BNO055(uint8_t SCK, uint8_t SDA) -{ - SCKPin = SCK; - SDAPin = SDA; -} - bool BNO055::initialize() { if (!bno.begin()) { return initialized = false; } - bno.setExtCrystalUse(true); // set to +-16g range adafruit_bno055_opmode_t mode = bno.getMode(); bno.setMode(OPERATION_MODE_CONFIG); delay(25); - Wire.beginTransmission(0x29);//BNO055 address - Wire.write(0x08);//ACC_CONFIG register address on BNO055 - Wire.write(0b11);//set to +-16g range - Wire.endTransmission(true); // send stop + + Wire.beginTransmission(0x29); // BNO055 address + Wire.write(0x08); // ACC_CONFIG register address on BNO055 + Wire.write(0b11); // set to +-16g range + Wire.endTransmission(true); // send stop + + recordLogData(INFO, "BNO055 Calibration Loading"); + recordLogData(INFO, "Pre-Loading Values:"); + adafruit_bno055_offsets_t sensorOffsets; + + if(!bno.getSensorOffsets(sensorOffsets)) + { + recordLogData(INFO, "Failed to get sensor offsets", TO_USB); + } + char data[100]; + + snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd", sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius); + recordLogData(INFO, data); + snprintf(data, 100, "GYR: %hd|%hd|%hd", sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z); + recordLogData(INFO, data); + snprintf(data, 100, "MAG: %hd|%hd|%hd|%hd", sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); + recordLogData(INFO, data); + + setCalibrationFromFile(); + + recordLogData(INFO, "Post-Loading Values:"); + if (!bno.getSensorOffsets(sensorOffsets)) + { + recordLogData(INFO, "Failed to get sensor offsets", TO_USB); + } + + snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd", sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius); + recordLogData(INFO, data); + snprintf(data, 100, "GYR: %hd|%hd|%hd", sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z); + recordLogData(INFO, data); + snprintf(data, 100, "MAG: %hd|%hd|%hd|%hd", sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); + recordLogData(INFO, data); + + bno.setExtCrystalUse(true); + bno.setMode(mode); delay(25); @@ -48,29 +77,18 @@ void BNO055::update() } prevReadings[19] = read; accelerationVec = read - (sum / 10.0); + } else { accelerationVec = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL); } + printf("Acceleration: %.2f, %.2f, %.2f\n", accelerationVec.x(), accelerationVec.y(), accelerationVec.z()); orientation = bno.getQuat(); orientationEuler = bno.getVector(Adafruit_BNO055::VECTOR_EULER); magnetometer = bno.getVector(Adafruit_BNO055::VECTOR_MAGNETOMETER); -} -void BNO055::calibrateBno() -{ - uint8_t system, gyro, accel, mag, i = 0; - while ((system != 3) || (gyro != 3) || (accel != 3) || (mag != 3)) - { - bno.getCalibration(&system, &gyro, &accel, &mag); - i = i + 1; - if (i == 10) - { - i = 0; - } - delay(10); - } + } imu::Quaternion BNO055::getOrientation() @@ -93,15 +111,6 @@ imu::Vector<3> BNO055::getMagnetometer() return magnetometer; } -imu::Vector<3> convertToEuler(const imu::Quaternion &orientation) - -{ - imu::Vector<3> euler = orientation.toEuler(); - // reverse the vector, since it returns in z, y, x - euler = imu::Vector<3>(euler.x(), euler.y(), euler.z()); - return euler; -} - const char *BNO055::getCsvHeader() { // incl I- for IMU return "I-AX (m/s/s),I-AY (m/s/s),I-AZ (m/s/s),I-ULRX,I-ULRY,I-ULRZ,I-QUATX,I-QUATY,I-QUATZ,I-QUATW,"; // trailing comma @@ -118,10 +127,13 @@ char *BNO055::getDataString() char *BNO055::getStaticDataString() { - // See State.cpp::setDataString() for comments on what these numbers mean - const int size = 30 + 12 * 3; - char *data = new char[size]; - snprintf(data, size, "Initial Magnetic Field (uT): %.2f,%.2f,%.2f\n", initialMagField.x(), initialMagField.y(), initialMagField.z()); + char *data = new char[100]; + adafruit_bno055_offsets_t sensorOffsets; + bno.getSensorOffsets(sensorOffsets); + snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd", + sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius, + sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z, + sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); return data; } @@ -133,4 +145,49 @@ const char *BNO055::getName() void BNO055::setBiasCorrectionMode(bool mode) { biasCorrectionMode = mode; +} + +void BNO055::setCalibrationFromFile() +{ + /* + File format: + + ACC: X|Y|Z|R + GYR: X|Y|Z + MAG: X|Y|Z|R + */ + char data[100]; + readCalibrationData(data, 100); + adafruit_bno055_offsets_t sensorOffsets; + sscanf(data, "ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd", + &sensorOffsets.accel_offset_x, &sensorOffsets.accel_offset_y, &sensorOffsets.accel_offset_z, &sensorOffsets.accel_radius, + &sensorOffsets.gyro_offset_x, &sensorOffsets.gyro_offset_y, &sensorOffsets.gyro_offset_z, + &sensorOffsets.mag_offset_x, &sensorOffsets.mag_offset_y, &sensorOffsets.mag_offset_z, &sensorOffsets.mag_radius); + printf("ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd\n", + sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius, + sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z, + sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); + bno.setSensorOffsets(sensorOffsets); +} + +void BNO055::recordCalibrationValues() +{ + adafruit_bno055_offsets_t sensorOffsets; + bno.getSensorOffsets(sensorOffsets); + char data[100]; + snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd", + sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius, + sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z, + sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); + writeCalibrationData(data); +} + +void BNO055::getSensorOffsets(adafruit_bno055_offsets_t &offsets) +{ + bno.getSensorOffsets(offsets); +} + +void BNO055::getCalibrationStatus(uint8_t &system, uint8_t &gyro, uint8_t &accel, uint8_t &mag) +{ + bno.getCalibration(&system, &gyro, &accel, &mag); } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h index d28650fc..c97daf8e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h @@ -1,6 +1,7 @@ #include #include #include "IMU.h" +#include "RecordData.h" class BNO055 : public IMU { @@ -15,8 +16,9 @@ class BNO055 : public IMU imu::Vector<3> initialMagField; imu::Vector<3> prevReadings[20]; + void setCalibrationFromFile(); + public: - BNO055(uint8_t SCK, uint8_t SDA); void calibrateBno(); imu::Quaternion getOrientation() override; // gives linearAcceleration in m/s/s, which excludes gravity @@ -24,8 +26,6 @@ class BNO055 : public IMU imu::Vector<3> getOrientationEuler() override; // values in uT, micro Teslas imu::Vector<3> getMagnetometer() override; - // gives it in rotations about the x, y, z (yaw, pitch, roll) axes - imu::Vector<3> convertToEuler(const imu::Quaternion &orientation); bool initialize() override; const char *getCsvHeader() override; char *getDataString() override; @@ -33,4 +33,10 @@ class BNO055 : public IMU char const *getName() override; void update() override; void setBiasCorrectionMode(bool mode) override; + void recordCalibrationValues(); + void getSensorOffsets(adafruit_bno055_offsets_t &offsets); + void getCalibrationStatus(uint8_t &system, uint8_t &gyro, uint8_t &accel, uint8_t &mag); }; + +// gives it in rotations about the x, y, z (yaw, pitch, roll) axes +imu::Vector<3> convertToEuler(const imu::Quaternion &orientation); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 02636335..f2654854 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -14,7 +14,7 @@ #define RPI_PWR 0 #define RPI_VIDEO 1 -BNO055 bno(13, 12); // I2C Address 0x29 +BNO055 bno; // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 @@ -26,7 +26,6 @@ APRSCmdMsg cmd(header); APRSTelemMsg telem(header); int timeOfLastCmd = 0; const int CMD_TIMEOUT_SEC = 100; // 10 seconds -void processCurrentCmdData(double time); State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); @@ -34,7 +33,7 @@ Pi rpi(RPI_PWR, RPI_VIDEO); PSRAM *ram; static double last = 0; // for better timing than "delay(100)" - +bool calibrationMode = false; // BlinkBuzz setup int BUZZER = 33; int LED = LED_BUILTIN; @@ -64,7 +63,6 @@ void setup() pinMode(BMP_ADDR_PIN, OUTPUT); digitalWrite(BMP_ADDR_PIN, HIGH); - ram = new PSRAM(); // init after the SD card for better data logging. // The SD card MUST be initialized first to allow proper data logging. if (setupSDCard()) @@ -81,7 +79,7 @@ void setup() } // The PSRAM must be initialized before the sensors to allow for proper data logging. - + ram = new PSRAM(); // init after the SD card for better data logging. if (ram->init()) recordLogData(INFO, "PSRAM Initialized"); else @@ -104,7 +102,12 @@ void setup() recordLogData(ERROR, "Some Sensors Failed to Initialize. Disabling those sensors."); bb.onoff(BUZZER, 200, 3); } + + computer.setRecordOwnFlightData(true); + sendSDCardHeader(computer.getCsvHeader()); + if (calibrationMode) + recordLogData(INFO, "Calibration Mode"); } void loop() @@ -128,8 +131,38 @@ void loop() last = time; computer.updateState(); - // recordLogData(INFO, computer.getStateString(), TO_USB); + if(!calibrationMode) + { + recordLogData(INFO, computer.getStateString(), TO_USB); + } + + + if (bno && computer.getStageNum() == 0 && (int)(time) % 5000 < 100) + { + if (calibrationMode) + { + recordLogData(INFO, "IMU Calibration Data", TO_USB); + adafruit_bno055_offsets_t calibData; + bno.getSensorOffsets(calibData); + char data[100]; + uint8_t system, gyro, accel, mag; + bno.getCalibrationStatus(system, gyro, accel, mag); + snprintf(data, 100, "System: %hhu, Gyro: %hhu, Accel: %hhu, Mag: %hhu", system, gyro, accel, mag); + recordLogData(INFO, data, TO_USB); + snprintf(data, 100, "Accel Offset: %hd, %hd, %hd", calibData.accel_offset_x, calibData.accel_offset_y, calibData.accel_offset_z); + recordLogData(INFO, data, TO_USB); + snprintf(data, 100, "Accel Radius: %hd", calibData.accel_radius); + recordLogData(INFO, data, TO_USB); + snprintf(data, 100, "Gyro Offset: %hd, %hd, %hd", calibData.gyro_offset_x, calibData.gyro_offset_y, calibData.gyro_offset_z); + recordLogData(INFO, data, TO_USB); + snprintf(data, 100, "Mag Offset: %hd, %hd, %hd", calibData.mag_offset_x, calibData.mag_offset_y, calibData.mag_offset_z); + recordLogData(INFO, data, TO_USB); + snprintf(data, 100, "Mag Radius: %hd\n", calibData.mag_radius); + recordLogData(INFO, data, TO_USB); + } + bno.recordCalibrationValues(); + } // Send Telemetry Data if (time - radioTimer >= 1000) { @@ -150,5 +183,3 @@ void loop() if ((computer.getStageNum() >= 1 || time - timeOfLastCmd > CMD_TIMEOUT_SEC * 1000) && rpi.isOn()) rpi.setRecording(true); } - - From 29831c21f64fc9d38a94ded2ef67b80fc5efcdd6 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Sat, 8 Jun 2024 17:24:58 -0400 Subject: [PATCH 34/41] Revert "nothing is working" This reverts commit d5ee48ce016b93a603fbf4bd8013ace73675d4ce. --- .../lib/RecordData/RecordData.cpp | 33 ----- .../lib/RecordData/RecordData.h | 13 -- .../lib/RecordData/sdCard.cpp | 23 +-- .../lib/RecordData/sdCard.h | 8 +- .../Code/Teensy-Based Avionics/platformio.ini | 41 +++--- .../Code/Teensy-Based Avionics/src/BNO055.cpp | 133 +++++------------- .../Code/Teensy-Based Avionics/src/BNO055.h | 12 +- .../Code/Teensy-Based Avionics/src/main.cpp | 47 ++----- 8 files changed, 78 insertions(+), 232 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp index 956d75e6..fb24046f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.cpp @@ -65,36 +65,3 @@ void setRecordMode(Mode m) } mode = m; } - -bool readCalibrationData(char *data, int len) -{ - if (isSDReady()) - { - calibFile = sd.open(calibFileName, FILE_READ); - if (calibFile) - { - int i = calibFile.read(data, len); - if(i > 0) - data[i] = '\0'; - calibFile.close(); - return i > 0; // most basic check to see if the file was read. - } - } - return false; -} - -bool writeCalibrationData(char *data) -{ - if (isSDReady()) - { - sd.remove(calibFileName); - calibFile = sd.open(calibFileName, FILE_WRITE); - if (calibFile) - { - calibFile.print(data); - calibFile.close(); - return true; - } - } - return false; -} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h index f3af1bb4..efdb80e5 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/RecordData.h @@ -13,32 +13,19 @@ enum LogType WARNING, INFO }; - enum Dest { BOTH, TO_USB, TO_FILE }; - enum Mode { FLIGHT, GROUND }; - -struct BnoCalibData{ - float accelOffset[3]; - float accelRadius; - float gyroOffset[3]; - float magOffset[3]; - float magRadius; -}; - void recordFlightData(char *data); //0 is preflight, 5 is postflight. void recordLogData(LogType type, const char *data, Dest dest = BOTH); void recordLogData(double timeStamp, LogType type, const char *data, Dest dest = BOTH); void setRecordMode(Mode mode);//Will enable or disable the PSRAM based on the mode. If mode is GROUND, PSRAM will be disabled and all data in PSRAM will be written to the SD card. If mode is FLIGHT, PSRAM will be enabled. -bool readCalibrationData(char *data, int len); //Reads the calibration data from the SD card and stores it in 'data'. -bool writeCalibrationData(char *data); //Writes the calibration data to the SD card. #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp index 86521eb8..7814a4bd 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.cpp @@ -3,10 +3,9 @@ static constexpr int NAME_SIZE = 24; // SdFs sd; // FsFile logFile; // File object to use for logging -char logFileName[NAME_SIZE]; // Name of the log file -char flightDataFileName[NAME_SIZE]; // Name of the flight data file -char calibFileName[] = "bno_calib.txt"; // Name of the calibration file -bool sdReady = false; // Whether the SD card has been initialized +char logFileName[NAME_SIZE]; // Name of the log file +char flightDataFileName[NAME_SIZE]; // Name of the flight data file +bool sdReady = false; // Whether the SD card has been initialized // SD_FAT_TYPE = 0 for SdFat/File as defined in SdFatConfig.h, // 1 for FAT16/FAT32, 2 for exFAT, 3 for FAT16/FAT32 and exFAT. @@ -56,7 +55,6 @@ ExFile flightDataFile; SdFs sd; FsFile logFile; FsFile flightDataFile; -FsFile calibFile; #else // SD_FAT_TYPE #error Invalid SD_FAT_TYPE #endif // SD_FAT_TYPE @@ -82,29 +80,21 @@ bool setupSDCard() snprintf(flightDataFileName, NAME_SIZE, "%d_FlightData.csv", fileNo); // will overwrite the previous file if it exists #pragma GCC diagnostic pop - // Set up files + // Setup files logFile = sd.open(logFileName, FILE_WRITE); if (logFile) { logFile.close(); rdy++; } - flightDataFile = sd.open(flightDataFileName, FILE_WRITE); if (flightDataFile) { flightDataFile.close(); rdy++; } - - calibFile = sd.open(calibFileName, FILE_WRITE); - if (calibFile) - { - calibFile.close(); - rdy++; - } } - sdReady = rdy == 3; + sdReady = rdy == 2; return sdReady; } @@ -124,5 +114,4 @@ void sendSDCardHeader(const char *csvHeader) bool isSDReady() { return sdReady; -} - +} \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h index 9836b1fd..fd82ada0 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/lib/RecordData/sdCard.h @@ -7,13 +7,11 @@ extern SdFs sd; extern FsFile logFile; extern FsFile flightDataFile; -extern FsFile calibFile; extern char logFileName[]; extern char flightDataFileName[]; -extern char calibFileName[]; -bool setupSDCard(); // Initializes the card -bool isSDReady(); // Returns whether the card is initialized -void sendSDCardHeader(const char *csvHeader); // Sends the header to the SD card for the csv file. +bool setupSDCard(); // Initializes the sensor +bool isSDReady(); // Returns whether the sensor is initialized +void sendSDCardHeader(const char *csvHeader); // Sends the header to the SD card #endif \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index b242041d..1792013a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -10,14 +10,6 @@ [platformio] default_envs = teensy41 -[common] -lib_deps_external = - adafruit/Adafruit BMP3XX Library@^2.1.2 - adafruit/RTClib @ ^2.1.1 - adafruit/Adafruit BNO055@^1.6.3 - sparkfun/SparkFun u-blox GNSS v3@^3.0.16 - https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 - [env:teensy41] platform = teensy board = teensy41 @@ -26,7 +18,12 @@ lib_extra_dirs = /lib/imumaths build_src_filter = +<*> - + - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict -lib_deps = ${common.lib_deps_external} +lib_deps = + adafruit/Adafruit BMP3XX Library@^2.1.2 + adafruit/RTClib @ ^2.1.1 + adafruit/Adafruit BNO055@^1.6.3 + sparkfun/SparkFun u-blox GNSS v3@^3.0.16 + https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 @@ -39,12 +36,16 @@ lib_extra_dirs = /lib/imumaths build_src_filter = +<*> - - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict -lib_deps = ${common.lib_deps_external} +lib_deps = + adafruit/Adafruit BMP3XX Library@^2.1.2 + adafruit/RTClib @ ^2.1.1 + adafruit/Adafruit BNO055@^1.6.3 + sparkfun/SparkFun u-blox GNSS v3@^3.0.16 check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 -[env:teensy41_test_state] +[env:teensy41_TEST_STATE] platform = teensy board = teensy41 framework = arduino @@ -52,12 +53,17 @@ lib_extra_dirs = /lib/imumaths build_src_filter = +<*> - - build_flags = -Wno-unknown-pragmas lib_compat_mode = strict -lib_deps = ${common.lib_deps_external} +lib_deps = + adafruit/Adafruit BMP3XX Library@^2.1.2 + adafruit/RTClib @ ^2.1.1 + adafruit/Adafruit BNO055@^1.6.3 + sparkfun/SparkFun u-blox GNSS v3@^3.0.16 + https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 -[env:teensy41_ground_reciever] +[env:teensy41_GROUND_STATION_RECEIVER] platform = teensy board = teensy41 framework = arduino @@ -69,11 +75,4 @@ lib_deps = adafruit/Adafruit BNO055@^1.6.3 ; For the imumaths library check_src_filters = -<*> + + + - check_flags = - cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 - -[env:teensy41_calibrate] -platform = teensy -board = teensy41 -framework = arduino -lib_extra_dirs = /lib/imumaths -build_src_filter = -<*> + + + \ No newline at end of file + cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp index 03a9bc0c..6a2e078f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp @@ -1,56 +1,27 @@ #include "BNO055.h" +BNO055::BNO055(uint8_t SCK, uint8_t SDA) +{ + SCKPin = SCK; + SDAPin = SDA; +} + bool BNO055::initialize() { if (!bno.begin()) { return initialized = false; } + bno.setExtCrystalUse(true); // set to +-16g range adafruit_bno055_opmode_t mode = bno.getMode(); bno.setMode(OPERATION_MODE_CONFIG); delay(25); - - Wire.beginTransmission(0x29); // BNO055 address - Wire.write(0x08); // ACC_CONFIG register address on BNO055 - Wire.write(0b11); // set to +-16g range - Wire.endTransmission(true); // send stop - - recordLogData(INFO, "BNO055 Calibration Loading"); - recordLogData(INFO, "Pre-Loading Values:"); - adafruit_bno055_offsets_t sensorOffsets; - - if(!bno.getSensorOffsets(sensorOffsets)) - { - recordLogData(INFO, "Failed to get sensor offsets", TO_USB); - } - char data[100]; - - snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd", sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius); - recordLogData(INFO, data); - snprintf(data, 100, "GYR: %hd|%hd|%hd", sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z); - recordLogData(INFO, data); - snprintf(data, 100, "MAG: %hd|%hd|%hd|%hd", sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); - recordLogData(INFO, data); - - setCalibrationFromFile(); - - recordLogData(INFO, "Post-Loading Values:"); - if (!bno.getSensorOffsets(sensorOffsets)) - { - recordLogData(INFO, "Failed to get sensor offsets", TO_USB); - } - - snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd", sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius); - recordLogData(INFO, data); - snprintf(data, 100, "GYR: %hd|%hd|%hd", sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z); - recordLogData(INFO, data); - snprintf(data, 100, "MAG: %hd|%hd|%hd|%hd", sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); - recordLogData(INFO, data); - - bno.setExtCrystalUse(true); - + Wire.beginTransmission(0x29);//BNO055 address + Wire.write(0x08);//ACC_CONFIG register address on BNO055 + Wire.write(0b11);//set to +-16g range + Wire.endTransmission(true); // send stop bno.setMode(mode); delay(25); @@ -77,18 +48,29 @@ void BNO055::update() } prevReadings[19] = read; accelerationVec = read - (sum / 10.0); - } else { accelerationVec = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL); } - printf("Acceleration: %.2f, %.2f, %.2f\n", accelerationVec.x(), accelerationVec.y(), accelerationVec.z()); orientation = bno.getQuat(); orientationEuler = bno.getVector(Adafruit_BNO055::VECTOR_EULER); magnetometer = bno.getVector(Adafruit_BNO055::VECTOR_MAGNETOMETER); +} - +void BNO055::calibrateBno() +{ + uint8_t system, gyro, accel, mag, i = 0; + while ((system != 3) || (gyro != 3) || (accel != 3) || (mag != 3)) + { + bno.getCalibration(&system, &gyro, &accel, &mag); + i = i + 1; + if (i == 10) + { + i = 0; + } + delay(10); + } } imu::Quaternion BNO055::getOrientation() @@ -111,6 +93,15 @@ imu::Vector<3> BNO055::getMagnetometer() return magnetometer; } +imu::Vector<3> convertToEuler(const imu::Quaternion &orientation) + +{ + imu::Vector<3> euler = orientation.toEuler(); + // reverse the vector, since it returns in z, y, x + euler = imu::Vector<3>(euler.x(), euler.y(), euler.z()); + return euler; +} + const char *BNO055::getCsvHeader() { // incl I- for IMU return "I-AX (m/s/s),I-AY (m/s/s),I-AZ (m/s/s),I-ULRX,I-ULRY,I-ULRZ,I-QUATX,I-QUATY,I-QUATZ,I-QUATW,"; // trailing comma @@ -127,13 +118,10 @@ char *BNO055::getDataString() char *BNO055::getStaticDataString() { - char *data = new char[100]; - adafruit_bno055_offsets_t sensorOffsets; - bno.getSensorOffsets(sensorOffsets); - snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd", - sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius, - sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z, - sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); + // See State.cpp::setDataString() for comments on what these numbers mean + const int size = 30 + 12 * 3; + char *data = new char[size]; + snprintf(data, size, "Initial Magnetic Field (uT): %.2f,%.2f,%.2f\n", initialMagField.x(), initialMagField.y(), initialMagField.z()); return data; } @@ -145,49 +133,4 @@ const char *BNO055::getName() void BNO055::setBiasCorrectionMode(bool mode) { biasCorrectionMode = mode; -} - -void BNO055::setCalibrationFromFile() -{ - /* - File format: - - ACC: X|Y|Z|R - GYR: X|Y|Z - MAG: X|Y|Z|R - */ - char data[100]; - readCalibrationData(data, 100); - adafruit_bno055_offsets_t sensorOffsets; - sscanf(data, "ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd", - &sensorOffsets.accel_offset_x, &sensorOffsets.accel_offset_y, &sensorOffsets.accel_offset_z, &sensorOffsets.accel_radius, - &sensorOffsets.gyro_offset_x, &sensorOffsets.gyro_offset_y, &sensorOffsets.gyro_offset_z, - &sensorOffsets.mag_offset_x, &sensorOffsets.mag_offset_y, &sensorOffsets.mag_offset_z, &sensorOffsets.mag_radius); - printf("ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd\n", - sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius, - sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z, - sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); - bno.setSensorOffsets(sensorOffsets); -} - -void BNO055::recordCalibrationValues() -{ - adafruit_bno055_offsets_t sensorOffsets; - bno.getSensorOffsets(sensorOffsets); - char data[100]; - snprintf(data, 100, "ACC: %hd|%hd|%hd|%hd\nGYR: %hd|%hd|%hd\nMAG: %hd|%hd|%hd|%hd", - sensorOffsets.accel_offset_x, sensorOffsets.accel_offset_y, sensorOffsets.accel_offset_z, sensorOffsets.accel_radius, - sensorOffsets.gyro_offset_x, sensorOffsets.gyro_offset_y, sensorOffsets.gyro_offset_z, - sensorOffsets.mag_offset_x, sensorOffsets.mag_offset_y, sensorOffsets.mag_offset_z, sensorOffsets.mag_radius); - writeCalibrationData(data); -} - -void BNO055::getSensorOffsets(adafruit_bno055_offsets_t &offsets) -{ - bno.getSensorOffsets(offsets); -} - -void BNO055::getCalibrationStatus(uint8_t &system, uint8_t &gyro, uint8_t &accel, uint8_t &mag) -{ - bno.getCalibration(&system, &gyro, &accel, &mag); } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h index c97daf8e..d28650fc 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.h @@ -1,7 +1,6 @@ #include #include #include "IMU.h" -#include "RecordData.h" class BNO055 : public IMU { @@ -16,9 +15,8 @@ class BNO055 : public IMU imu::Vector<3> initialMagField; imu::Vector<3> prevReadings[20]; - void setCalibrationFromFile(); - public: + BNO055(uint8_t SCK, uint8_t SDA); void calibrateBno(); imu::Quaternion getOrientation() override; // gives linearAcceleration in m/s/s, which excludes gravity @@ -26,6 +24,8 @@ class BNO055 : public IMU imu::Vector<3> getOrientationEuler() override; // values in uT, micro Teslas imu::Vector<3> getMagnetometer() override; + // gives it in rotations about the x, y, z (yaw, pitch, roll) axes + imu::Vector<3> convertToEuler(const imu::Quaternion &orientation); bool initialize() override; const char *getCsvHeader() override; char *getDataString() override; @@ -33,10 +33,4 @@ class BNO055 : public IMU char const *getName() override; void update() override; void setBiasCorrectionMode(bool mode) override; - void recordCalibrationValues(); - void getSensorOffsets(adafruit_bno055_offsets_t &offsets); - void getCalibrationStatus(uint8_t &system, uint8_t &gyro, uint8_t &accel, uint8_t &mag); }; - -// gives it in rotations about the x, y, z (yaw, pitch, roll) axes -imu::Vector<3> convertToEuler(const imu::Quaternion &orientation); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index f2654854..02636335 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -14,7 +14,7 @@ #define RPI_PWR 0 #define RPI_VIDEO 1 -BNO055 bno; // I2C Address 0x29 +BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 @@ -26,6 +26,7 @@ APRSCmdMsg cmd(header); APRSTelemMsg telem(header); int timeOfLastCmd = 0; const int CMD_TIMEOUT_SEC = 100; // 10 seconds +void processCurrentCmdData(double time); State computer; // = useKalmanFilter = true, stateRecordsOwnData = true uint32_t radioTimer = millis(); @@ -33,7 +34,7 @@ Pi rpi(RPI_PWR, RPI_VIDEO); PSRAM *ram; static double last = 0; // for better timing than "delay(100)" -bool calibrationMode = false; + // BlinkBuzz setup int BUZZER = 33; int LED = LED_BUILTIN; @@ -63,6 +64,7 @@ void setup() pinMode(BMP_ADDR_PIN, OUTPUT); digitalWrite(BMP_ADDR_PIN, HIGH); + ram = new PSRAM(); // init after the SD card for better data logging. // The SD card MUST be initialized first to allow proper data logging. if (setupSDCard()) @@ -79,7 +81,7 @@ void setup() } // The PSRAM must be initialized before the sensors to allow for proper data logging. - ram = new PSRAM(); // init after the SD card for better data logging. + if (ram->init()) recordLogData(INFO, "PSRAM Initialized"); else @@ -102,12 +104,7 @@ void setup() recordLogData(ERROR, "Some Sensors Failed to Initialize. Disabling those sensors."); bb.onoff(BUZZER, 200, 3); } - - computer.setRecordOwnFlightData(true); - sendSDCardHeader(computer.getCsvHeader()); - if (calibrationMode) - recordLogData(INFO, "Calibration Mode"); } void loop() @@ -131,38 +128,8 @@ void loop() last = time; computer.updateState(); + // recordLogData(INFO, computer.getStateString(), TO_USB); - if(!calibrationMode) - { - recordLogData(INFO, computer.getStateString(), TO_USB); - } - - - if (bno && computer.getStageNum() == 0 && (int)(time) % 5000 < 100) - { - if (calibrationMode) - { - recordLogData(INFO, "IMU Calibration Data", TO_USB); - adafruit_bno055_offsets_t calibData; - bno.getSensorOffsets(calibData); - char data[100]; - uint8_t system, gyro, accel, mag; - bno.getCalibrationStatus(system, gyro, accel, mag); - snprintf(data, 100, "System: %hhu, Gyro: %hhu, Accel: %hhu, Mag: %hhu", system, gyro, accel, mag); - recordLogData(INFO, data, TO_USB); - snprintf(data, 100, "Accel Offset: %hd, %hd, %hd", calibData.accel_offset_x, calibData.accel_offset_y, calibData.accel_offset_z); - recordLogData(INFO, data, TO_USB); - snprintf(data, 100, "Accel Radius: %hd", calibData.accel_radius); - recordLogData(INFO, data, TO_USB); - snprintf(data, 100, "Gyro Offset: %hd, %hd, %hd", calibData.gyro_offset_x, calibData.gyro_offset_y, calibData.gyro_offset_z); - recordLogData(INFO, data, TO_USB); - snprintf(data, 100, "Mag Offset: %hd, %hd, %hd", calibData.mag_offset_x, calibData.mag_offset_y, calibData.mag_offset_z); - recordLogData(INFO, data, TO_USB); - snprintf(data, 100, "Mag Radius: %hd\n", calibData.mag_radius); - recordLogData(INFO, data, TO_USB); - } - bno.recordCalibrationValues(); - } // Send Telemetry Data if (time - radioTimer >= 1000) { @@ -183,3 +150,5 @@ void loop() if ((computer.getStageNum() >= 1 || time - timeOfLastCmd > CMD_TIMEOUT_SEC * 1000) && rpi.isOn()) rpi.setRecording(true); } + + From afd560485d26bc5b9d84e0776aa860e755a7c346 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Sat, 8 Jun 2024 17:47:30 -0400 Subject: [PATCH 35/41] Remapped BNO X and Z axes --- Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp | 7 ++++++- Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp | 2 +- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp index 6a2e078f..8a2405f8 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/BNO055.cpp @@ -12,7 +12,6 @@ bool BNO055::initialize() { return initialized = false; } - bno.setExtCrystalUse(true); // set to +-16g range adafruit_bno055_opmode_t mode = bno.getMode(); @@ -25,6 +24,8 @@ bool BNO055::initialize() bno.setMode(mode); delay(25); + bno.setExtCrystalUse(true); + initialMagField = bno.getVector(Adafruit_BNO055::VECTOR_MAGNETOMETER); imu::Vector<3> read = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL); for (int i = 0; i < 20; i++) @@ -53,6 +54,10 @@ void BNO055::update() { accelerationVec = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL); } + double x = accelerationVec.z(); + accelerationVec.x() = accelerationVec.z(); + accelerationVec.z() = x; + orientation = bno.getQuat(); orientationEuler = bno.getVector(Adafruit_BNO055::VECTOR_EULER); magnetometer = bno.getVector(Adafruit_BNO055::VECTOR_MAGNETOMETER); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 02636335..b2f43beb 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -128,7 +128,7 @@ void loop() last = time; computer.updateState(); - // recordLogData(INFO, computer.getStateString(), TO_USB); + recordLogData(INFO, computer.getStateString(), TO_USB); // Send Telemetry Data if (time - radioTimer >= 1000) From 6005632aa84893a2bb5ecf68a87e7de3a8fa1a6d Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 12 Jun 2024 22:57:51 -0400 Subject: [PATCH 36/41] refactor: Improve logging in RadioHandler processCmdData --- .../Code/Teensy-Based Avionics/src/Radio/RadioHandler.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h index a1b98992..2f15c74c 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h @@ -13,25 +13,25 @@ namespace radioHandler void processCmdData(APRSCmdMsg &cmd, APRSCmdData &old, APRSCmdData ¤tCmdData, int time) { char log[100]; - if (cmd.data.Launch != old.Launch) + if (cmd.data.Launch != old.Launch && cmd.data.Launch >= 0) { snprintf(log, 100, "Launch Command Changed to %d.", cmd.data.Launch); recordLogData(INFO, log); currentCmdData.Launch = cmd.data.Launch; } - if (cmd.data.MinutesUntilPowerOn != old.MinutesUntilPowerOn) + if (cmd.data.MinutesUntilPowerOn != old.MinutesUntilPowerOn && cmd.data.MinutesUntilPowerOn >= 0) { snprintf(log, 100, "Power On Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilPowerOn, (int)(currentCmdData.MinutesUntilPowerOn - time) / 60000); recordLogData(INFO, log); currentCmdData.MinutesUntilPowerOn = cmd.data.MinutesUntilPowerOn * 60 * 1000 + time; } - if (cmd.data.MinutesUntilVideoStart != old.MinutesUntilVideoStart) + if (cmd.data.MinutesUntilVideoStart != old.MinutesUntilVideoStart && cmd.data.MinutesUntilVideoStart >= 0) { snprintf(log, 100, "Video Start Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilVideoStart, (int)(currentCmdData.MinutesUntilVideoStart - time) / 60000); recordLogData(INFO, log); currentCmdData.MinutesUntilVideoStart = cmd.data.MinutesUntilVideoStart * 60 * 1000 + time; } - if (cmd.data.MinutesUntilDataRecording != old.MinutesUntilDataRecording) + if (cmd.data.MinutesUntilDataRecording != old.MinutesUntilDataRecording && cmd.data.MinutesUntilDataRecording >= 0) { snprintf(log, 100, "Data Recording Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilDataRecording, (int)(currentCmdData.MinutesUntilDataRecording - time) / 60000); recordLogData(INFO, log); From 1c1fcb360f49bf20e3fdf5ab9c1e41f7f22c9bda Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Fri, 14 Jun 2024 13:28:30 -0400 Subject: [PATCH 37/41] Radio Freq Changes --- .../src/GroundStationReceiver/main.cpp | 3 ++- .../Code/Teensy-Based Avionics/src/Radio/RadioHandler.h | 1 + Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp | 6 +++--- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index e6357473..0987bbf9 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -7,13 +7,14 @@ APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '/', 'o'}; APRSTelemMsg msg(header); APRSCmdMsg cmd(header); -RadioSettings settings = {915.0, 0x02, 0x01, &hardware_spi, 10, 31, 32}; +RadioSettings settings = {433, 0x02, 0x01, &hardware_spi, 10, 31, 32}; RFM69HCW radio(&settings); void setup() { delay(2000); // Delay to allow the serial monitor to connect + if (!radio.init()) Serial.println("Radio failed to initialize"); else diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h index 2f15c74c..68e8cda9 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h @@ -12,6 +12,7 @@ namespace radioHandler { void processCmdData(APRSCmdMsg &cmd, APRSCmdData &old, APRSCmdData ¤tCmdData, int time) { + bb.aonoff(BUZZER, 100, 2); char log[100]; if (cmd.data.Launch != old.Launch && cmd.data.Launch >= 0) { diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index b2f43beb..32276d3e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -18,7 +18,7 @@ BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 -RadioSettings settings = {915.0, 0x01, 0x02, &hardware_spi, 10, 31, 32}; +RadioSettings settings = {433, 0x01, 0x02, &hardware_spi, 10, 31, 32}; RFM69HCW radio(&settings); APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '^', 'M'}; APRSCmdData currentCmdData = {800000, 800000, 800000, false}; @@ -38,8 +38,8 @@ static double last = 0; // for better timing than "delay(100)" // BlinkBuzz setup int BUZZER = 33; int LED = LED_BUILTIN; -int allowedPins[] = {LED}; -BlinkBuzz bb(allowedPins, 1, true); +int allowedPins[] = {LED, BUZZER}; +BlinkBuzz bb(allowedPins, 2, true); // Free memory debug function extern unsigned long _heap_start; From a515fca4a488a008bbeb27481b017e85009a6698 Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 19 Jun 2024 00:45:23 -0400 Subject: [PATCH 38/41] test --- .../src/GroundStationReceiver/main.cpp | 6 +++--- .../23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp | 1 + Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp | 4 ++-- 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index 0987bbf9..e99eadb8 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -7,7 +7,7 @@ APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '/', 'o'}; APRSTelemMsg msg(header); APRSCmdMsg cmd(header); -RadioSettings settings = {433, 0x02, 0x01, &hardware_spi, 10, 31, 32}; +RadioSettings settings = {433.78, 0x02, 0x01, &hardware_spi, 15, 16, 14}; RFM69HCW radio(&settings); @@ -22,8 +22,8 @@ void setup() // Test Case for Demo Purposes cmd.data.MinutesUntilPowerOn = 0; - cmd.data.MinutesUntilDataRecording = 1; - cmd.data.MinutesUntilVideoStart = 2; + cmd.data.MinutesUntilDataRecording = -1; + cmd.data.MinutesUntilVideoStart = -2; cmd.data.Launch = false; } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index 810f254f..5b434431 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -173,6 +173,7 @@ bool RFM69HCW::dequeueReceive(uint8_t *message) inc(recvBuffer.head); // Empty the buffer up to the length of the expected message copyFromBuffer(recvBuffer, message, len); + Serial.write(message, len); return true; } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 32276d3e..abbd0608 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -18,7 +18,7 @@ BNO055 bno(13, 12); // I2C Address 0x29 BMP390 bmp(13, 12); // I2C Address 0x77 MAX_M10S gps(13, 12, 0x42); // I2C Address 0x42 -RadioSettings settings = {433, 0x01, 0x02, &hardware_spi, 10, 31, 32}; +RadioSettings settings = {433.78, 0x01, 0x02, &hardware_spi, 10, 31, 32}; RFM69HCW radio(&settings); APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '^', 'M'}; APRSCmdData currentCmdData = {800000, 800000, 800000, false}; @@ -128,7 +128,7 @@ void loop() last = time; computer.updateState(); - recordLogData(INFO, computer.getStateString(), TO_USB); + //recordLogData(INFO, computer.getStateString(), TO_USB); // Send Telemetry Data if (time - radioTimer >= 1000) From ef8eeb8584bf39b5d7b2eb19ecd1050b96948e3c Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 19 Jun 2024 01:31:04 -0600 Subject: [PATCH 39/41] completely fixed 100 percent except not haha gotcha --- .../Code/Teensy-Based Avionics/platformio.ini | 1 + .../src/GroundStationReceiver/main.cpp | 37 +++++++++++++++---- .../src/Radio/RadioHandler.h | 23 +++++++++--- .../Code/Teensy-Based Avionics/src/State.cpp | 2 +- .../Code/Teensy-Based Avionics/src/main.cpp | 2 +- 5 files changed, 51 insertions(+), 14 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini index 1792013a..3d46ab6b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/platformio.ini @@ -73,6 +73,7 @@ build_flags = -Wno-unknown-pragmas lib_compat_mode = strict lib_deps = adafruit/Adafruit BNO055@^1.6.3 ; For the imumaths library + https://github.com/DrewBrandt/BlinkBuzz.git@^1.0.2 check_src_filters = -<*> + + + - check_flags = cppcheck: --suppressions-list=cppcheck-suppressions.txt -j 12 \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index e99eadb8..40ecb037 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -3,6 +3,7 @@ #include #include "../Radio/RFM69HCW.h" #include "../Radio/APRS/APRSCmdMsg.h" +#include APRSHeader header = {"KC3UTM", "APRS", "WIDE1-1", '/', 'o'}; APRSTelemMsg msg(header); @@ -10,24 +11,25 @@ APRSCmdMsg cmd(header); RadioSettings settings = {433.78, 0x02, 0x01, &hardware_spi, 15, 16, 14}; RFM69HCW radio(&settings); - +int arr[] = {LED_BUILTIN, 33}; +BlinkBuzz bb(arr, 1, true); void setup() { + delay(2000); // Delay to allow the serial monitor to connect - + if (!radio.init()) Serial.println("Radio failed to initialize"); else Serial.println("Radio initialized"); - // Test Case for Demo Purposes + // Test Case for Demo Purposes cmd.data.MinutesUntilPowerOn = 0; cmd.data.MinutesUntilDataRecording = -1; cmd.data.MinutesUntilVideoStart = -2; cmd.data.Launch = false; } - int counter = 1; void loop() { @@ -39,14 +41,35 @@ void loop() aprsToSerial::encodeAPRSForSerial(msg, buffer, 255, radio.RSSI()); Serial.println(buffer); } - if(counter % 50 == 0) // Send a command every 50x a message is received (or every 25 seconds) + if (counter % 50 == 0) // Send a command every 50x a message is received (or every 25 seconds) radio.enqueueSend(&cmd); - if(counter == 190) // Send a command after 190x a message is received (or after 95 seconds) to launch the rocket + if (counter == 190) // Send a command after 190x a message is received (or after 95 seconds) to launch the rocket { cmd.data.Launch = !cmd.data.Launch; radio.enqueueSend(&cmd); } - counter++; + } + if (Serial.available()) + { + char buffer[255]; + Serial.readBytesUntil('\n', buffer, 255); + char boolStr[6]; // "true" or "false" (max length 5 + 1 for null terminator) + + // Parse the input string + sscanf(buffer, "%d,%d,%d,%5s", &cmd.data.MinutesUntilPowerOn, &cmd.data.MinutesUntilVideoStart, &cmd.data.MinutesUntilDataRecording, boolStr); + + // Convert the string "true"/"false" to a boolean value + if (strcmp(boolStr, "true") == 0) + { + cmd.data.Launch = true; + } + else if (strcmp(boolStr, "false") == 0) + { + cmd.data.Launch = false; + } + + // Send the command + radio.enqueueSend(&cmd); } } \ No newline at end of file diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h index 68e8cda9..2fbd0739 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RadioHandler.h @@ -14,40 +14,53 @@ namespace radioHandler { bb.aonoff(BUZZER, 100, 2); char log[100]; - if (cmd.data.Launch != old.Launch && cmd.data.Launch >= 0) + if (cmd.data.Launch > 0) { snprintf(log, 100, "Launch Command Changed to %d.", cmd.data.Launch); recordLogData(INFO, log); currentCmdData.Launch = cmd.data.Launch; } - if (cmd.data.MinutesUntilPowerOn != old.MinutesUntilPowerOn && cmd.data.MinutesUntilPowerOn >= 0) + if ( cmd.data.MinutesUntilPowerOn >= 0) { snprintf(log, 100, "Power On Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilPowerOn, (int)(currentCmdData.MinutesUntilPowerOn - time) / 60000); recordLogData(INFO, log); currentCmdData.MinutesUntilPowerOn = cmd.data.MinutesUntilPowerOn * 60 * 1000 + time; } - if (cmd.data.MinutesUntilVideoStart != old.MinutesUntilVideoStart && cmd.data.MinutesUntilVideoStart >= 0) + if (cmd.data.MinutesUntilVideoStart >= 0) { snprintf(log, 100, "Video Start Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilVideoStart, (int)(currentCmdData.MinutesUntilVideoStart - time) / 60000); recordLogData(INFO, log); currentCmdData.MinutesUntilVideoStart = cmd.data.MinutesUntilVideoStart * 60 * 1000 + time; } - if (cmd.data.MinutesUntilDataRecording != old.MinutesUntilDataRecording && cmd.data.MinutesUntilDataRecording >= 0) + if (cmd.data.MinutesUntilDataRecording >= 0) { snprintf(log, 100, "Data Recording Time Changed: %d with %d minutes remaining.", cmd.data.MinutesUntilDataRecording, (int)(currentCmdData.MinutesUntilDataRecording - time) / 60000); recordLogData(INFO, log); currentCmdData.MinutesUntilDataRecording = cmd.data.MinutesUntilDataRecording * 60 * 1000 + time; } + // if(currentCmdData.Reset) + // { + // recordLogData(INFO, "Reset Command Received. Restarting Flight Computer."); + // currentCmdData.Reset = true; + // } } void processCurrentCmdData(APRSCmdData ¤tCmdData, State &computer, Pi &rpi, int time) { + // if(currentCmdData.Reset) + // { + // computer.init(); + // computer.launch(); + // rpi.setOn(true); + // rpi.setRecording(true); + // computer.setRecordOwnFlightData(true); + // currentCmdData.Reset = false; + // } if (currentCmdData.Launch && computer.getStageNum() == 0) { recordLogData(INFO, "Launch Command Received. Launching Rocket."); computer.launch(); } - if (time > currentCmdData.MinutesUntilPowerOn && !rpi.isOn()) { recordLogData(INFO, "Power On RPI Time Reached. Turning on Raspberry Pi."); diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index 9a4eb924..f198165b 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -32,7 +32,7 @@ State::State(bool useKalmanFilter, bool stateRecordsOwnFlightData) /// - recordOwnFlightData = false; // For radio testing. Will not record own data unless told to do so or if it detects a launch. + // recordOwnFlightData = false; // For radio testing. Will not record own data unless told to do so or if it detects a launch. /// diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index abbd0608..4cfa52fe 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -39,7 +39,7 @@ static double last = 0; // for better timing than "delay(100)" int BUZZER = 33; int LED = LED_BUILTIN; int allowedPins[] = {LED, BUZZER}; -BlinkBuzz bb(allowedPins, 2, true); +BlinkBuzz bb(allowedPins, 1, true); // Free memory debug function extern unsigned long _heap_start; From 7ad0ccd99f69641d347ef4ba09485e6147d89bf5 Mon Sep 17 00:00:00 2001 From: Varun Unnithan Date: Wed, 19 Jun 2024 03:31:48 -0400 Subject: [PATCH 40/41] Changed sending format --- .../src/GroundStationReceiver/EncodeAPRSForSerial.h | 6 +++--- .../23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp | 1 - 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index debcd07d..c272af4f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -20,7 +20,7 @@ namespace aprsToSerial */ void encodeAPRSForSerial(const APRSTelemMsg &msg, char *buffer, size_t buffer_size, int RSSI) { - char prefix[8] = "s\r\n"; + char prefix[8] = ""; char header[100]; snprintf(header, 100, @@ -39,10 +39,10 @@ namespace aprsToSerial char flags[5]; encodeFlags(msg, flags, 5); - char suffix[10] = "e\r\n"; + char suffix[10] = "!e"; // format: s\r\nSource:CALLSIGN,Destination:TOCALL,Path:PATH,Type:Position Without Timestamp,Data:!DDMM.MM[NS][OVERLAY]DDDMM.MM[WE][hhh/sss/A=DDDDDD/S[s]/zzz/yyy/xxx/fff,RSSI:RSSI\r\ne\r\n snprintf(buffer, buffer_size, - "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d/%s,RSSI:%03d\r\n%s", + "%s%sData:!%s%c%03d/%03d/%s/S%d/%03d/%03d/%03d/%s,RSSI:%03d%s", prefix, header, latLong, diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index 5b434431..810f254f 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -173,7 +173,6 @@ bool RFM69HCW::dequeueReceive(uint8_t *message) inc(recvBuffer.head); // Empty the buffer up to the length of the expected message copyFromBuffer(recvBuffer, message, len); - Serial.write(message, len); return true; } From 0cc5cf778aef9d19121e135fa90e5401e5ea8c9d Mon Sep 17 00:00:00 2001 From: Drew Brandt Date: Wed, 19 Jun 2024 05:44:22 -0600 Subject: [PATCH 41/41] launch ready --- .../GroundStationReceiver/EncodeAPRSForSerial.h | 1 + .../src/GroundStationReceiver/main.cpp | 16 ++++++++++------ .../Teensy-Based Avionics/src/Radio/RFM69HCW.cpp | 1 - .../Code/Teensy-Based Avionics/src/State.cpp | 6 +++--- .../23-24/Code/Teensy-Based Avionics/src/State.h | 3 ++- .../Code/Teensy-Based Avionics/src/main.cpp | 9 ++++----- 6 files changed, 20 insertions(+), 16 deletions(-) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h index c272af4f..dabc2c7a 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/EncodeAPRSForSerial.h @@ -56,6 +56,7 @@ namespace aprsToSerial flags, RSSI, suffix); + Serial.println(buffer); } void encodeLatLong(const APRSTelemMsg &msg, char *buffer, size_t buffer_size) diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp index 40ecb037..8556a7a6 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/GroundStationReceiver/main.cpp @@ -33,6 +33,7 @@ void setup() int counter = 1; void loop() { + delay(5); if (radio.update()) { if (radio.dequeueReceive(&msg)) @@ -40,16 +41,19 @@ void loop() char buffer[255]; aprsToSerial::encodeAPRSForSerial(msg, buffer, 255, radio.RSSI()); Serial.println(buffer); + counter = 0; } - if (counter % 50 == 0) // Send a command every 50x a message is received (or every 25 seconds) - radio.enqueueSend(&cmd); - - if (counter == 190) // Send a command after 190x a message is received (or after 95 seconds) to launch the rocket + } + else// reset the radio if we havent heard anything in a while + { + if (counter == 15000) { - cmd.data.Launch = !cmd.data.Launch; - radio.enqueueSend(&cmd); + radio.init(); + counter = 0; } } + counter ++; + if (Serial.available()) { char buffer[255]; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp index 810f254f..885fb80e 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/Radio/RFM69HCW.cpp @@ -131,7 +131,6 @@ bool RFM69HCW::enqueueSend(const uint8_t *message, uint8_t len) inc(sendBuffer.tail); copyToBuffer(sendBuffer, message, len); - return true; } diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp index f198165b..8f20749c 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.cpp @@ -407,7 +407,7 @@ void State::determineStage() if (stageNumber == 0 && (sensorOK(imu) || sensorOK(baro)) && (sensorOK(imu) ? accelerationMagnitude > 25 : true) && - (sensorOK(baro) ? baro->getRelAltFt() > 60 : true)) + (sensorOK(baro) ? baro->getRelAltFt() > 30 : true)) // if we are in preflight AND // we have either the IMU OR the barometer AND // imu is ok AND the accel Magnitude is greater than 25 ft/s^2 OR imu is not ok AND @@ -418,7 +418,7 @@ void State::determineStage() recordLogData(INFO, "Launch detected."); launch(); } // TODO: Add checks for each sensor being ok and decide what to do if they aren't. - else if (stageNumber == 1 && accelerationMagnitude < 10) + else if (stageNumber == 1 && accelerationMagnitude < 15) { bb.aonoff(BUZZER, 200, 2); timePreviousStage = timeAbsolute; @@ -442,7 +442,7 @@ void State::determineStage() timePreviousStage = timeAbsolute; recordLogData(INFO, "Main parachute conditions detected."); } - else if (stageNumber == 4 && baroVelocity > -1 && baro->getRelAltFt() < 66 && timeSinceLaunch > 15) + else if (stageNumber == 4 && baroVelocity > -3 && baro->getRelAltFt() < 66 && timeSinceLaunch > 15) { bb.aonoff(BUZZER, 200, 5); timePreviousStage = timeAbsolute; diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h index 0e56e276..a49903b2 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/State.h @@ -24,6 +24,8 @@ class State // stateRecordsOwnData: whether or not the state should call recordFlightData() itself. If false, other funcitons must call recordFlightData() to record the state's data. explicit State(bool useKalmanFilter = true, bool stateRecordsOwnData = true); ~State(); + + double baroVelocity; // in m/s // to be called after all applicable sensors have been added. // Returns false if any sensor failed to init. check data log for failed sensor. Disables sensor if failed. @@ -104,7 +106,6 @@ class State imu::Vector<3> velocity; // in m/s imu::Vector<3> acceleration; // in m/s^2 imu::Quaternion orientation; // in quaternion - double baroVelocity; // in m/s double baroOldAltitude; // in m double headingAngle; // in degrees diff --git a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp index 4cfa52fe..2f9af4d3 100644 --- a/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp +++ b/Spaceport/23-24/Code/Teensy-Based Avionics/src/main.cpp @@ -39,7 +39,7 @@ static double last = 0; // for better timing than "delay(100)" int BUZZER = 33; int LED = LED_BUILTIN; int allowedPins[] = {LED, BUZZER}; -BlinkBuzz bb(allowedPins, 1, true); +BlinkBuzz bb(allowedPins, 2, true); // Free memory debug function extern unsigned long _heap_start; @@ -58,7 +58,6 @@ void FreeMem() void setup() { - bb.onoff(BUZZER, 100, 4, 100); recordLogData(INFO, "Initializing Avionics System. 5 second delay to prevent unnecessary file generation.", TO_USB); // delay(5000); @@ -128,10 +127,10 @@ void loop() last = time; computer.updateState(); - //recordLogData(INFO, computer.getStateString(), TO_USB); - + recordLogData(INFO, computer.getStateString(), TO_USB); + Serial.println(computer.baroVelocity); // Send Telemetry Data - if (time - radioTimer >= 1000) + if (time - radioTimer >= 500) { computer.fillAPRSData(telem.data);