From a7258fad641b4afb9feff12b67256fca8b70be91 Mon Sep 17 00:00:00 2001 From: Honghyun Date: Tue, 4 Apr 2023 13:53:15 +0900 Subject: [PATCH 1/7] FastSyncRead, FastBulkRead implementation --- c++/include/dynamixel_sdk/dynamixel_sdk.h | 2 + c++/include/dynamixel_sdk/group_bulk_read.h | 39 ++---- c++/include/dynamixel_sdk/group_bulk_write.h | 37 ++---- .../dynamixel_sdk/group_fast_bulk_read.h | 48 +++++++ .../dynamixel_sdk/group_fast_sync_read.h | 45 +++++++ c++/include/dynamixel_sdk/group_handler.h | 57 +++++++++ c++/include/dynamixel_sdk/group_sync_read.h | 38 ++---- c++/include/dynamixel_sdk/group_sync_write.h | 38 ++---- c++/include/dynamixel_sdk/packet_handler.h | 26 ++-- .../dynamixel_sdk/protocol1_packet_handler.h | 5 +- .../dynamixel_sdk/protocol2_packet_handler.h | 5 +- c++/src/dynamixel_sdk/group_bulk_read.cpp | 9 +- c++/src/dynamixel_sdk/group_bulk_write.cpp | 5 +- .../dynamixel_sdk/group_fast_bulk_read.cpp | 121 ++++++++++++++++++ .../dynamixel_sdk/group_fast_sync_read.cpp | 98 ++++++++++++++ c++/src/dynamixel_sdk/group_handler.cpp | 39 ++++++ c++/src/dynamixel_sdk/group_sync_read.cpp | 7 +- c++/src/dynamixel_sdk/group_sync_write.cpp | 5 +- .../protocol1_packet_handler.cpp | 12 +- .../protocol2_packet_handler.cpp | 69 +++++++++- 20 files changed, 552 insertions(+), 153 deletions(-) create mode 100644 c++/include/dynamixel_sdk/group_fast_bulk_read.h create mode 100644 c++/include/dynamixel_sdk/group_fast_sync_read.h create mode 100644 c++/include/dynamixel_sdk/group_handler.h create mode 100644 c++/src/dynamixel_sdk/group_fast_bulk_read.cpp create mode 100644 c++/src/dynamixel_sdk/group_fast_sync_read.cpp create mode 100644 c++/src/dynamixel_sdk/group_handler.cpp diff --git a/c++/include/dynamixel_sdk/dynamixel_sdk.h b/c++/include/dynamixel_sdk/dynamixel_sdk.h index 9e3bc7f1..ff0a121d 100644 --- a/c++/include/dynamixel_sdk/dynamixel_sdk.h +++ b/c++/include/dynamixel_sdk/dynamixel_sdk.h @@ -27,6 +27,8 @@ #include "group_bulk_write.h" #include "group_sync_read.h" #include "group_sync_write.h" +#include "group_fast_sync_read.h" +#include "group_fast_bulk_read.h" #include "packet_handler.h" #include "port_handler.h" diff --git a/c++/include/dynamixel_sdk/group_bulk_read.h b/c++/include/dynamixel_sdk/group_bulk_read.h index 624c00de..f2041e45 100644 --- a/c++/include/dynamixel_sdk/group_bulk_read.h +++ b/c++/include/dynamixel_sdk/group_bulk_read.h @@ -23,10 +23,9 @@ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_H_ -#include -#include #include "port_handler.h" #include "packet_handler.h" +#include "group_handler.h" namespace dynamixel { @@ -34,26 +33,18 @@ namespace dynamixel //////////////////////////////////////////////////////////////////////////////// /// @brief The class for reading multiple Dynamixel data from different addresses with different lengths at once //////////////////////////////////////////////////////////////////////////////// -class WINDECLSPEC GroupBulkRead +class WINDECLSPEC GroupBulkRead : public GroupHandler { - private: - PortHandler *port_; - PacketHandler *ph_; +protected: + std::map address_list_; // + std::map length_list_; // + std::map error_list_; // - std::vector id_list_; - std::map address_list_; // - std::map length_list_; // - std::map data_list_; // - std::map error_list_; // + bool last_result_; - bool last_result_; - bool is_param_changed_; + void makeParam(); - uint8_t *param_; - - void makeParam(); - - public: +public: //////////////////////////////////////////////////////////////////////////////// /// @brief The function that Initializes instance for Bulk Read /// @param port PortHandler instance @@ -66,18 +57,6 @@ class WINDECLSPEC GroupBulkRead //////////////////////////////////////////////////////////////////////////////// ~GroupBulkRead() { clearParam(); } - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PortHandler instance - /// @return PortHandler instance - //////////////////////////////////////////////////////////////////////////////// - PortHandler *getPortHandler() { return port_; } - - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PacketHandler instance - /// @return PacketHandler instance - //////////////////////////////////////////////////////////////////////////////// - PacketHandler *getPacketHandler() { return ph_; } - //////////////////////////////////////////////////////////////////////////////// /// @brief The function that adds id, start_address, data_length to the Bulk Read list /// @param id Dynamixel ID diff --git a/c++/include/dynamixel_sdk/group_bulk_write.h b/c++/include/dynamixel_sdk/group_bulk_write.h index f3c2af2b..69914ea7 100644 --- a/c++/include/dynamixel_sdk/group_bulk_write.h +++ b/c++/include/dynamixel_sdk/group_bulk_write.h @@ -23,10 +23,9 @@ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_ -#include -#include #include "port_handler.h" #include "packet_handler.h" +#include "group_handler.h" namespace dynamixel { @@ -34,25 +33,17 @@ namespace dynamixel //////////////////////////////////////////////////////////////////////////////// /// @brief The class for writing multiple Dynamixel data from different addresses with different lengths at once //////////////////////////////////////////////////////////////////////////////// -class WINDECLSPEC GroupBulkWrite +class WINDECLSPEC GroupBulkWrite : public GroupHandler { - private: - PortHandler *port_; - PacketHandler *ph_; +private: + std::map address_list_; // + std::map length_list_; // - std::vector id_list_; - std::map address_list_; // - std::map length_list_; // - std::map data_list_; // + uint16_t param_length_; - bool is_param_changed_; + void makeParam(); - uint8_t *param_; - uint16_t param_length_; - - void makeParam(); - - public: +public: //////////////////////////////////////////////////////////////////////////////// /// @brief The function that Initializes instance for Bulk Write /// @param port PortHandler instance @@ -65,18 +56,6 @@ class WINDECLSPEC GroupBulkWrite //////////////////////////////////////////////////////////////////////////////// ~GroupBulkWrite() { clearParam(); } - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PortHandler instance - /// @return PortHandler instance - //////////////////////////////////////////////////////////////////////////////// - PortHandler *getPortHandler() { return port_; } - - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PacketHandler instance - /// @return PacketHandler instance - //////////////////////////////////////////////////////////////////////////////// - PacketHandler *getPacketHandler() { return ph_; } - //////////////////////////////////////////////////////////////////////////////// /// @brief The function that adds id, start_address, data_length to the Bulk Write list /// @param id Dynamixel ID diff --git a/c++/include/dynamixel_sdk/group_fast_bulk_read.h b/c++/include/dynamixel_sdk/group_fast_bulk_read.h new file mode 100644 index 00000000..78ffe2b4 --- /dev/null +++ b/c++/include/dynamixel_sdk/group_fast_bulk_read.h @@ -0,0 +1,48 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +//////////////////////////////////////////////////////////////////////////////// +/// @file The file for Dynamixel Fast Bulk Read +/// @author Honghyun Kim +//////////////////////////////////////////////////////////////////////////////// + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPFASTBULKREAD_H +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPFASTBULKREAD_H + + +#include "group_bulk_read.h" + +namespace dynamixel +{ + +class WINDECLSPEC GroupFastBulkRead : public GroupBulkRead +{ +public: + GroupFastBulkRead(PortHandler *port, PacketHandler *ph); + ~GroupFastBulkRead() { clearParam(); } + + int txPacket(); + int rxPacket(); + int txRxPacket(); + +private: + void makeParam(); +}; + +} + + +#endif // DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPFASTBULKREAD_H diff --git a/c++/include/dynamixel_sdk/group_fast_sync_read.h b/c++/include/dynamixel_sdk/group_fast_sync_read.h new file mode 100644 index 00000000..a5b56a07 --- /dev/null +++ b/c++/include/dynamixel_sdk/group_fast_sync_read.h @@ -0,0 +1,45 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +//////////////////////////////////////////////////////////////////////////////// +/// @file The file for Dynamixel Fast Sync Read +/// @author Honghyun Kim +//////////////////////////////////////////////////////////////////////////////// + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPFASTSYNCREAD_H +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPFASTSYNCREAD_H + + +#include "group_sync_read.h" + +namespace dynamixel +{ + +class WINDECLSPEC GroupFastSyncRead : public GroupSyncRead +{ +public: + GroupFastSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length); + ~GroupFastSyncRead() { clearParam(); } + + int txPacket(); + int rxPacket(); + int txRxPacket(); +}; + +} + + +#endif // DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPFASTSYNCREAD_H diff --git a/c++/include/dynamixel_sdk/group_handler.h b/c++/include/dynamixel_sdk/group_handler.h new file mode 100644 index 00000000..1ad5e711 --- /dev/null +++ b/c++/include/dynamixel_sdk/group_handler.h @@ -0,0 +1,57 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +//////////////////////////////////////////////////////////////////////////////// +/// @file The file for Group Handler +/// @author Honghyun Kim +//////////////////////////////////////////////////////////////////////////////// + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPHANDLER_H +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPHANDLER_H + + +#include +#include +#include "port_handler.h" +#include "packet_handler.h" + +namespace dynamixel +{ + +class WINDECLSPEC GroupHandler +{ +public: + GroupHandler(PortHandler *port, PacketHandler *ph); + + PortHandler *getPortHandler() { return port_; } + PacketHandler *getPacketHandler() { return ph_; } + +protected: + PortHandler *port_; + PacketHandler *ph_; + + std::vector id_list_; + std::map data_list_; // + + bool is_param_changed_; + + uint8_t *param_; +}; + +} + + +#endif // DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPHANDLER_H diff --git a/c++/include/dynamixel_sdk/group_sync_read.h b/c++/include/dynamixel_sdk/group_sync_read.h index 0b934f60..19a36dd5 100644 --- a/c++/include/dynamixel_sdk/group_sync_read.h +++ b/c++/include/dynamixel_sdk/group_sync_read.h @@ -23,10 +23,9 @@ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCREAD_H_ -#include -#include #include "port_handler.h" #include "packet_handler.h" +#include "group_handler.h" namespace dynamixel { @@ -34,26 +33,19 @@ namespace dynamixel //////////////////////////////////////////////////////////////////////////////// /// @brief The class for reading multiple Dynamixel data from same address with same length at once //////////////////////////////////////////////////////////////////////////////// -class WINDECLSPEC GroupSyncRead +class WINDECLSPEC GroupSyncRead : public GroupHandler { - private: - PortHandler *port_; - PacketHandler *ph_; +protected: + std::map error_list_; // - std::vector id_list_; - std::map data_list_; // - std::map error_list_; // + bool last_result_; - bool last_result_; - bool is_param_changed_; + uint16_t start_address_; + uint16_t data_length_; - uint8_t *param_; - uint16_t start_address_; - uint16_t data_length_; + void makeParam(); - void makeParam(); - - public: +public: //////////////////////////////////////////////////////////////////////////////// /// @brief The function that Initializes instance for Sync Read /// @param port PortHandler instance @@ -68,18 +60,6 @@ class WINDECLSPEC GroupSyncRead //////////////////////////////////////////////////////////////////////////////// ~GroupSyncRead() { clearParam(); } - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PortHandler instance - /// @return PortHandler instance - //////////////////////////////////////////////////////////////////////////////// - PortHandler *getPortHandler() { return port_; } - - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PacketHandler instance - /// @return PacketHandler instance - //////////////////////////////////////////////////////////////////////////////// - PacketHandler *getPacketHandler() { return ph_; } - //////////////////////////////////////////////////////////////////////////////// /// @brief The function that adds id, start_address, data_length to the Sync Read list /// @param id Dynamixel ID diff --git a/c++/include/dynamixel_sdk/group_sync_write.h b/c++/include/dynamixel_sdk/group_sync_write.h index 81f5e8ce..4059e8a9 100644 --- a/c++/include/dynamixel_sdk/group_sync_write.h +++ b/c++/include/dynamixel_sdk/group_sync_write.h @@ -23,10 +23,9 @@ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_H_ -#include -#include #include "port_handler.h" #include "packet_handler.h" +#include "group_handler.h" namespace dynamixel { @@ -34,24 +33,15 @@ namespace dynamixel //////////////////////////////////////////////////////////////////////////////// /// @brief The class for writing multiple Dynamixel data from same address with same length at once //////////////////////////////////////////////////////////////////////////////// -class WINDECLSPEC GroupSyncWrite +class WINDECLSPEC GroupSyncWrite : public GroupHandler { - private: - PortHandler *port_; - PacketHandler *ph_; +private: + uint16_t start_address_; + uint16_t data_length_; - std::vector id_list_; - std::map data_list_; // + void makeParam(); - bool is_param_changed_; - - uint8_t *param_; - uint16_t start_address_; - uint16_t data_length_; - - void makeParam(); - - public: +public: //////////////////////////////////////////////////////////////////////////////// /// @brief The function that Initializes instance for Sync Write /// @param port PortHandler instance @@ -66,18 +56,6 @@ class WINDECLSPEC GroupSyncWrite //////////////////////////////////////////////////////////////////////////////// ~GroupSyncWrite() { clearParam(); } - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PortHandler instance - /// @return PortHandler instance - //////////////////////////////////////////////////////////////////////////////// - PortHandler *getPortHandler() { return port_; } - - //////////////////////////////////////////////////////////////////////////////// - /// @brief The function that returns PacketHandler instance - /// @return PacketHandler instance - //////////////////////////////////////////////////////////////////////////////// - PacketHandler *getPacketHandler() { return ph_; } - //////////////////////////////////////////////////////////////////////////////// /// @brief The function that adds id, start_address, data_length to the Sync Write list /// @param id Dynamixel ID @@ -107,7 +85,7 @@ class WINDECLSPEC GroupSyncWrite //////////////////////////////////////////////////////////////////////////////// /// @brief The function that clears the Sync Write list //////////////////////////////////////////////////////////////////////////////// - void clearParam (); + void clearParam(); //////////////////////////////////////////////////////////////////////////////// /// @brief The function that transmits the Sync Write instruction packet which might be constructed by GroupSyncWrite::addParam function diff --git a/c++/include/dynamixel_sdk/packet_handler.h b/c++/include/dynamixel_sdk/packet_handler.h index 8b20e26f..c4491a7f 100644 --- a/c++/include/dynamixel_sdk/packet_handler.h +++ b/c++/include/dynamixel_sdk/packet_handler.h @@ -61,17 +61,20 @@ #define INST_STATUS 85 // 0x55 #define INST_SYNC_READ 130 // 0x82 #define INST_BULK_WRITE 147 // 0x93 +// Fast +const uint8_t INST_FAST_SYNC_READ = 0x8A; +const uint8_t INST_FAST_BULK_READ = 0x9A; // Communication Result -#define COMM_SUCCESS 0 // tx or rx packet communication success -#define COMM_PORT_BUSY -1000 // Port is busy (in use) -#define COMM_TX_FAIL -1001 // Failed transmit instruction packet -#define COMM_RX_FAIL -1002 // Failed get status packet -#define COMM_TX_ERROR -2000 // Incorrect instruction packet -#define COMM_RX_WAITING -3000 // Now recieving status packet -#define COMM_RX_TIMEOUT -3001 // There is no status packet -#define COMM_RX_CORRUPT -3002 // Incorrect status packet -#define COMM_NOT_AVAILABLE -9000 // +#define COMM_SUCCESS 0 // tx or rx packet communication success +#define COMM_PORT_BUSY (-1000) // Port is busy (in use) +#define COMM_TX_FAIL (-1001) // Failed transmit instruction packet +#define COMM_RX_FAIL (-1002) // Failed get status packet +#define COMM_TX_ERROR (-2000) // Incorrect instruction packet +#define COMM_RX_WAITING (-3000) // Now recieving status packet +#define COMM_RX_TIMEOUT (-3001) // There is no status packet +#define COMM_RX_CORRUPT (-3002) // Incorrect status packet +#define COMM_NOT_AVAILABLE (-9000) // namespace dynamixel { @@ -149,7 +152,7 @@ class WINDECLSPEC PacketHandler /// @return when rxpacket passes checksum test /// @return or COMM_RX_FAIL //////////////////////////////////////////////////////////////////////////////// - virtual int rxPacket (PortHandler *port, uint8_t *rxpacket) = 0; + virtual int rxPacket (PortHandler *port, uint8_t *rxpacket, bool skip_stuffing = false) = 0; //////////////////////////////////////////////////////////////////////////////// /// @brief The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time via PortHandler port @@ -587,6 +590,9 @@ class WINDECLSPEC PacketHandler /// @return communication results which come from PacketHandler::txRxPacket() //////////////////////////////////////////////////////////////////////////////// virtual int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length) = 0; + + virtual int fastSyncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0; + virtual int fastBulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length) = 0; }; } diff --git a/c++/include/dynamixel_sdk/protocol1_packet_handler.h b/c++/include/dynamixel_sdk/protocol1_packet_handler.h index 3dcbadd1..0502b63f 100644 --- a/c++/include/dynamixel_sdk/protocol1_packet_handler.h +++ b/c++/include/dynamixel_sdk/protocol1_packet_handler.h @@ -103,7 +103,7 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler /// @return when rxpacket passes checksum test /// @return or COMM_RX_FAIL //////////////////////////////////////////////////////////////////////////////// - int rxPacket (PortHandler *port, uint8_t *rxpacket); + int rxPacket (PortHandler *port, uint8_t *rxpacket, bool skip_stuffing = false); //////////////////////////////////////////////////////////////////////////////// /// @brief The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time via PortHandler port @@ -529,6 +529,9 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler /// @return COMM_NOT_AVAILABLE //////////////////////////////////////////////////////////////////////////////// int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length); + + int fastSyncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length); + int fastBulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length); }; } diff --git a/c++/include/dynamixel_sdk/protocol2_packet_handler.h b/c++/include/dynamixel_sdk/protocol2_packet_handler.h index b8bd8856..0fffed71 100644 --- a/c++/include/dynamixel_sdk/protocol2_packet_handler.h +++ b/c++/include/dynamixel_sdk/protocol2_packet_handler.h @@ -107,7 +107,7 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler /// @return when rxpacket passes checksum test /// @return or COMM_RX_FAIL //////////////////////////////////////////////////////////////////////////////// - int rxPacket (PortHandler *port, uint8_t *rxpacket); + int rxPacket (PortHandler *port, uint8_t *rxpacket, bool skip_stuffing = false); //////////////////////////////////////////////////////////////////////////////// /// @brief The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time via PortHandler port @@ -546,6 +546,9 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler /// @return communication results which come from Protocol2PacketHandler::txRxPacket() //////////////////////////////////////////////////////////////////////////////// int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length); + + int fastSyncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length); + int fastBulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length); }; } diff --git a/c++/src/dynamixel_sdk/group_bulk_read.cpp b/c++/src/dynamixel_sdk/group_bulk_read.cpp index edd1ad69..54340f4e 100644 --- a/c++/src/dynamixel_sdk/group_bulk_read.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_read.cpp @@ -33,11 +33,8 @@ using namespace dynamixel; GroupBulkRead::GroupBulkRead(PortHandler *port, PacketHandler *ph) - : port_(port), - ph_(ph), - last_result_(false), - is_param_changed_(false), - param_(0) + : GroupHandler(port, ph), + last_result_(false) { clearParam(); } @@ -233,4 +230,4 @@ bool GroupBulkRead::getError(uint8_t id, uint8_t* error) // if (last_result_ == false || error_list_.find(id) == error_list_.end()) return error[0] = error_list_[id][0]; -} \ No newline at end of file +} diff --git a/c++/src/dynamixel_sdk/group_bulk_write.cpp b/c++/src/dynamixel_sdk/group_bulk_write.cpp index 665378f2..63685a98 100644 --- a/c++/src/dynamixel_sdk/group_bulk_write.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_write.cpp @@ -32,10 +32,7 @@ using namespace dynamixel; GroupBulkWrite::GroupBulkWrite(PortHandler *port, PacketHandler *ph) - : port_(port), - ph_(ph), - is_param_changed_(false), - param_(0), + : GroupHandler(port, ph), param_length_(0) { clearParam(); diff --git a/c++/src/dynamixel_sdk/group_fast_bulk_read.cpp b/c++/src/dynamixel_sdk/group_fast_bulk_read.cpp new file mode 100644 index 00000000..0b8d92b7 --- /dev/null +++ b/c++/src/dynamixel_sdk/group_fast_bulk_read.cpp @@ -0,0 +1,121 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Honghyun Kim */ + +#include + +#if defined(__linux__) +#include "group_fast_bulk_read.h" +#elif defined(__APPLE__) +#include "group_fast_bulk_read.h" +#elif defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#include "group_fast_bulk_read.h" +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#include "../../include/dynamixel_sdk/group_fast_bulk_read.h" +#endif + +const int RXPACKET_MAX_LEN = 1024; +const int PKT_ID = 4; +const int PKT_PARAMETER0 = 8; + +using namespace dynamixel; + +GroupFastBulkRead::GroupFastBulkRead(PortHandler *port, PacketHandler *ph) + : GroupBulkRead(port, ph) +{ + clearParam(); +} + +void GroupFastBulkRead::makeParam() +{ + if ((1.0 == ph_->getProtocolVersion()) || (id_list_.empty())) + return; + + if (0 != param_) + delete[] param_; + param_ = 0; + + param_ = new uint8_t[id_list_.size() * 5]; // ID(1) + ADDR(2) + LENGTH(2) + + int idx = 0; + for (unsigned int i = 0; i < id_list_.size(); i++) { + uint8_t id = id_list_[i]; + param_[idx++] = id; // ID + param_[idx++] = DXL_LOBYTE(address_list_[id]); // ADDR_L + param_[idx++] = DXL_HIBYTE(address_list_[id]); // ADDR_H + param_[idx++] = DXL_LOBYTE(length_list_[id]); // LEN_L + param_[idx++] = DXL_HIBYTE(length_list_[id]); // LEN_H + } +} + +int GroupFastBulkRead::txPacket() +{ + if ((1.0 == ph_->getProtocolVersion()) || (id_list_.empty())) + return COMM_NOT_AVAILABLE; + + if ((true == is_param_changed_) || (0 == param_)) + makeParam(); + + return ph_->fastBulkReadTx(port_, param_, id_list_.size() * 5); +} + +int GroupFastBulkRead::rxPacket() +{ + last_result_ = false; + + if ((1.0 == ph_->getProtocolVersion()) || (id_list_.empty())) + return COMM_NOT_AVAILABLE; + + int count = id_list_.size(); + int result = COMM_RX_FAIL; + uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); + if (NULL == rxpacket) + return result; + + do { + result = ph_->rxPacket(port_, rxpacket, true); + } while ((COMM_SUCCESS == result) && (BROADCAST_ID != rxpacket[PKT_ID])); + + if ((COMM_SUCCESS == result) && (BROADCAST_ID == rxpacket[PKT_ID])) { + int index = PKT_PARAMETER0; + for (int i = 0; i < count; ++i) { + uint8_t id = id_list_[i]; + uint16_t length = length_list_[id]; + *error_list_[id] = (uint8_t)rxpacket[index]; + for (uint16_t s = 0; s < length; s++) { + data_list_[id][s] = rxpacket[index + 2 + s]; + } + index += (length + 4); + } + last_result_ = true; + } + + free(rxpacket); + return result; +} + +int GroupFastBulkRead::txRxPacket() +{ + if (1.0 == ph_->getProtocolVersion()) + return COMM_NOT_AVAILABLE; + + int result = txPacket(); + if (COMM_SUCCESS != result) + return result; + return rxPacket(); +} diff --git a/c++/src/dynamixel_sdk/group_fast_sync_read.cpp b/c++/src/dynamixel_sdk/group_fast_sync_read.cpp new file mode 100644 index 00000000..ef3635ef --- /dev/null +++ b/c++/src/dynamixel_sdk/group_fast_sync_read.cpp @@ -0,0 +1,98 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Honghyun Kim */ + +#include + +#if defined(__linux__) +#include "group_fast_sync_read.h" +#elif defined(__APPLE__) +#include "group_fast_sync_read.h" +#elif defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#include "group_fast_sync_read.h" +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#include "../../include/dynamixel_sdk/group_fast_sync_read.h" +#endif + +const int RXPACKET_MAX_LEN = 1024; +const int PKT_ID = 4; +const int PKT_PARAMETER0 = 8; + +using namespace dynamixel; + +GroupFastSyncRead::GroupFastSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length) + : GroupSyncRead(port, ph, start_address, data_length) +{ + clearParam(); +} + +int GroupFastSyncRead::txPacket() +{ + if ((1.0 == ph_->getProtocolVersion()) || (id_list_.empty())) + return COMM_NOT_AVAILABLE; + + if ((true == is_param_changed_) || (0 == param_)) + makeParam(); + + return ph_->fastSyncReadTx(port_, start_address_, data_length_, param_, (uint16_t)id_list_.size() * 1); +} + +int GroupFastSyncRead::rxPacket() +{ + last_result_ = false; + + if ((1.0 == ph_->getProtocolVersion()) || (id_list_.empty())) + return COMM_NOT_AVAILABLE; + + int count = id_list_.size(); + int result = COMM_RX_FAIL; + uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); + if (NULL == rxpacket) + return result; + + do { + result = ph_->rxPacket(port_, rxpacket, true); + } while ((COMM_SUCCESS == result) && (BROADCAST_ID != rxpacket[PKT_ID])); + + if ((COMM_SUCCESS == result) && (BROADCAST_ID == rxpacket[PKT_ID])) { + int index = PKT_PARAMETER0; + for (int i = 0; i < count; ++i) { + uint8_t id = id_list_[i]; + *error_list_[id] = (uint8_t)rxpacket[index]; + for (uint16_t s = 0; s < data_length_; s++) { + data_list_[id][s] = rxpacket[index + 2 + s]; + } + index += (data_length_ + 4); + } + last_result_ = true; + } + + free(rxpacket); + return result; +} + +int GroupFastSyncRead::txRxPacket() +{ + if (1.0 == ph_->getProtocolVersion()) + return COMM_NOT_AVAILABLE; + + int result = txPacket(); + if (COMM_SUCCESS != result) + return result; + return rxPacket(); +} diff --git a/c++/src/dynamixel_sdk/group_handler.cpp b/c++/src/dynamixel_sdk/group_handler.cpp new file mode 100644 index 00000000..5998de53 --- /dev/null +++ b/c++/src/dynamixel_sdk/group_handler.cpp @@ -0,0 +1,39 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Honghyun Kim */ + +#if defined(__linux__) +#include "group_handler.h" +#elif defined(__APPLE__) +#include "group_handler.h" +#elif defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#include "group_handler.h" +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#include "../../include/dynamixel_sdk/group_handler.h" +#endif + +using namespace dynamixel; + +GroupHandler::GroupHandler(PortHandler *port, PacketHandler *ph) + : port_(port), + ph_(ph), + is_param_changed_(false), + param_(0) +{ + +} diff --git a/c++/src/dynamixel_sdk/group_sync_read.cpp b/c++/src/dynamixel_sdk/group_sync_read.cpp index 79e5f3b8..a8e4e5e5 100644 --- a/c++/src/dynamixel_sdk/group_sync_read.cpp +++ b/c++/src/dynamixel_sdk/group_sync_read.cpp @@ -32,11 +32,8 @@ using namespace dynamixel; GroupSyncRead::GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length) - : port_(port), - ph_(ph), + : GroupHandler(port, ph), last_result_(false), - is_param_changed_(false), - param_(0), start_address_(start_address), data_length_(data_length) { @@ -202,4 +199,4 @@ bool GroupSyncRead::getError(uint8_t id, uint8_t* error) // if (ph_->getProtocolVersion() == 1.0 || last_result_ == false || error_list_.find(id) == error_list_.end()) return error[0] = error_list_[id][0]; -} \ No newline at end of file +} diff --git a/c++/src/dynamixel_sdk/group_sync_write.cpp b/c++/src/dynamixel_sdk/group_sync_write.cpp index 1202d472..b15c78a5 100644 --- a/c++/src/dynamixel_sdk/group_sync_write.cpp +++ b/c++/src/dynamixel_sdk/group_sync_write.cpp @@ -32,10 +32,7 @@ using namespace dynamixel; GroupSyncWrite::GroupSyncWrite(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length) - : port_(port), - ph_(ph), - is_param_changed_(false), - param_(0), + : GroupHandler(port, ph), start_address_(start_address), data_length_(data_length) { diff --git a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp index 668adfa3..324586e1 100644 --- a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp @@ -157,7 +157,7 @@ int Protocol1PacketHandler::txPacket(PortHandler *port, uint8_t *txpacket) return COMM_SUCCESS; } -int Protocol1PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket) +int Protocol1PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket, bool skip_stuffing) { int result = COMM_TX_FAIL; @@ -753,3 +753,13 @@ int Protocol1PacketHandler::bulkWriteTxOnly(PortHandler *port, uint8_t *param, u { return COMM_NOT_AVAILABLE; } + +int Protocol1PacketHandler::fastSyncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) +{ + return COMM_NOT_AVAILABLE; +} + +int Protocol1PacketHandler::fastBulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length) +{ + return COMM_NOT_AVAILABLE; +} diff --git a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp index 06dae1d2..ea05b143 100644 --- a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp @@ -304,7 +304,7 @@ int Protocol2PacketHandler::txPacket(PortHandler *port, uint8_t *txpacket) return COMM_SUCCESS; } -int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket) +int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket, bool skip_stuffing) { int result = COMM_TX_FAIL; @@ -328,7 +328,7 @@ int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket) if (idx == 0) // found at the beginning of the packet { if (rxpacket[PKT_RESERVED] != 0x00 || - rxpacket[PKT_ID] > 0xFC || +// rxpacket[PKT_ID] > 0xFC || // FAST protocol responds with a broadcast ID DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) > RXPACKET_MAX_LEN || rxpacket[PKT_INSTRUCTION] != 0x55) { @@ -413,7 +413,7 @@ int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket) } port->is_using_ = false; - if (result == COMM_SUCCESS) + if ((result == COMM_SUCCESS) && (false == skip_stuffing)) removeStuffing(rxpacket); return result; @@ -1076,3 +1076,66 @@ int Protocol2PacketHandler::bulkWriteTxOnly(PortHandler *port, uint8_t *param, u //delete[] txpacket; return result; } + +int Protocol2PacketHandler::fastSyncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) +{ + int result = COMM_TX_FAIL; + + uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3)); + // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + + if (NULL == txpacket) + return result; + + txpacket[PKT_ID] = BROADCAST_ID; + txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + txpacket[PKT_INSTRUCTION] = INST_FAST_SYNC_READ; + txpacket[PKT_PARAMETER0 + 0] = DXL_LOBYTE(start_address); + txpacket[PKT_PARAMETER0 + 1] = DXL_HIBYTE(start_address); + txpacket[PKT_PARAMETER0 + 2] = DXL_LOBYTE(data_length); + txpacket[PKT_PARAMETER0 + 3] = DXL_HIBYTE(data_length); + + for (uint16_t s = 0; s < param_length; s++) + txpacket[PKT_PARAMETER0 + 4 + s] = param[s]; + //memcpy(&txpacket[PKT_PARAMETER0+4], param, param_length); + + result = txPacket(port, txpacket); + if (COMM_SUCCESS == result) + port->setPacketTimeout((uint16_t)((11 + data_length) * param_length)); + + free(txpacket); + return result; +} + +int Protocol2PacketHandler::fastBulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length) +{ + int result = COMM_TX_FAIL; + + uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3)); + // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + + if (NULL == txpacket) + return result; + + txpacket[PKT_ID] = BROADCAST_ID; + txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H + txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H + txpacket[PKT_INSTRUCTION] = INST_FAST_BULK_READ; + + for (uint16_t s = 0; s < param_length; s++) + txpacket[PKT_PARAMETER0 + s] = param[s]; + //memcpy(&txpacket[PKT_PARAMETER0], param, param_length); + + result = txPacket(port, txpacket); + if (result == COMM_SUCCESS) { + int wait_length = 0; + for (uint16_t i = 0; i < param_length; i += 5) + wait_length += DXL_MAKEWORD(param[i + 3], param[i + 4]) + 10; + port->setPacketTimeout((uint16_t)wait_length); + } + + free(txpacket); + //delete[] txpacket; + return result; +} From f84b57c9cbe9b66b82ec4abb06785872c3edadda Mon Sep 17 00:00:00 2001 From: Honghyun Date: Fri, 21 Apr 2023 15:32:43 +0900 Subject: [PATCH 2/7] =?UTF-8?q?OpenRB-150=20=EC=A7=80=EC=9B=90?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- c++/include/dynamixel_sdk/packet_handler.h | 2 +- c++/include/dynamixel_sdk/port_handler.h | 2 +- .../dynamixel_sdk/port_handler_arduino.h | 2 +- c++/src/dynamixel_sdk/group_bulk_read.cpp | 2 +- c++/src/dynamixel_sdk/group_bulk_write.cpp | 2 +- c++/src/dynamixel_sdk/group_sync_read.cpp | 2 +- c++/src/dynamixel_sdk/group_sync_write.cpp | 2 +- c++/src/dynamixel_sdk/packet_handler.cpp | 2 +- c++/src/dynamixel_sdk/port_handler.cpp | 4 +-- .../dynamixel_sdk/port_handler_arduino.cpp | 26 +++++++++++-------- .../protocol1_packet_handler.cpp | 2 +- .../protocol2_packet_handler.cpp | 2 +- 12 files changed, 27 insertions(+), 23 deletions(-) diff --git a/c++/include/dynamixel_sdk/packet_handler.h b/c++/include/dynamixel_sdk/packet_handler.h index 8b20e26f..84e8cf77 100644 --- a/c++/include/dynamixel_sdk/packet_handler.h +++ b/c++/include/dynamixel_sdk/packet_handler.h @@ -22,7 +22,7 @@ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_ -#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include #define ERROR_PRINT SerialBT2.print diff --git a/c++/include/dynamixel_sdk/port_handler.h b/c++/include/dynamixel_sdk/port_handler.h index 63976c00..820e953b 100644 --- a/c++/include/dynamixel_sdk/port_handler.h +++ b/c++/include/dynamixel_sdk/port_handler.h @@ -32,7 +32,7 @@ #else #define WINDECLSPEC __declspec(dllimport) #endif -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #define WINDECLSPEC #endif diff --git a/c++/include/dynamixel_sdk/port_handler_arduino.h b/c++/include/dynamixel_sdk/port_handler_arduino.h index 78ddea93..cba5a9d8 100644 --- a/c++/include/dynamixel_sdk/port_handler_arduino.h +++ b/c++/include/dynamixel_sdk/port_handler_arduino.h @@ -22,7 +22,7 @@ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ -#if defined(ARDUINO) || defined(__OPENCR__) || defined (__OPENCM904__) +#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include #endif diff --git a/c++/src/dynamixel_sdk/group_bulk_read.cpp b/c++/src/dynamixel_sdk/group_bulk_read.cpp index edd1ad69..c48bf615 100644 --- a/c++/src/dynamixel_sdk/group_bulk_read.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_read.cpp @@ -26,7 +26,7 @@ #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT #include "group_bulk_read.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/group_bulk_read.h" #endif diff --git a/c++/src/dynamixel_sdk/group_bulk_write.cpp b/c++/src/dynamixel_sdk/group_bulk_write.cpp index 665378f2..43724f87 100644 --- a/c++/src/dynamixel_sdk/group_bulk_write.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_write.cpp @@ -25,7 +25,7 @@ #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT #include "group_bulk_write.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/group_bulk_write.h" #endif diff --git a/c++/src/dynamixel_sdk/group_sync_read.cpp b/c++/src/dynamixel_sdk/group_sync_read.cpp index 79e5f3b8..f52f8ece 100644 --- a/c++/src/dynamixel_sdk/group_sync_read.cpp +++ b/c++/src/dynamixel_sdk/group_sync_read.cpp @@ -25,7 +25,7 @@ #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT #include "group_sync_read.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/group_sync_read.h" #endif diff --git a/c++/src/dynamixel_sdk/group_sync_write.cpp b/c++/src/dynamixel_sdk/group_sync_write.cpp index 1202d472..6efa5b8c 100644 --- a/c++/src/dynamixel_sdk/group_sync_write.cpp +++ b/c++/src/dynamixel_sdk/group_sync_write.cpp @@ -25,7 +25,7 @@ #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT #include "group_sync_write.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/group_sync_write.h" #endif diff --git a/c++/src/dynamixel_sdk/packet_handler.cpp b/c++/src/dynamixel_sdk/packet_handler.cpp index c9267150..4fcf890b 100644 --- a/c++/src/dynamixel_sdk/packet_handler.cpp +++ b/c++/src/dynamixel_sdk/packet_handler.cpp @@ -29,7 +29,7 @@ #include "packet_handler.h" #include "protocol1_packet_handler.h" #include "protocol2_packet_handler.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/packet_handler.h" #include "../../include/dynamixel_sdk/protocol1_packet_handler.h" #include "../../include/dynamixel_sdk/protocol2_packet_handler.h" diff --git a/c++/src/dynamixel_sdk/port_handler.cpp b/c++/src/dynamixel_sdk/port_handler.cpp index 3054c855..7dc1ec4e 100644 --- a/c++/src/dynamixel_sdk/port_handler.cpp +++ b/c++/src/dynamixel_sdk/port_handler.cpp @@ -26,7 +26,7 @@ #define WINDLLEXPORT #include "port_handler.h" #include "port_handler_windows.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/port_handler.h" #include "../../include/dynamixel_sdk/port_handler_arduino.h" #endif @@ -41,7 +41,7 @@ PortHandler *PortHandler::getPortHandler(const char *port_name) return (PortHandler *)(new PortHandlerMac(port_name)); #elif defined(_WIN32) || defined(_WIN64) return (PortHandler *)(new PortHandlerWindows(port_name)); -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) return (PortHandler *)(new PortHandlerArduino(port_name)); #endif } diff --git a/c++/src/dynamixel_sdk/port_handler_arduino.cpp b/c++/src/dynamixel_sdk/port_handler_arduino.cpp index 07add9ad..9542ec54 100644 --- a/c++/src/dynamixel_sdk/port_handler_arduino.cpp +++ b/c++/src/dynamixel_sdk/port_handler_arduino.cpp @@ -16,7 +16,7 @@ /* Author: Ryu Woon Jung (Leon) */ -#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include @@ -27,6 +27,10 @@ #define DYNAMIXEL_SERIAL Serial3 #endif +#if defined (ARDUINO_OpenRB) +#define DYNAMIXEL_SERIAL Serial1 +#endif + #define LATENCY_TIMER 4 // msec (USB latency timer) using namespace dynamixel; @@ -40,7 +44,7 @@ PortHandlerArduino::PortHandlerArduino(const char *port_name) is_using_ = false; setPortName(port_name); -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) pinMode(BDPIN_DXL_PWR_EN, OUTPUT); setPowerOff(); @@ -74,7 +78,7 @@ PortHandlerArduino::PortHandlerArduino(const char *port_name) bool PortHandlerArduino::openPort() { -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) pinMode(BDPIN_DXL_PWR_EN, OUTPUT); setPowerOn(); @@ -92,7 +96,7 @@ void PortHandlerArduino::closePort() void PortHandlerArduino::clearPort() { int temp __attribute__((unused)); -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) while (DYNAMIXEL_SERIAL.available()) { temp = DYNAMIXEL_SERIAL.read(); @@ -136,7 +140,7 @@ int PortHandlerArduino::getBytesAvailable() { int bytes_available; -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) bytes_available = DYNAMIXEL_SERIAL.available(); #elif defined(__OPENCM904__) bytes_available = p_dxl_serial->available(); @@ -149,7 +153,7 @@ int PortHandlerArduino::readPort(uint8_t *packet, int length) { int rx_length; -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) rx_length = DYNAMIXEL_SERIAL.available(); #elif defined(__OPENCM904__) rx_length = p_dxl_serial->available(); @@ -160,7 +164,7 @@ int PortHandlerArduino::readPort(uint8_t *packet, int length) for (int i = 0; i < rx_length; i++) { -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) packet[i] = DYNAMIXEL_SERIAL.read(); #elif defined(__OPENCM904__) packet[i] = p_dxl_serial->read(); @@ -176,7 +180,7 @@ int PortHandlerArduino::writePort(uint8_t *packet, int length) setTxEnable(); -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) length_written = DYNAMIXEL_SERIAL.write(packet, length); #elif defined(__OPENCM904__) length_written = p_dxl_serial->write(packet, length); @@ -228,7 +232,7 @@ double PortHandlerArduino::getTimeSinceStart() bool PortHandlerArduino::setupPort(int baudrate) { -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) DYNAMIXEL_SERIAL.begin(baudrate); #elif defined(__OPENCM904__) p_dxl_serial->setDxlMode(true); @@ -268,14 +272,14 @@ int PortHandlerArduino::checkBaudrateAvailable(int baudrate) void PortHandlerArduino::setPowerOn() { -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) digitalWrite(BDPIN_DXL_PWR_EN, HIGH); #endif } void PortHandlerArduino::setPowerOff() { -#if defined(__OPENCR__) +#if defined(__OPENCR__) || defined(ARDUINO_OpenRB) digitalWrite(BDPIN_DXL_PWR_EN, LOW); #endif } diff --git a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp index 668adfa3..ea4071e4 100644 --- a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp @@ -23,7 +23,7 @@ #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT #include "protocol1_packet_handler.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/protocol1_packet_handler.h" #endif diff --git a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp index 06dae1d2..c7f1c311 100644 --- a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp @@ -26,7 +26,7 @@ #define WINDLLEXPORT #include #include "protocol2_packet_handler.h" -#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) +#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB) #include "../../include/dynamixel_sdk/protocol2_packet_handler.h" #endif From 21b65791ee7aad17a312b837c685145bd2684b64 Mon Sep 17 00:00:00 2001 From: Honghyun Date: Fri, 2 Jun 2023 13:55:31 +0900 Subject: [PATCH 3/7] add: fast_bulk_read example --- .../fast_bulk_read/fast_bulk_read.cpp | 335 ++++++++++++++++++ .../fast_bulk_read/linux32/Makefile | 80 +++++ .../fast_bulk_read/linux64/Makefile | 80 +++++ .../fast_bulk_read/linux_sbc/Makefile | 79 +++++ .../protocol2.0/fast_bulk_read/mac/Makefile | 78 ++++ .../fast_bulk_read/win32/fast_bulk_read.sln | 28 ++ .../fast_bulk_read/fast_bulk_read.vcxproj | 155 ++++++++ .../fast_bulk_read.vcxproj.filters | 22 ++ .../fast_bulk_read.vcxproj.user | 7 + .../fast_bulk_read/win64/fast_bulk_read.sln | 28 ++ .../fast_bulk_read/fast_bulk_read.vcxproj | 157 ++++++++ .../fast_bulk_read.vcxproj.filters | 22 ++ .../fast_bulk_read.vcxproj.user | 7 + 13 files changed, 1078 insertions(+) create mode 100644 c++/example/protocol2.0/fast_bulk_read/fast_bulk_read.cpp create mode 100644 c++/example/protocol2.0/fast_bulk_read/linux32/Makefile create mode 100644 c++/example/protocol2.0/fast_bulk_read/linux64/Makefile create mode 100644 c++/example/protocol2.0/fast_bulk_read/linux_sbc/Makefile create mode 100644 c++/example/protocol2.0/fast_bulk_read/mac/Makefile create mode 100644 c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read.sln create mode 100644 c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj create mode 100644 c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.filters create mode 100644 c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.user create mode 100644 c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read.sln create mode 100644 c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj create mode 100644 c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.filters create mode 100644 c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.user diff --git a/c++/example/protocol2.0/fast_bulk_read/fast_bulk_read.cpp b/c++/example/protocol2.0/fast_bulk_read/fast_bulk_read.cpp new file mode 100644 index 00000000..05fbb29a --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/fast_bulk_read.cpp @@ -0,0 +1,335 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ryu Woon Jung (Leon), Honghyun Kim */ + +// +// ********* Bulk Read and Bulk Write Example ********* +// +// +// Available DYNAMIXEL model on this example : All models using Protocol 2.0 +// This example is tested with two DYNAMIXEL P Series, and an U2D2 +// Be sure that DYNAMIXEL P properties are already set as %% ID : 1 and 2 / Baudnum : 1 (Baudrate : 57600) +// + +#if defined(__linux__) || defined(__APPLE__) +#include +#include +#define STDIN_FILENO 0 +#elif defined(_WIN32) || defined(_WIN64) +#include +#endif + +#include +#include + +#include "dynamixel_sdk.h" // Uses DYNAMIXEL SDK library + +// Control table address +#define ADDR_PRO_TORQUE_ENABLE 512 // Control table address is different in DYNAMIXEL model +#define ADDR_PRO_LED_RED 513 +#define ADDR_PRO_GOAL_POSITION 564 +#define ADDR_PRO_PRESENT_POSITION 580 + +// Data Byte Length +#define LEN_PRO_LED_RED 1 +#define LEN_PRO_GOAL_POSITION 4 +#define LEN_PRO_PRESENT_POSITION 4 + +// Protocol version +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the DYNAMIXEL + +// Default setting +#define DXL1_ID 1 // DYNAMIXEL#1 ID: 1 +#define DXL2_ID 2 // DYNAMIXEL#2 ID: 2 +#define BAUDRATE 57600 +#define DEVICENAME "COM3" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // DYNAMIXEL will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the DYNAMIXEL would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 20 // DYNAMIXEL moving status threshold + +#define ESC_ASCII_VALUE 0x1b + +int getch() +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + ch = getchar(); + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + return ch; +#elif defined(_WIN32) || defined(_WIN64) + return _getch(); +#endif +} + +int kbhit(void) +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + int oldf; + + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + oldf = fcntl(STDIN_FILENO, F_GETFL, 0); + fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK); + + ch = getchar(); + + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + fcntl(STDIN_FILENO, F_SETFL, oldf); + + if (ch != EOF) + { + ungetc(ch, stdin); + return 1; + } + + return 0; +#elif defined(_WIN32) || defined(_WIN64) + return _kbhit(); +#endif +} + +int main() +{ + // Initialize PortHandler instance + // Set the port path + // Get methods and members of PortHandlerLinux or PortHandlerWindows + dynamixel::PortHandler *portHandler = dynamixel::PortHandler::getPortHandler(DEVICENAME); + + // Initialize PacketHandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler + dynamixel::PacketHandler *packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION); + + // Initialize GroupBulkWrite instance + dynamixel::GroupBulkWrite groupBulkWrite(portHandler, packetHandler); + + // Initialize GroupFastBulkRead instance + dynamixel::GroupFastBulkRead groupFastBulkRead(portHandler, packetHandler); + + int index = 0; + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // addParam result + bool dxl_getdata_result = false; // GetParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position + + uint8_t dxl_error = 0; // DYNAMIXEL error + uint8_t dxl_led_value[2] = {0x00, 0xFF}; // DYNAMIXEL LED value for write + uint8_t param_goal_position[4]; + int32_t dxl1_present_position = 0; // Present position + uint8_t dxl2_led_value_read; // DYNAMIXEL LED value for read + + // Open port + if (portHandler->openPort()) + { + printf("Succeeded to open the port!\n"); + } + else + { + printf("Failed to open the port!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Set port baudrate + if (portHandler->setBaudRate(BAUDRATE)) + { + printf("Succeeded to change the baudrate!\n"); + } + else + { + printf("Failed to change the baudrate!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Enable DYNAMIXEL#1 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + else + { + printf("DYNAMIXEL#%d has been successfully connected \n", DXL1_ID); + } + + // Enable DYNAMIXEL#2 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + else + { + printf("DYNAMIXEL#%d has been successfully connected \n", DXL2_ID); + } + + // Add parameter storage for DYNAMIXEL#1 present position + dxl_addparam_result = groupFastBulkRead.addParam(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupFastBulkRead addparam failed", DXL1_ID); + return 0; + } + + // Add parameter storage for DYNAMIXEL#2 LED value + dxl_addparam_result = groupFastBulkRead.addParam(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupFastBulkRead addparam failed", DXL2_ID); + return 0; + } + + while(1) + { + printf("Press any key to continue! (or press ESC to quit!)\n"); + if (getch() == ESC_ASCII_VALUE) + break; + + // Allocate goal position value into byte array + param_goal_position[0] = DXL_LOBYTE(DXL_LOWORD(dxl_goal_position[index])); + param_goal_position[1] = DXL_HIBYTE(DXL_LOWORD(dxl_goal_position[index])); + param_goal_position[2] = DXL_LOBYTE(DXL_HIWORD(dxl_goal_position[index])); + param_goal_position[3] = DXL_HIBYTE(DXL_HIWORD(dxl_goal_position[index])); + + // Add parameter storage for DYNAMIXEL#1 goal position + dxl_addparam_result = groupBulkWrite.addParam(DXL1_ID, ADDR_PRO_GOAL_POSITION, LEN_PRO_GOAL_POSITION, param_goal_position); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupBulkWrite addparam failed", DXL1_ID); + return 0; + } + + // Add parameter storage for DYNAMIXEL#2 LED value + dxl_addparam_result = groupBulkWrite.addParam(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED, &dxl_led_value[index]); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupBulkWrite addparam failed", DXL2_ID); + return 0; + } + + // Bulkwrite goal position and LED value + dxl_comm_result = groupBulkWrite.txPacket(); + if (dxl_comm_result != COMM_SUCCESS) printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + + // Clear bulkwrite parameter storage + groupBulkWrite.clearParam(); + + do + { + // Bulkread present position and LED status + dxl_comm_result = groupFastBulkRead.txRxPacket(); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (groupFastBulkRead.getError(DXL1_ID, &dxl_error)) + { + printf("[ID:%03d] %s\n", DXL1_ID, packetHandler->getRxPacketError(dxl_error)); + } + else if (groupFastBulkRead.getError(DXL2_ID, &dxl_error)) + { + printf("[ID:%03d] %s\n", DXL2_ID, packetHandler->getRxPacketError(dxl_error)); + } + + // Check if groupFastBulkRead data of DYNAMIXEL#1 is available + dxl_getdata_result = groupFastBulkRead.isAvailable(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) + { + fprintf(stderr, "[ID:%03d] groupFastBulkRead getdata failed", DXL1_ID); + return 0; + } + + // Check if groupFastBulkRead data of DYNAMIXEL#2 is available + dxl_getdata_result = groupFastBulkRead.isAvailable(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED); + if (dxl_getdata_result != true) + { + fprintf(stderr, "[ID:%03d] groupFastBulkRead getdata failed", DXL2_ID); + return 0; + } + + // Get present position value + dxl1_present_position = groupFastBulkRead.getData(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + + // Get LED value + dxl2_led_value_read = groupFastBulkRead.getData(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED); + + printf("[ID:%03d] Present Position : %d \t [ID:%03d] LED Value: %d\n", DXL1_ID, dxl1_present_position, DXL2_ID, dxl2_led_value_read); + + }while(abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD); + + // Change goal position + if (index == 0) + { + index = 1; + } + else + { + index = 0; + } + } + + // Disable DYNAMIXEL#1 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + // Disable DYNAMIXEL#2 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + // Close port + portHandler->closePort(); + + return 0; +} diff --git a/c++/example/protocol2.0/fast_bulk_read/linux32/Makefile b/c++/example/protocol2.0/fast_bulk_read/linux32/Makefile new file mode 100644 index 00000000..c68bcf32 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/linux32/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_bulk_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_bulk_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m32 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x86_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = fast_bulk_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_bulk_read/linux64/Makefile b/c++/example/protocol2.0/fast_bulk_read/linux64/Makefile new file mode 100644 index 00000000..cdaba0cb --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/linux64/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_bulk_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_bulk_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m64 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x64_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = fast_bulk_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_bulk_read/linux_sbc/Makefile b/c++/example/protocol2.0/fast_bulk_read/linux_sbc/Makefile new file mode 100644 index 00000000..05d470e7 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/linux_sbc/Makefile @@ -0,0 +1,79 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_bulk_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_bulk_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_sbc_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = fast_bulk_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_bulk_read/mac/Makefile b/c++/example/protocol2.0/fast_bulk_read/mac/Makefile new file mode 100644 index 00000000..dfae9885 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/mac/Makefile @@ -0,0 +1,78 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_bulk_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_bulk_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_mac_cpp + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = fast_bulk_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read.sln b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read.sln new file mode 100644 index 00000000..c225ee16 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio Express 14 for Windows Desktop +VisualStudioVersion = 14.0.25123.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "fast_bulk_read", "fast_bulk_read\fast_bulk_read.vcxproj", "{62F90CF0-0FBA-4884-B748-400030E52C55}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x64.ActiveCfg = Debug|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x64.Build.0 = Debug|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x86.ActiveCfg = Debug|Win32 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x86.Build.0 = Debug|Win32 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x64.ActiveCfg = Release|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x64.Build.0 = Release|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x86.ActiveCfg = Release|Win32 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj new file mode 100644 index 00000000..ee0d7576 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj @@ -0,0 +1,155 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {62F90CF0-0FBA-4884-B748-400030E52C55} + Win32Proj + fast_bulk_read + 8.1 + fast_bulk_read + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + $(VC_LibraryPath_x86);$(WindowsSDK_LibraryPath_x86);$(NETFXKitsDir)Lib\um\x86;..\..\..\..\..\build\win32\output + + + false + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsCpp + + + Console + true + true + true + dxl_x86_cpp.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + + + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.filters b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.filters new file mode 100644 index 00000000..60b62e1f --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.user b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.user new file mode 100644 index 00000000..45bf49fb --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win32/fast_bulk_read/fast_bulk_read.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win32\output; + WindowsLocalDebugger + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read.sln b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read.sln new file mode 100644 index 00000000..c225ee16 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio Express 14 for Windows Desktop +VisualStudioVersion = 14.0.25123.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "fast_bulk_read", "fast_bulk_read\fast_bulk_read.vcxproj", "{62F90CF0-0FBA-4884-B748-400030E52C55}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x64.ActiveCfg = Debug|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x64.Build.0 = Debug|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x86.ActiveCfg = Debug|Win32 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Debug|x86.Build.0 = Debug|Win32 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x64.ActiveCfg = Release|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x64.Build.0 = Release|x64 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x86.ActiveCfg = Release|Win32 + {62F90CF0-0FBA-4884-B748-400030E52C55}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj new file mode 100644 index 00000000..b5cdbb16 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj @@ -0,0 +1,157 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {62F90CF0-0FBA-4884-B748-400030E52C55} + Win32Proj + fast_bulk_read + 8.1 + fast_bulk_read + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + + + false + $(SolutionDir)$(Configuration)\ + $(Configuration)\ + $(VC_LibraryPath_x64);$(WindowsSDK_LibraryPath_x64);$(NETFXKitsDir)Lib\um\x64;..\..\..\..\..\build\win64\output + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsCpp + + + Console + true + true + true + dxl_x64_cpp.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + + + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.filters b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.filters new file mode 100644 index 00000000..60b62e1f --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.user b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.user new file mode 100644 index 00000000..0f71dd30 --- /dev/null +++ b/c++/example/protocol2.0/fast_bulk_read/win64/fast_bulk_read/fast_bulk_read.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win64\output; + WindowsLocalDebugger + + \ No newline at end of file From be4a67ec876456a7065734bb5f3cd8cef0a79748 Mon Sep 17 00:00:00 2001 From: Honghyun Date: Fri, 2 Jun 2023 13:56:10 +0900 Subject: [PATCH 4/7] add: fast_sync_read example --- .../fast_sync_read/fast_sync_read.cpp | 331 ++++++++++++++++++ .../fast_sync_read/linux32/Makefile | 80 +++++ .../fast_sync_read/linux64/Makefile | 80 +++++ .../fast_sync_read/linux_sbc/Makefile | 79 +++++ .../protocol2.0/fast_sync_read/mac/Makefile | 78 +++++ .../fast_sync_read/win32/fast_sync_read.sln | 28 ++ .../fast_sync_read/fast_sync_read.vcxproj | 155 ++++++++ .../fast_sync_read.vcxproj.filters | 22 ++ .../fast_sync_read.vcxproj.user | 7 + .../fast_sync_read/win64/fast_sync_read.sln | 28 ++ .../fast_sync_read/fast_sync_read.vcxproj | 157 +++++++++ .../fast_sync_read.vcxproj.filters | 22 ++ .../fast_sync_read.vcxproj.user | 7 + 13 files changed, 1074 insertions(+) create mode 100644 c++/example/protocol2.0/fast_sync_read/fast_sync_read.cpp create mode 100644 c++/example/protocol2.0/fast_sync_read/linux32/Makefile create mode 100644 c++/example/protocol2.0/fast_sync_read/linux64/Makefile create mode 100644 c++/example/protocol2.0/fast_sync_read/linux_sbc/Makefile create mode 100644 c++/example/protocol2.0/fast_sync_read/mac/Makefile create mode 100644 c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read.sln create mode 100644 c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj create mode 100644 c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.filters create mode 100644 c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.user create mode 100644 c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read.sln create mode 100644 c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj create mode 100644 c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.filters create mode 100644 c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.user diff --git a/c++/example/protocol2.0/fast_sync_read/fast_sync_read.cpp b/c++/example/protocol2.0/fast_sync_read/fast_sync_read.cpp new file mode 100644 index 00000000..82635c0e --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/fast_sync_read.cpp @@ -0,0 +1,331 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ryu Woon Jung (Leon), Honghyun Kim */ + +// +// ********* Sync Read and Sync Write Example ********* +// +// +// Available DYNAMIXEL model on this example : All models using Protocol 2.0 +// This example is tested with two DYNAMIXEL P Series, and an U2D2 +// Be sure that DYNAMIXEL P properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +// + +#if defined(__linux__) || defined(__APPLE__) +#include +#include +#define STDIN_FILENO 0 +#elif defined(_WIN32) || defined(_WIN64) +#include +#endif + +#include +#include + +#include "dynamixel_sdk.h" // Uses DYNAMIXEL SDK library + +// Control table address +#define ADDR_PRO_TORQUE_ENABLE 512 // Control table address is different in DYNAMIXEL model +#define ADDR_PRO_GOAL_POSITION 564 +#define ADDR_PRO_PRESENT_POSITION 580 + +// Data Byte Length +#define LEN_PRO_GOAL_POSITION 4 +#define LEN_PRO_PRESENT_POSITION 4 + +// Protocol version +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the DYNAMIXEL + +// Default setting +#define DXL1_ID 1 // DYNAMIXEL#1 ID: 1 +#define DXL2_ID 2 // DYNAMIXEL#2 ID: 2 +#define BAUDRATE 57600 +#define DEVICENAME "COM3" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // DYNAMIXEL will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the DYNAMIXEL would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 20 // DYNAMIXEL moving status threshold + +#define ESC_ASCII_VALUE 0x1b + +int getch() +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + ch = getchar(); + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + return ch; +#elif defined(_WIN32) || defined(_WIN64) + return _getch(); +#endif +} + +int kbhit(void) +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + int oldf; + + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + oldf = fcntl(STDIN_FILENO, F_GETFL, 0); + fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK); + + ch = getchar(); + + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + fcntl(STDIN_FILENO, F_SETFL, oldf); + + if (ch != EOF) + { + ungetc(ch, stdin); + return 1; + } + + return 0; +#elif defined(_WIN32) || defined(_WIN64) + return _kbhit(); +#endif +} + +int main() +{ + // Initialize PortHandler instance + // Set the port path + // Get methods and members of PortHandlerLinux or PortHandlerWindows + dynamixel::PortHandler *portHandler = dynamixel::PortHandler::getPortHandler(DEVICENAME); + + // Initialize PacketHandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler + dynamixel::PacketHandler *packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION); + + // Initialize GroupSyncWrite instance + dynamixel::GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_PRO_GOAL_POSITION, LEN_PRO_GOAL_POSITION); + + // Initialize GroupFastSyncRead instance for Present Position + dynamixel::GroupFastSyncRead groupFastSyncRead(portHandler, packetHandler, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + + int index = 0; + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // addParam result + bool dxl_getdata_result = false; // GetParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position + + uint8_t dxl_error = 0; // DYNAMIXEL error + uint8_t param_goal_position[4]; + int32_t dxl1_present_position = 0, dxl2_present_position = 0; // Present position + + // Open port + if (portHandler->openPort()) + { + printf("Succeeded to open the port!\n"); + } + else + { + printf("Failed to open the port!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Set port baudrate + if (portHandler->setBaudRate(BAUDRATE)) + { + printf("Succeeded to change the baudrate!\n"); + } + else + { + printf("Failed to change the baudrate!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Enable DYNAMIXEL#1 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + else + { + printf("DYNAMIXEL#%d has been successfully connected \n", DXL1_ID); + } + + // Enable DYNAMIXEL#2 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + else + { + printf("DYNAMIXEL#%d has been successfully connected \n", DXL2_ID); + } + + // Add parameter storage for DYNAMIXEL#1 present position value + dxl_addparam_result = groupFastSyncRead.addParam(DXL1_ID); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupSyncRead addparam failed", DXL1_ID); + return 0; + } + + // Add parameter storage for Dynamixel#2 present position value + dxl_addparam_result = groupFastSyncRead.addParam(DXL2_ID); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupSyncRead addparam failed", DXL2_ID); + return 0; + } + + while(1) + { + printf("Press any key to continue! (or press ESC to quit!)\n"); + if (getch() == ESC_ASCII_VALUE) + break; + + // Allocate goal position value into byte array + param_goal_position[0] = DXL_LOBYTE(DXL_LOWORD(dxl_goal_position[index])); + param_goal_position[1] = DXL_HIBYTE(DXL_LOWORD(dxl_goal_position[index])); + param_goal_position[2] = DXL_LOBYTE(DXL_HIWORD(dxl_goal_position[index])); + param_goal_position[3] = DXL_HIBYTE(DXL_HIWORD(dxl_goal_position[index])); + + // Add DYNAMIXEL#1 goal position value to the Syncwrite storage + dxl_addparam_result = groupSyncWrite.addParam(DXL1_ID, param_goal_position); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL1_ID); + return 0; + } + + // Add DYNAMIXEL#2 goal position value to the Syncwrite parameter storage + dxl_addparam_result = groupSyncWrite.addParam(DXL2_ID, param_goal_position); + if (dxl_addparam_result != true) + { + fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL2_ID); + return 0; + } + + // Syncwrite goal position + dxl_comm_result = groupSyncWrite.txPacket(); + if (dxl_comm_result != COMM_SUCCESS) printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + + // Clear syncwrite parameter storage + groupSyncWrite.clearParam(); + + do + { + // Syncread present position + dxl_comm_result = groupFastSyncRead.txRxPacket(); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (groupFastSyncRead.getError(DXL1_ID, &dxl_error)) + { + printf("[ID:%03d] %s\n", DXL1_ID, packetHandler->getRxPacketError(dxl_error)); + } + else if (groupFastSyncRead.getError(DXL2_ID, &dxl_error)) + { + printf("[ID:%03d] %s\n", DXL2_ID, packetHandler->getRxPacketError(dxl_error)); + } + + // Check if groupFastSyncRead data of DYNAMIXEL#1 is available + dxl_getdata_result = groupFastSyncRead.isAvailable(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) + { + fprintf(stderr, "[ID:%03d] groupFastSyncRead getdata failed", DXL1_ID); + return 0; + } + + // Check if groupFastSyncRead data of DYNAMIXEL#2 is available + dxl_getdata_result = groupFastSyncRead.isAvailable(DXL2_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) + { + fprintf(stderr, "[ID:%03d] groupFastSyncRead getdata failed", DXL2_ID); + return 0; + } + + // Get DYNAMIXEL#1 present position value + dxl1_present_position = groupFastSyncRead.getData(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + + // Get DYNAMIXEL#2 present position value + dxl2_present_position = groupFastSyncRead.getData(DXL2_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + + printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position); + + }while((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + + // Change goal position + if (index == 0) + { + index = 1; + } + else + { + index = 0; + } + } + + // Disable DYNAMIXEL#1 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + // Disable DYNAMIXEL#2 Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + // Close port + portHandler->closePort(); + + return 0; +} diff --git a/c++/example/protocol2.0/fast_sync_read/linux32/Makefile b/c++/example/protocol2.0/fast_sync_read/linux32/Makefile new file mode 100644 index 00000000..787bb0e9 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/linux32/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_sync_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_sync_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m32 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x86_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = ../fast_sync_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_sync_read/linux64/Makefile b/c++/example/protocol2.0/fast_sync_read/linux64/Makefile new file mode 100644 index 00000000..96569f60 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/linux64/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_sync_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_sync_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m64 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x64_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = ../fast_sync_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_sync_read/linux_sbc/Makefile b/c++/example/protocol2.0/fast_sync_read/linux_sbc/Makefile new file mode 100644 index 00000000..c5802660 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/linux_sbc/Makefile @@ -0,0 +1,79 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_sync_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_sync_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_sbc_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = ../fast_sync_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_sync_read/mac/Makefile b/c++/example/protocol2.0/fast_sync_read/mac/Makefile new file mode 100644 index 00000000..38f2a58b --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/mac/Makefile @@ -0,0 +1,78 @@ +################################################## +# PROJECT: DXL Protocol 2.0 fast_sync_read Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = fast_sync_read + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_mac_cpp + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = fast_sync_read.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read.sln b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read.sln new file mode 100644 index 00000000..d92aa324 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio Express 14 for Windows Desktop +VisualStudioVersion = 14.0.25123.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "fast_sync_read", "fast_sync_read\fast_sync_read.vcxproj", "{2AE832A6-39C8-47AA-8C78-3429607108C0}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x64.ActiveCfg = Debug|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x64.Build.0 = Debug|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x86.ActiveCfg = Debug|Win32 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x86.Build.0 = Debug|Win32 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x64.ActiveCfg = Release|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x64.Build.0 = Release|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x86.ActiveCfg = Release|Win32 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj new file mode 100644 index 00000000..f18a7cf1 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj @@ -0,0 +1,155 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {2AE832A6-39C8-47AA-8C78-3429607108C0} + Win32Proj + fast_sync_read + 8.1 + fast_sync_read + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + $(VC_LibraryPath_x86);$(WindowsSDK_LibraryPath_x86);$(NETFXKitsDir)Lib\um\x86;..\..\..\..\..\build\win32\output + + + false + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsCpp + + + Console + true + true + true + dxl_x86_cpp.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + + + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.filters b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.filters new file mode 100644 index 00000000..17dee47d --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.user b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.user new file mode 100644 index 00000000..45bf49fb --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win32/fast_sync_read/fast_sync_read.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win32\output; + WindowsLocalDebugger + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read.sln b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read.sln new file mode 100644 index 00000000..d92aa324 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio Express 14 for Windows Desktop +VisualStudioVersion = 14.0.25123.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "fast_sync_read", "fast_sync_read\fast_sync_read.vcxproj", "{2AE832A6-39C8-47AA-8C78-3429607108C0}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x64.ActiveCfg = Debug|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x64.Build.0 = Debug|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x86.ActiveCfg = Debug|Win32 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Debug|x86.Build.0 = Debug|Win32 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x64.ActiveCfg = Release|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x64.Build.0 = Release|x64 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x86.ActiveCfg = Release|Win32 + {2AE832A6-39C8-47AA-8C78-3429607108C0}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj new file mode 100644 index 00000000..a1456d95 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj @@ -0,0 +1,157 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {2AE832A6-39C8-47AA-8C78-3429607108C0} + Win32Proj + fast_sync_read + 8.1 + fast_sync_read + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + + + false + $(SolutionDir)$(Configuration)\ + $(Configuration)\ + $(VC_LibraryPath_x64);$(WindowsSDK_LibraryPath_x64);$(NETFXKitsDir)Lib\um\x64;..\..\..\..\..\build\win64\output + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsCpp + + + Console + true + true + true + dxl_x64_cpp.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + + + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.filters b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.filters new file mode 100644 index 00000000..17dee47d --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + \ No newline at end of file diff --git a/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.user b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.user new file mode 100644 index 00000000..0f71dd30 --- /dev/null +++ b/c++/example/protocol2.0/fast_sync_read/win64/fast_sync_read/fast_sync_read.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win64\output; + WindowsLocalDebugger + + \ No newline at end of file From 27484ced2985d9b91f11cca779fce0aa6f81eb1f Mon Sep 17 00:00:00 2001 From: Honghyun Date: Fri, 2 Jun 2023 14:01:34 +0900 Subject: [PATCH 5/7] modify Makefile --- c++/build/linux32/Makefile | 3 +++ c++/build/linux64/Makefile | 3 +++ c++/build/linux_sbc/Makefile | 3 +++ c++/build/mac/Makefile | 3 +++ 4 files changed, 12 insertions(+) diff --git a/c++/build/linux32/Makefile b/c++/build/linux32/Makefile index 86764849..24421df0 100644 --- a/c++/build/linux32/Makefile +++ b/c++/build/linux32/Makefile @@ -52,6 +52,9 @@ SOURCES = src/dynamixel_sdk/group_bulk_read.cpp \ src/dynamixel_sdk/group_bulk_write.cpp \ src/dynamixel_sdk/group_sync_read.cpp \ src/dynamixel_sdk/group_sync_write.cpp \ + src/dynamixel_sdk/group_fast_bulk_read.cpp \ + src/dynamixel_sdk/group_fast_sync_read.cpp \ + src/dynamixel_sdk/group_handler.cpp \ src/dynamixel_sdk/packet_handler.cpp \ src/dynamixel_sdk/port_handler.cpp \ src/dynamixel_sdk/protocol1_packet_handler.cpp \ diff --git a/c++/build/linux64/Makefile b/c++/build/linux64/Makefile index 43a0bcca..12fe82a3 100644 --- a/c++/build/linux64/Makefile +++ b/c++/build/linux64/Makefile @@ -52,6 +52,9 @@ SOURCES = src/dynamixel_sdk/group_bulk_read.cpp \ src/dynamixel_sdk/group_bulk_write.cpp \ src/dynamixel_sdk/group_sync_read.cpp \ src/dynamixel_sdk/group_sync_write.cpp \ + src/dynamixel_sdk/group_fast_bulk_read.cpp \ + src/dynamixel_sdk/group_fast_sync_read.cpp \ + src/dynamixel_sdk/group_handler.cpp \ src/dynamixel_sdk/packet_handler.cpp \ src/dynamixel_sdk/port_handler.cpp \ src/dynamixel_sdk/protocol1_packet_handler.cpp \ diff --git a/c++/build/linux_sbc/Makefile b/c++/build/linux_sbc/Makefile index d0eee798..47c4c3d0 100644 --- a/c++/build/linux_sbc/Makefile +++ b/c++/build/linux_sbc/Makefile @@ -51,6 +51,9 @@ SOURCES = src/dynamixel_sdk/group_bulk_read.cpp \ src/dynamixel_sdk/group_bulk_write.cpp \ src/dynamixel_sdk/group_sync_read.cpp \ src/dynamixel_sdk/group_sync_write.cpp \ + src/dynamixel_sdk/group_fast_bulk_read.cpp \ + src/dynamixel_sdk/group_fast_sync_read.cpp \ + src/dynamixel_sdk/group_handler.cpp \ src/dynamixel_sdk/packet_handler.cpp \ src/dynamixel_sdk/port_handler.cpp \ src/dynamixel_sdk/protocol1_packet_handler.cpp \ diff --git a/c++/build/mac/Makefile b/c++/build/mac/Makefile index fbff6fa6..83abdee6 100644 --- a/c++/build/mac/Makefile +++ b/c++/build/mac/Makefile @@ -45,6 +45,9 @@ SOURCES = src/dynamixel_sdk/group_bulk_read.cpp \ src/dynamixel_sdk/group_bulk_write.cpp \ src/dynamixel_sdk/group_sync_read.cpp \ src/dynamixel_sdk/group_sync_write.cpp \ + src/dynamixel_sdk/group_fast_bulk_read.cpp \ + src/dynamixel_sdk/group_fast_sync_read.cpp \ + src/dynamixel_sdk/group_handler.cpp \ src/dynamixel_sdk/packet_handler.cpp \ src/dynamixel_sdk/port_handler.cpp \ src/dynamixel_sdk/protocol1_packet_handler.cpp \ From 0e876f62301ca88aeeaf7e55bef64f09e10e97f7 Mon Sep 17 00:00:00 2001 From: Honghyun Date: Fri, 2 Jun 2023 14:22:44 +0900 Subject: [PATCH 6/7] update build for windows --- .../win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj | 6 ++++++ .../dxl_x86_cpp/dxl_x86_cpp.vcxproj.filters | 18 ++++++++++++++++++ c++/build/win32/output/dxl_x86_cpp.dll | Bin 61952 -> 67072 bytes c++/build/win32/output/dxl_x86_cpp.lib | Bin 79440 -> 86558 bytes .../win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj | 6 ++++++ .../dxl_x64_cpp/dxl_x64_cpp.vcxproj.filters | 18 ++++++++++++++++++ .../dxl_x64_cpp/dxl_x64_cpp.vcxproj.user | 4 ++++ c++/build/win64/output/dxl_x64_cpp.dll | Bin 77824 -> 86528 bytes c++/build/win64/output/dxl_x64_cpp.lib | Bin 81332 -> 88684 bytes 9 files changed, 52 insertions(+) create mode 100644 c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.user diff --git a/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj b/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj index 18b16858..20cca603 100644 --- a/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj +++ b/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj @@ -22,6 +22,9 @@ + + + @@ -33,6 +36,9 @@ + + + diff --git a/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj.filters b/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj.filters index 3351e706..5b7c8fee 100644 --- a/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj.filters +++ b/c++/build/win32/dxl_x86_cpp/dxl_x86_cpp.vcxproj.filters @@ -51,6 +51,15 @@ Header Files\dynamixel_sdk + + Header Files\dynamixel_sdk + + + Header Files\dynamixel_sdk + + + Header Files\dynamixel_sdk + @@ -80,5 +89,14 @@ Source Files\dynamixel_sdk + + Source Files\dynamixel_sdk + + + Source Files\dynamixel_sdk + + + Source Files\dynamixel_sdk + \ No newline at end of file diff --git a/c++/build/win32/output/dxl_x86_cpp.dll b/c++/build/win32/output/dxl_x86_cpp.dll index a7ca7687c3fc6ef3b9171a34e3cda5a3d8ae586d..0dd9ab84ea6e924735a08f8eff53c3b76483c6bc 100644 GIT binary patch literal 67072 zcmeFa3w%_?**|{vl4MDioJALi7G>3-*dRuN2rSTqut@|08v+T)B_K%*5lKvT0p+&I zCUrN*wY0T2wQsTN``XsFv{i`K+JtBlEWPVO10nSUpE`Zb zQ&I50vwGFjlbB!fw4M1sdW!p{?0vzS)g@GhS|g`J5a#Nlg-$Z+<(An{!&r&c%Do+Loldd&_*D}(EOzeLc{n6iq{lY3c@T3 zw<+l^XcFNumEcuWR;3RG>F+2t0OM@kz7X(Y;vxK`dH!uHLqeW*)dCM7aoGE;c z0;N;Za?{x+y(_IG6+JY#zBjP7x73s;j{w?dn{=*gB{5)rn^-g_Uv8+Px|*aGDf>*J ze<%T1Qm|qvY74wtqNzTVCyoF#vU;1O=7G`@hAq1G-wBp*efhgu`*6HkWvNkp`g-+q z4hz-Km?uv{RYLU(DD`XiT(*9MFRvc}e5BA~(E3Tba9s#vDa{xWK>U%HFP)b%t%3Pg zXD~V7=yl4`*J3o;V3oH3yfohg&Z^z(S|(*$k{YLz)Tx+owsEv8Iyk&_Cy1BUYj3Pj zUXoh9=Z%%hi}(C3>(xZ9Ir5!=){;pbop`k+(@ak-nIy%8f)&KA2M%z4`Bj)-fL(un zIq%=nExApB`6emaA0uTL{h7uc_sh@z8S_qCdl$njFka2{0gi6m}|JSU;Yhx zQxJ4TQTv^8Dp3u^WUyi~Y*I72nYQzTVv+C*!tgUp_9oXjsa38M!9xarhDl0C!DcDl z3(Ow} zrdA{0Vv*zIX)H1^Fh5Zf`67!knI~ zg+u*;cZVFOoHtSs#9f*W0R+)!bZC=6Mk2Zl()@e`WgXY-=+y@@#__NxSlC2_8PK;T zvc46|VNLU8P8+;ig$N$WFMas20G%g-A8(A)^5agF1bz&xNDQ%LATv>6-7jL5q>043 zQAip&NoIAMH_dHSOUrK{Pqc z5KRO3`VE8j`g2z5_05^1ARTSgQ34y(=IJLPo@QwS8(2g2i`}BcvL@>n`yF16qt_@M zYR;S{$RD6v4$z3E&~Q)v-P<*pdRT@zDZ?bz6oF|VRBIbtL!7ehQP#^Kq*^i<;*w5E zH3r*`FYoz6v^aXi@ljcS6f8eG`{pdkzlr7dL)K)NbMsSzDJNJV zmq3GJar7)I$^__jMuX20931$gX#qzN^NVh0VBR>n2dyp5vq_Hbx>SqLDB`)!5%kRx zbv%{qZP6oPqI`%FI%K5kd_+lP6nUCbVkpWVA4-x(bKJceZNn`Y@?ZG-4&wI6iFO=wW2M`i&sIFN0!w^ojo;sT3I z_I(>hOQ(}g+0#vKQx3%LMRYg_Ta5NL$xvsE?i?A4`ZyF7Rp&7IbU}b}n55;sG>>xz z=8TiK4=3`S3Cu|>mfV(Nf4Kz-Sgh>kQN>cWx!9j&5qCE`<&;NQV+ZC~rS4F|_b6fZ znNpqqVXHh$O)*iE;x(RPr>+1=Ry3!N(y^(Zne!;44~Qe~a+{>%`O+q{^j8cyNo@=A z!n7gE^w>9<#hMSnSW>zVb$Q0w8@}7tkR$0$T&=V}T%IDYfnmbH^ITLvaC(#up2a7$SiM0+` zzSSugMnIn^_bGp(Q=W+wM4iyoSTo+e9+qF;F6)3Z95%(uG$&=EkME;Co@q`wi#OLC z%xW;C7@C2a?39xj;xbk1W+2WYCt|Q;@$F7Ij>WfAyq?9IGXMn%?A;Zwu+)iuOpvm> zlsOwZ^OV0O5ny)8H?_&w6bFmQ^* z?;Fg=mr?a2Fd@pNWl4cKslY^IlRK_}A;S>POF3J6Vrwa8W8ff&DW8M-CK&RJQ+|q; z0PLm92|ktULhmQ>K2H7&6GBKSX}%FWDLJ~NVaz`%?oPEh(aD4N1Q$%JZE%}20N(z^ z=AWW;-HHN*P#F2-W0!(KBrr(_S9HvUY+j)uAd^292)F5SaXE|!*?#oZe% z#r6*??h40`lSlG+aW_d;hb5_1+}&h2WN+OZ2Pw%{#%8RrCNyXzC7+TJz9)OUUE^}4 z`B($U6Hv3726tRac=TXp&Ps$(0#ZMxdHt+Jl$dJqGr!3z>%=}48&bVJuN+zp-Yv|-YyeStP$C1?AeDYJVpkTS7*X>vSzQ(B>td*^3k*m?RORW zmGe?eSgPK@Wz@%zVod%$94Sv?NSek#n&QFKlF6j$;35O%LkhIzNp7>0W%N7(?oP<9 zyKyoYIZC>h82qp_go0gNOYLp0VRi9SXIm;_p;KDnw@?+NY&_{msl;ZPfJc3Y7OWXY zdr##!Dc*i)!>vi@?HO!}a!|gH=BV>%iZWJ;t~179CX!(+SV8O3P?|}hG{!n@0!A-y zmpNBD4vbCyO?{jMDz3Xs29{mzoCGH>79+Vka2N z%!NUKwgL1ARUx$WVh=QPA5nY6wG;Ow2&fYt5J$h z>XB0Noq3%40pmTOzFJ>mf#6+o>pCa|RgnySQuH6krE{KbU{A*W`{lnwyh)St<)@Gu zHIOdxDFp~0q2WOO9P~PA5edih(mnQQ_x1L7-6Lc#E!ks0XLL%F-^BZ|eUEFoXX8*o zYIUbcP7@RM*GYN`a^Jz%FKztQb+&VqIviYUpJ{T(OMCn%X8{`_T%Y?FnK1xr~H$L z7y*?2N5sOYYl2E?gE6Vu+oP+TDv45KQgaqP$CbPc^23CR#q`s8^2d-Ipk}1Hl;oAtzatb~3g^^f;3=5Uz&bP99}xV}P*zFN zX#Wfo4Q3II1C9nfZx@ZXkUt;fV+};j=*|FlGop`@x}|9Ll&q{Dm3PqpMsz3^b*;Ue z=-=%Jj8qon`kcSTG07DrZ8CKxphr_`mr*+387FNu*}o8LX>cc|l5&l1gFoL$on4r+ z*yxV(Z!~tsO}XA}^iSfp?);QW#)(QP=?hjnIG-OHoVNvy5WxE65GHbYLS+VA#%L*v2ws z(@cK7Lg|6A6$x9XiBLCn>is5vj*0M%Wh3DYA*`B1c#E~K;hA9;jbRlX9>V}b zVnx%OY1ZY+hEi06#ug)%%$UU+vl!Co{Y$y9!N{3rv}aMtOfDlWHq;tRk7osXs>r{IH4F#h(UUJY(nn zL?#@mVSzCCQ{gpew1IAHB(}WaVgY<`y2lf;jLaQvL^9q02vvyR@ft$amgx93UNl1> zzs-BGmg)yFaa$r*+CXJX~s31QFn= z;|qkBG39LM#Ht|MBDpD$d5gV8h3J$=DiF(W@qW_o&*<%p%a;ubv~KBIXkC)_&j&F33a&s8hbB)P)aw>pn=q3GBneu=}+l1+#SGljSp8dr7Uz_ z$kI_tXBGMQ6%tkcSZPm_A}`(7pwojFRVkVP{$ zyxCMPRv`bZ*ApdvKzmOjE$NX2;>NBAI>Az*c2M3w7YvpPrGoq!_Qr|LI6evg71GyZHh=Z_ zTq4dL5TBQ?4xellpZmi2sQekk@D?MbYDe}R7>fgkft(Z2jRIU$~QmE7@Izkyo)Qz0#jIWHw7%X%e zkdqDFBvuL_g|o1FP}XJ&KU|@F%hxL3@-LK66L7Y&H=tUI3gU*k(X2mDzAs+YM4VPN z5z=vcx9hsPn5h}@71!`;t!Pd)3T#be5-=|{`?r{#q%WS1rHIqp5RYAxJOn%CWwcPi z;y&99?!eGvI$5{pK&kmID@Cr}H`fIXNSKeOVw|_Pb?yHsfHqF8iO8 zv*IgrF)R}jOe*bn-3*vcfRt+n1xV-;viA>~qK*|PdaFPnrO+=ij!c=1y)c&v1y4o6 z4@mPO3T9wYaNM9^8EPoFgOo7?))f_zuPrXYUWw=B$0i?E17Sbu){Hnr1L^HUb}3ypk=A%Q={A4^LB@K2tMxwRm*1uDRD zSm6q_XCcBcPMENiPi2eEJt4hCUVf=nIxojAMUHN)?vU0fjr5NQFpVZDUUjh2!OWOF z7D&xnWf~+W@+TnwzWcsreszBDg3g@QSeU}|Y5sNU3~!QFx4`E3S$uLhTpXP$NP4>t z)BITJUKZ&3r?Onov*iGr|FV6XOyl(Z2M(AkMg-jn@+8z2buDQP>5io338^rQkQ^|I zGD@Po(H-w!LRC(HTWsna?SWFuWyY(B@`m}Z>l}(;yrh}14qsv-gPob4$NoBzPy-vDL`pUOR#tN9twZ>v3 zt{X!9hoMO75x=(wku^uqNi;L?lT!9c=^WO0h?rrwyYHlNGQSi?9+>A8UWBHA_jsC= z_S?|dW5LkZCBIKvU3V81ml2QrQ+1U$<^V2s#N^IhBwtElPz_#YrC zDBM5(azFaV6a@TB{UdTeb6|T%`Q;cuWmcD}$>oAiFkjp-PTsqaV)~d|-pwKt<(CkN zo(hu^!#k*nb}orkd&vIy#ur2Sn}N$8%-(Y7KZ3yl>@7d}JQ&p49}i$|nSvyWxg|_1 z$==c_k49Lrlrgc`pEB~Di8;P3(F%(g7)xku9!2TTH2GGn zs{X*96%(CLoQyG38WbZPDmvvXPwE=a?4-t#N!6@GSVY{0hJ!6ZLPoKaYAN246 zAPg+5s*Z@eGhzRAGzYVcOdHhPnP#wj$_fA6L~9b6b4^9TfqX01=aT)5PTJ?2m3S?H zUrQyx24fK~!RFm)#UyG7VLIPdhj^bcPE7`ziTR20(`b4!xxllO&&?vQ)u~B<#wH%0 zO!-q`78$2kBd0NQoTWT|GK+^zWt>5cpT*+sJU$h~P$3xA6r;RNQ7q92o+ttO0y`Ep zGt~rh5o?uwJT?me$cn-kouR44sB{M5Xcs3bS+m%?H@^Xk4=ZQ{+NFVJL^^w`SbY!^ z9_Tr_s9=LSwSSkHHNJlf85ODRA88Op=1`A@4Kbl#*Z>PnG%IX%b}fQhAZ(l%GTd~x zG2@i^Ci&A3(EC(lL(u#-Le|k!jCCzpQ--6)$!0_$9NMKGarg0D|8kZ>Zkf;63$~xI zq=Zqu!;%xo?#Y39{(}T7y9c(EWK-q(rnKBjMnKsisPetMG#J#>8E^C%<1_5%Hh(B> zIfMSD3)vT`i*QB{Q=h)jpBAFjLi6H5i9i;b-S!Qz(EJ&t%QOe(F$+y)dn7ntwa}ce zSZG>5Bgv*(Xd+ae*{&tpIQeu(L<$%l*&Us%$_ zE1RJH;e7ysxo9a!Ml*;jn_muUf;wJ04`YNHFt%zhnx_CC`Y!+<#1=JVGpko%zKSYe z9l{}d(IvB4mVd=w6w6-K)IY)!lmy?VySXj9>kf?(X^eDG{&Np#I?pKX&cLaf^)^^y z!bJ2LP=%R@hHX#7%O_=jZ9|xU2A-eER+`=&Qr44lG`&Tf-bs89(g3G-o<>#qJQ6fg zr;;%&a-6)CMfRCWes+R#Cd#Wgkua64Zw2)JQ%QAv$jQT$i#8v7paV=EE;)>)XGt0CqQa3TWSQ+1n`Lpjz+vBUGLSw}`zdLXgSpM6wDCwcu&d z66M4xjrW(IDHg{&&QKGIQWu&9W)$`e$mDkRtjt`-K|KcAwPe^3iX?O_BsV``#Bq+C zduf-^M%NPO8rpE-t~iZ~aFN{ye zu*fbJsX1!_3tyb~FtNy!p`6NDi}zS$=Sc$lUSL}k;(-8F45CQGR8wfuO!en;)*iDkmGp0E$83TupOuak zZkD4|>`~qUVSnhra}K2I&}@z`y*x+7oVZDYLCEpeYQ~ z=gl{k>T-kF_zgNSEjWhJruHZ>^K3F+a(|q%H}4G--u&4xjyf|XyGwlH_tbj%;~+Nq zywQP~2_3aL;FPyxxgj|Yz-*e?1Uq_o%$qn*%834^GD_%D8Zf97+Z!uqv$=>INY_hS zWSAs4PNtm2v<3Ot`0~0_KEPnU9$2qKX324~ZdNo-?!*VZojUh12{c;%p5#6QaN_Pp zLMyx5+iXlT5V}Cx4vZhqL3=VA?%d$;okR@>kz*+%0h2N8Ns%#({#S1AM>Ur55M=K{ zy9ApOl4*9P6AKyD^Zt9~^MwmRX1;1wg;4chxtuxg;PU&B?0ggS9YoG3=qvK^?^=1$ zU)e_7HSqb_>~}F~>VIDF)(?ZhLCy1uzXTa zkb^#huV3dMrB$cqd}=)8czFG~10@c+e*HT{A4|&CuWpufoG$~oWdgSh;Fby8GLj>g zs|x+DJia_nI|!li<%jgfbPj6kz4;duk5R%tOKrXH?HQ=`P=C$%FoUGUAmhUk9yj3l zVETndUoqJDV8w2lGD^HlyY!(^;#l9E95zbu8U0oEhfQgU{F~B8{!OFJKQ<;n{*mY- zo`4V}7ID&WzXS55zZg{6nakf~E`OUd#`PD5?IaA_xiB0~0#F&F*qW6OMv5@(ju3`2 zgyA(@7_#EU(H>wzmgOW5Cn@sqB*{bCP*CMz{-3!#JmcTeGbOuQe8P`N3?nEuQXU?2 z$`&vkgbkB=qf>%D$h~5FMsnpnn7Dfz^oAw~Xf7h@jG$F+|A5lBiM#)r$%I{3oe{?s zV~g!ulPmrzEtg>^NF`;T!J$DSW16AIpG}C^fym=zM*s@x3PNJ;B#F5`w7tsq>?7aK zhUMFX1If3mI8lkRNvvyYalbyE=t-c28-xyqJRpshCxPJH*(7fE>x*av`GXPMbnm^V* zth{%VNE*C{C_@69Ea&1}CR<0~aHczMX?PaR4`!}_GFTl?`<>6cfO)OANaR*S2Vk9`I+KSnTRvQGB4s-)vYVeqab>^5b3wv7{9Y0?JR zme2|JUeXfE-OvL}Np^ix+?@{*?=~0PPgmSP2QtOo^ONaNX0u@*4rRs`?9@@AIQK_q zUHFsQB&UaXBl6t63m(EvS>77DEHSaah& zG4zfFI^M0J_cQF>h<9=KhVf`=aX0kK;S-#WuD%C29Va8tZ)U$2d3>{AMO-5j@n!`j zj>5B;a%)liF5a=y$L>8f2#gf0bZ~P|(mr-#la6lU)Mj5$ymom!D`>;=B{kxxW^(u- zZA$ncEo(1+UQ-e6*R#BrKd-qmERXXBn6AqsXhwceF4%<{gcp2~oEqX+=!dRq{x#5j zNz1_@Xf8$2Vl4-)BGz(~4oB`+Vz!xx$x0&pTjAe2z!$wg033SGC^#`t!X9Ft$eQFY@V}GL#TuXhuhb zk(beWXVBT4G9O8x^$e5SV$GjvFjDVNX`jdj4>ivjd?KVOQ`-Y49$-uMb?zrI zVPbXp`$?9!peh63PckzU6}q1Umy?LQ({FXkt(>lG`-^RS;nETLVXzx2l+wWVzKZSX zx8hb591>7B+K^-(CBfNi+WMM7TVDhY+k+=D6DFyO~m6p2!`j!c`L) z^hJMvEG$1SvwtLmx=FO*{h!pw)cZ@cn?snaKFCUElhyn0V#)e$4qe4$^oLET0_Ka^ zyn(J_G8&pMexA(Q^lImeSjk}Vk%aqtV)%6!O`c8cVvbGhVve8Ej4;=nluH(pdE)NM zTl1wUfefAa+da-;C6q7eiMR(RCHSK!K@#j_H$6)iMXHCT!5_zE%?sXJbab6$_}0T` z>EcLDlH*Z}u~iTbXwlL2lHv4dFIq^LGz$q<dRMRCU z1uH0op8A~^r^`QHD?|)4%lR(g)A4Pc^jktueA5!=e&au=`j84l9mq zgq5+s2&WT(f_HDw`{pR<8?qYFI{+Um_Hg}SNk=u7PC3;|Q;k`7QM(8>;#iFtyENk> zNtH9?Z77M=cphqu3oJr49wjxWyuCtpj$;*OhGo3E2cQRi7&C!{U>on_ynhbRGnGDB z8XJ7r6dZ0wg;@sRPZPYfFo|)nRind3OjvlJOh!*!-x!3kHmnQ|Ia@5x zY9r#vU&(wf&NP}bULn-y%J{U9Rws;4JzhijkYI$oSCIiCirnM~u>wP<0hRd@zb`4U zH379|^gDj?iG3EBc8>BX2NOs`ah0VBBY z_*4zFZh0SGL-f)h%Rm9&0qo-@hvgT^59-{dLWu|TEX6$sc*Ii!_7Ne36TtKsBOzei zwvuw{vrkV596nA7dILcvbdI0>uqdk% z^&F)ZSrCaiDw9})q);n|JC+4wS%wSpSUL+2Sc?GVAR>jgILN31M-#h&GQ2bVt%tne z@QFOnWOVHe+fE%wuIb$?T8Z){yeB`whJ8+*z^y8Ea68aJlA_tY6B=gmGHyQD{fnCbOP9jI(jY^x9$T7`~EF)dh1=O z>~Zs#G!Hx?9r7(q!R1ClCtVnDC^s+Y9J_R~Lv-;9QM>U96{OHrJsN2qUjIV<%BJ<|1ZyxXTd$#H?Zn&jxp22he!iH~nwi>r>7>?}T2ICZm*_Bs!-qT|2Scxf7 z$`O=0JY_H0!_>`+*Uj`1b@$m1Z9a8rf5!}@ATmg)6N7EjaKlV8Woe+ctvOL3KH0D$ ziaLd&kQ8?XU!``%VedeGFfj9y{qWXDy*>DZ#u(nXS>D$6ROy14zc;Bz9D5iy3s{WF zfi#P^5sllxS_uKLX2D|{YTXW%1RlRm`|ii>1f&6JwC~w+jiQg&k4jEsA)CKE`%X&3 zn&5?At9MDV*pG!9^1)Y$2?#jA3#@9$Fc+P)M zoVCZZNq@<;)N?+{mFGFHmkznF6?dgaOCw>O9*ugTv6DMvq?l63e(dJMEH%3qljMB1 z%`Uap?sZ%1()Cj_^zKijMOK^vkE+Ws`t&ObB(CYTP@fXmC5$+!r4a#;S9F$MM-yr` zadVCe;ZDiecsVLO{s1~vrWwMv#qlK?N@#YRhwH-Y=lt~)juW~qq`b+7j_ai7t4kFL z1uOV!n+w^oH*p~gGwzrLfkj=u49DQ_>88*FMhp&BzZ zG+mC>&m68_9oKqoI<2;nIxjx4Q;FV8pV?>={3kSmw3)nz9 zlqcQe-4nean3qgb3tX6oRi8XJ1c}ic_0P*Mxd6_pOq@zSb4qlSBzsx?{axNAqvKQzKo!^L+3uFlmu-xPyuqZ4qqzQ-=HEy z{TZDdxAZ8cOhM=5zWqH1=h7ryU{P=Zr9)Q_LN=f|=u%e`C|?Il(^!@H01xRC!s#tM zJ(ne^Jc~7yr4RL)d;vcCtHGyt0i`p8K)rMo9^eT=!jFT6|{$VP5 zR9_W8o*!q-dHyhl{Xt+af`PEo`E=lCyexj;R%>8UFAdfUQW_{R4vjc20!4PoIw&V~ z*PeCX3QS=In0*QIsu#${9mdN=_CP$2bA=uiNu5V5^8UkqsU%G*$MS2ux z&Qa2$gutBWq{B*oG{!33@xP&t!#n_Une1NNkn6-E40pBR#!1#Uz^iO~iW*MKB)~61 ze}&0)uDE--HID{_FC@n(*ns5&X;>zxc=u3O1w768)W46uaJ||ks4|)QK)S(~$tseG ziU2P|vAwBs1XX4}DpMCxjUb)i>_#VEK@Cf}lwtU&4|tSB=tYM?r)`BCWAg3y%C>eq)~@uiZh z=2zqYE&Lk&uk!1c_@oB)4K}6>#IMGG3%@=QDn{W~KA#EqNVH#0E-unefXw)UX0!C! zpvcj%kH83|!wO%2iS;h@G;A(fe3{X#k9i5_Z-Acy^JB17qwiBhb~K0z(r?f-mzXKs z%LWq{Ox_cImN0%Hfu@Ys5%|FbBHf_i2LXorn!hI~l*CsJ`t^JuM3;M0KeFHuAcnW3 zl(Q*ED93eV9I{>9y~o=ePvU2K1+0tiRwe4 z`mjTNIHo?>Uge2fHVc+ExZ`ji!*#-)fx8G7jRF<+AbQhgJ{=rwtxRS2$o?^i*W%tENXOtG9Xqr*4Y9jWK8m zd~B!K-o5@Btf)g;APxh45KZpP#Tv~J3|>~~VLMa>)wIxoU`*Ky!}37hMJQMvB5lm%pnJGy^JGY|czF7Yq??&+xac-1 zx`g+Uyco-yR2<$(`oiz-NjW>k-Ln-Ur6=V`z<7N|opG|y2!?vset7dgVbTOL0->bi zShf$JhNT5IW!UYqo^1xfJ-4nPx^7z(R6;Z-hT^C=u8ot{-nL_nMrp_}$50h=>3s&?I=wbFS1sC)%_+}gKr&r!M zzu6-657=Qqe{ObkVSch~d)GzjrK>sQrwMKOajw)<; z|ETKf9x4c7l$p>^Il-iKenUwsBJov0d?K%Q>}h<3#OV)=g71IDf?wbAZdNJZ^7HZ# zS|-QPJ-txpj8gUUfkoXC%dmj<KNOKMw2S9acJs>l9)K}1=o}}G7Nn8&Q~_}}>*1^hhDNSz zH5{Y73V*xbC9zZtW~9YGY5A4K|J+dF#on*t#p>T;%g< zLiaB2`oZ0lZC79-Je5t*KWmv;5ZXB~4iOms@523Ihc_f8?ehl+J^GqNd=AVoVk1_&2i06@|}04@>$YB4X{K+?=Ev%h_gAP48D|IF-J~!?rz3@7H@fP1QW~P`q2on`m4=C7n40dz;Ya9O zEr5?wn97isu;?TdhG(dwFohv6quFtiA@C0r21RVBNSZb?a;%VlhoOu{x<2zOZUgWEuS!pAM14_REE|ADkEYfr;XIYzuii!?H5BD)yaIYni9Dh8;0F_79cu8-PucnGqV8yLRO zpVGYOe@1_5)aXw!99>?2I^xp3^GM%54D%{H(a zwH$Wov~>VYXJjLQ{L~82s8TCHKLb7qwF9)OGDg1JxmMNWiwh}LM<`0wx>*y345U!S zv6!$z^#PNL8qGJj{;d92zx?Gd&wUceFdzOb->^qI?}R$->QocP=JXh-(xRY5gLwZ5 zE+q0E5om_(!xj+f)=b1==|fT)XblAo@JP~2rN<_}H_A~ykZ@(`|0x}E+Xg{cV=uH)C)6V_Ro4D(+=Z{%jTrENTvki z!3-dutqGtcqAjdzFsw@Zr4;X;IPtfO5=i!kbV0N;rRaj7W@GY%^lSgF3VHu66}oCI zoQl6C0{_^78pOZF(zi_%ZJee}pqq>NUbqTc+Cx8Q>Z_Rt?KS$jUXXqY?oByM`Z*l@ zX8O5iZ%eGV8LQ)kIwMXp=?rZ1#c-k6{zb({P}Q+L^<-%anGo{5Lz4RgYwHw!H0c|! zT;Hp!?Dq$#EaaaV9~|#5|4`j4w~ThW$NB5u$X<0}ba8|K|GEBh74*MqetRlhr~mW( zW*=&_=q#t*`qNFPJD$X1vV(5JM>m5STJFZmaS1bu?i@|;typ|6A$jB7f*qe2c>_kh z&L}w-9z{RLqg_XrHRKgD(`v^zoBiq)pKvcaH!!ih&Ckt~ zfw<6Ano!b1C0~Q2DQ9u36Xw}|_es0k;+mPX1z*NsrF=>w&LNbN(fKhxGU|7<&0tuDBM*F8*NXIV`+>cnxJN5x(1fO-7 zbg-ywiJk?+aaU}qIZvkZKueZj8VX{n_oVK0j4CV~p`i^#eJTojYi(9w=;@>7@#_#A)# zgU+}7Q({u@^dI9;f#8ZMjgi-2X5JD-@5F5KAtc489*g9)SWJ|7e+H;2n2X9fN@h$n z{RaYWrhs@JFcwuSNu>IH2kX@()R%6T3pfy4iH%~d6#F2HvAz8zUGpO$?TONB3{!dD>^5qV zqkzTA4eDI6-k{zUg~71%F8uJ%;J$`<`WWEJ+OuK}St|12x1h5R1wR%F&O~)tus5i4 z-wdOP8*`n6=bZ?L9VMO~M@Ig%61i%Ft|)KN;LhSu%fe7yck`gBNF{Z5V)TdlA}5$! zlJ*1Y%=k|RAhL`~;iI8V5FI3p=mvF?W>T|U4+bLc&XewTqRD{^fC7JODOO8%5lPc7gLfMZ8CSQ4rNzJRrYd)t1KDTf=^$B&3rxbkAblh9a77D?%%#Xy zHIjPX0es00Ju9kyB_SLfV}Ykk>q|O+f~%N&X7KiIxCdQoDNa>Mlob%3Dr< zk&I8tWBWmAFl=}Q9NmS_QNGhn*cvGGLk^=#1$^d~bDHXgaVXUECC`2jy_p7Axf1;Z zOrQueY}RH?GvHuInl+G&EI0(@s z?+1fp)QFLYmkM)Kzv zIUWz4pChqs#FHEZFuZ^O@@iI&JAv^ktXAO?H7SOqhOjL{|L#JU}hnwu=Fl- z$qte;|3Se`^6yz7u5y7-`2385JAQ&+)(cF6JEl3R9vO7<9CQYG8)ASX&L99{1%HV} zz6U5@XU9$*qda(tlz!Nhi1J?2xi`zZK?+pvv&g0P)B zgtE(Mn@XeP(U1%WN=+rEeUN=c5G*9+>a*{IZgmRE6fExL&*CJErK+A@oDO^(Y3{3W z5D3Lnd}wuxdj`53eX7EOy}}&%SwNui#C4l@W1_J6CWUWz>N-c$N7RLsy;YL|wn2On za+t)Cl3+rEJRVtD54mGroe$WZmfC|bnra+6EK?8~+bwae zel}S-cNl#hmxGRPy41cQOUmPRpuz(>D7sG;AVdg%9+&Gh>x+R!e3{0Gl7FYsgL{nW+0 z+H&T-u$FnhE`j&VcWR%3CpnD%+9&Z4poblJXki%8R8UIoEp_^9x3kz6aker5tdIe? zv^ZWIE(obDj+el?m|wpf9PR``@^HZ7+=+nWMG~wG&h;nIT9=ymY?y9H;nQJAv7zFw zrgO)>(Qs1~Rg$0T%FTNtp-Hg(k$&u7R6;E`17r0N-1a&YLrCzixMdRS?av^bn~>B- zN$Dpt>Br~$BqfS_#~ei|g12j2Zpw-DAvajj;-#_d3*U52U{V zzW)Zw6WDSzSNys3#ZrHae}mCKAD=Mw=bLfLN!oG@a-iy5X3;t~mKk@iSyyx~DvOoI z-RoRMYe52V49^+|6UpUAdy@UOv)}jF?=kj!l>N4`-#6LsV*FzGO93heUL`Kaw(uRtuF{jM~$Lv}cj_AitdfaBkQMIPk~RGkELnu)I#_ zmEm0Go>Rc93>LX3-YFJ4as6%O;fV z;{7oDIB~pK{O}Mm?k^Vq`8m>bAnYK*zC_q5P^sP9BW%3|K#=L5e?>qWO86U2Pi;LC zx5uRr#|Eqsg6;px4=Cz%(`%Rs3Nrnub;3?0)mz+cO!QtbxlA?HLDa=P_V^t()WvU2 zY?+maafxUtPomRD_ zyV273qt($oV$Cp2ij-7Jt0C`jndQB6-}*bf=Z&rruc2%~PDLKh29xmAY30w~q)--b z!xLpzTf6c$wY9~XWE8_&_yRpKX6nXM$4FlOF_h!JhH`VX@BCW@a9)OXEBiYta0axm zJc^&K?Qsn%y?3&##EehkiSjDUxJRt6CfI+ZF(ZgQo73Vq8yh=D!zjY|_6}4HJM^P* zyb8hl8b708^Is^K4otqt{Kbt;f#(xZX@T;ygjz76WE>m-G?EPPu)g>@ezh8WX`uV_wz8kAE}QMJ09-~nm#~LFB9m!Xr%+e;oCtmjJgAOA(Y-j1&`w63-t@%M85A* zKJ^dF-j1yFY;dz~g$P-{orSwXp1Qtms|+y@43pHQ}w$Y!T(&rr4=sOOZ145c8z z*HMaAO7SjIs4d5RV#*(DF*$<_GCs&qe}*!=&^Lq1|1edhtjlp3dqi2krmSP3f9)t` zSsDE2HHip5eej`vAtl1JJQATuMht}Zie3VNJ=L)6hL5gHnIPv!9F#lr}>`M=# z*bqwgG68BvGLkd@>;C2%bi!h|Lb&yC)o@S3?ST6Y+&;L!!O3tJ;7m9ke>2=fxLI(Q zaIv4&q!Y%&&4ybECnM|tTs_?LaNmY2g`>awkjDi_f1{%CjP%j)C&3*>_#U{I;C>F5 zhp;aA^>FmJ1MfeEy97snb;wJ9?_ttefv{Nk2jOmQG0*hd=!LjGd{PbdA{_6XJg%r%Bc&4PY{shBrsBzZAEn4^By0Q)H zY(*Pa7nQr#l&wSjx)*q z$||NUoMCg7mD$#ot$RQa9$Hm?XJwHqBCzlc!QvUlZuYhmKKp;SzY)0Z0KLBso`!lbz6Za4~*P{I%5-jC#+t&$}mE~yDhY<$XO@0N^C~hVEHn^3Q2zMbK&f*p< zsc;^+9dPY%w)F^u+W{wRfDc!`5k6cSobZTXNro$j+X?4<6nQow46Y51%AJAA;!e|5N~)*-JnIIhCuf~A36 z0OdRZJiY_i+W{M{;k$yx2fEq{L7!s4fZGnY1FiwC4XztbcmR3eJaEnu#KCWXziip~ zWn(G@VN4-zyK|V!c!|+(J(a9*p z8f>}k-gV_}mu-F7TGy%vifl#Hikx9ST;6mD3B zR$y>!Wvf@a(b9$EZ43dMt3-`Kb<)e$xhg>2g{$rd4aSDDIvCIAvZlVBc&86NR5mTM zl~7{PkzVrvHC$(#C>oxUKQal^XXT(*Z+xmK49fFIb< zR=CQw%C>&hS~ugzGEEEhhZ#!GhqN%au>x$XDluA?qqh_lUM4Rui-y&rLQW9QR4lxI zzWjUw zEd0*%ea{btXM~@4d_utU7zPS&)wgwz>-<$e*8Q~VM^)d$hxJ~m`g7H5x?ffOM)$n# z*{XKkKdSy&^_lLgs!O^vx>Hr}RK2TvPj|ekRrhvPOVu7-s?Je0ziPH_Y1IndLS0T( zWz~A!X5AxICAx>I9;muscT3f+x^cSOt0wEFSKU)J0b3ixt43E{uZydS*BN!XDuXxL zU^Wc#CKzt;j`Ut*NH*N<{g!vCA;~-5kZ8EcyV6kPE%TNdHhH%iT!x3ex!yd(GQ$#Y zmLc1l>78k4FudhGiyX8ocBKsFByK}tvCG1 zyW9JF!*;_Dyg&0kWstm27-|evUXQ-E`a9Ki`lqY^L;s}yyVZZF-lczC|7!J%`d?T7 zSM|^Jf3N;T-=*)U?$KYYK39EO-=_ad^@r7e)9C}>-2^CRn<2AnCd&Lzp1xZ&(KfQ-&K8W^$7ha{dLtQ{m|-|YCY6b zo^R3k!vDJIIaPTfPkByM{A9&X<^GPxxS#qR?r;B<5-;@m>rTT83V%46!u~?jQ%~f3 zdlP?ePv?F&`7oCGCpHYo7bo-Zl@1dJp;OY?QlKyT7U_(jmkQ!A?6?0GopbxIS^TG5KR;-i)}-ed6K~r~O-|efbxkX~Sy= z<}I`bNn5ND*_9frVTnjF*{wTjTErmUUu(_JFlz%McAEYcwdlXK^ ziD1wl;ci5G%g8qnT`Y)W36&p8M`1R&fne36j0D9)-uFtVNp6Y4CVlW=LJE)4ei1SID83Np!?!5iA_bdKf zL$phux@-|<-<8W&yDHW$n^jc#psTEWSr*os%Vs^YZq-9;HWsbToi%6K>ZGJ)_q*4u zEnK!?&AOBc%P{g|BDkz@uGNY6rm?cIFUjk|!tP^bkJ5%MnW}g*+WJ)PgAn z<*})z_#{_ugiqxW-#>pD7?g%^G(+nRuiu}FlT#^YsZ!2rrJQx} zL0;hzC4PtE|Ci$bM)6;Pui`WDGG(P|FsQhL*NJeTI+4E-d8xkbfTu~y9tl3-@(j{Y zT3?@XC@d9D{nL-{5C50~-|}CB!|zq#%U6K^;awb8Dvxkh%O#(1AvYOXf5MyUmxX5v zTMQpw=&vu{Kbvr6xZ5>wcPMaoUIFf(CSDn?tbyC3z%?~r9^aw&Tp4aEV5oF(;+g8a z@(OStvR@hQk2P>#RN&TM0d8Q%mEm@4;0i4qUkm(Dqv3(-z}o#q4lfQqgi4J!R3UKhj=%kHL~t~>j47` zR%e1S_X=r~k(TIokCKPrZ@fYtj|Tormr0BLH`Wi2D!%%j2VFhktiI#>H7p&yKaaS# z`^2|t;wj%xei)g*FMR8d29NJRoax6(yyDmF<#K#G{FmSeIhxl~Sty#}Mr*0HN_utu zpp84y2j(%rA^9l7SK$&on%|SJ&HFPouTs`A#V2~yJR?|s1V?$afB#U{f6gPE_YWYF z++xfDd~XXveH-SVFsdrY`qB9<%vVz3?nM|}!+a!k;y>1vZPy5bX90%xd2qQ1r^ViK z$nIf~3FJ_+lS*HWyhR9Ki?I6zVf$t{_^BwPZ3Y&!Sx5)Cserd58&kujct`$J=y{o!wb-{vjz8d%#u@WfWHLpCZt7uQ&G=yxa4bq z1AH6&_CnMRd9W8EV2=TtM2G|Jx{)7yBg}0d4Iglzrx(hxQ1+w&)@(B2-rhG1K|Bp;0WLH4TNK2XIlin0AX8^_eQumD9eewixG|$gT;d| z;Ep{A0eca`4m|HDMLy6HdmIAxV+8DT2u|enfPYpZ|4QU<$Oj&)Knu_cdoe;e(FZ)0 zya0HBPS`^dus0*%vnK*RWg?`ay|Mqp9QJ?&a@YrA4tqhEFd?tv%Hfmq04MAn3D}bn zuzv(I62LtIGd8$3xC?MI-w}i|xYyu5g`0R3pD=*?HrxTYFX3kV1-ccu-^2X{?h@RX zcLgB>&IR`~xczV!;covc^vZBs;eHOc7p@!bnqz`+H{24q&2T@3dkgLq+zrPCVGi7* za4*4q05|k+f-n`X1nx(0Z^4~{OFRMiaNmRb1Kbg~9=My|!#DuV+;i{Td-5n?*k5o_0&p+jW59$%a4CRQfF}U&1I~R1F&N-_z)rwF z0K&UCzYMq^@CM-g_u$U}YXJKJqYh)e3b-Dy4R8o>{$C+$Kpb#4U@zb}VB-7m*MMz+ z&jFqf@U9wg0C3?E$PVx*VEBiG)C2ATd;sA8h6A*K1AvmhgD&84K*3S0;{h81{|mV2 zBghD_8SpW{a}2fvcmXi>W5^Ql2%z8-$O3R3U@PDa!0De7QUgc;?gqR7_ySP=8O#vy zB;a$vl+Ph&z#72YfXT-RxfZYw@Fifv7oZKe4)6fr0N{IHq7GmsU>D#hpy&i#7T{sP z-vN_Of@J7m^`lCSX0_Lx6;}r8@JRLWYt8 zGK>r-Bd|t2m5d~(kx}Gyat1jQlh$|0S>$XohKwcWknfUlS&rkp@7A*Ey@xs-e#yAzX08JSF`5QeaX5{~f1K?LF?B9VxTxUr|N5D)PZAMulN zG8JpgN-~X9k!n¥>7OwPZS(L4JfO?s8HGuItGxGMmgH4R9V;lB+Pq{g_-$f@B^E zkw#2x%_K}(u#4JCBDj*Y0PhIeNtDD$2b^x4B;XFa$U-=aZa9*kke`ypY4a3pkP$nixs9wMzap#2?PLwPgRCWYlDo*i;hn+1 zlm8&UhAi(U_mF$Z2J#y$E$<_n5V+k>9v}~r-(f3v3$|AtA`g>oc-QaK~qed zElvw1I{V$rzK{pd?#!NOQ@^CEwrhplpLVON3^Gm$K1Zb`C71hilxl(5OZgUf{o%~O zmsJOQHD`s`pZ2mOp%OB+A=4&JG3~UOZTAN8*I-07Xk*C|C3nyn2bF=64K%&M%;40| zb@Vmz46RyV2g)mwDoq_qU@g1k&-7Y9z+jErt6zEzYJ<8pZVq*}PuHi(ErVie6$YHX zTt*I>m0cUqEJm6EqaQ>p%|1!SQlzs|3S$j+U^Ev~1QSCs;N{hPZ(M6Vrg8bcH0amd zoMDJ(u+5Zdf!>E+`>0`|9g7;~+D;;8x$9&P`a&tF}H^ z?w?gr=dZ5}`YiaQ)#bz+(higP^80s;#_F8uk@_mt*&&C7HG6%KXl@RK;-Pk5Un4y@ zqcS<)<6uw@w%JJ6&;xLCDvMb)ECvfInB!Vd&(NOP+0}ycUGvjow3Y#;$p*b*V;o1{ znh*;Hj8&~?O;hn<5PD0JXOVrC_^Kacj>VyyL}#Y&@xR~z-+X}Q?! z90a9>x{bXl*<{;DNmFNi_m84&J>LXlX5qcjtERvRSjx%qxB;P*KDwwB3pO?OWZt!F&7vet%=9Sc+!c- z5@FRR_Y=Pb4mK9=!I|qYs^pz6Oowe{O1!4T?5Zk5EVJ4k{3vfRtlbUNY%-S`=_<99 ziVf6kdZ4PRJoIdGm!XFfuH~Vw=DHAeM+_6Rx!qK&)~?p*=?o|Qsk5^EuQyda4;}5S zkF@7&4D-_ry|D_Med%*TuF>aXFqXkh$vh_jG~j9{t@|XL@l+sfK)0Zsg|40%4@H~M z&%7gLrXK+fOSQ#18tPTkTDLhhvm-?eKU7w$_iK za@H~a{YCdkYsu6=* z=~ocmtAh35Oh)aIMAE8Nq2PdGe&-d`98r5{L2g8p8xCN@O`BLvP!RBbJbOrIuZvTXcjXrx$)MFTVRGNc+~v4QV0q=#x2 z6}#-Dsm#{`r@?L2VU5~1J-ghQ&@+gBFj`D?*FbJS%;|G;du(C8$Qds_8nkFG9yY=5 z6}DQVn+3#uW9K72us!v-ej&ck?FDT&B^%Q!{zo4yuq}FQg5597)B@S2{lK(?Gqh-zG$ZzH@;}$@~_1R-Rb$ zrMjgb=rQKW8(|YuIE6rPqj7_zq$)q;3@;k>)L=(vooy5&A?B4i&3o#qNpSURj z*q0-#&54F?rAXPAWs(%K-dxia4yyS-)ZJ#hWY4?Z%p`Z4{lsfo*_stHlor(21|0*?3llrs_I3~5CGX!b!Am*o6E?afu4Ql^x>n? z)7RUBd3CJ6GqEIRn?Y?RHIg&**0%Igv9bj{`^*`or>|}YC%qaq+R@lEBWIhzUgQQN zz0~G{kv#)F`^*`oXLIGP@i5qdo@EX>#BBE_hnPVy12R+1qwBpi&>9e1DlL4}d+@1G zZ2`V-#hn{N*=m$^plpYsY#wqJB7-z8Qe^7Bi~NSWQFhpXSBTt;$S6&C1KvcG9YG8G$HNkV=yx#04yaJ(lF zj<>|(?dt45EgnWN5N+xqds1}NL}K9JS~9f_r#+HyWpQg{s(SK9rK!EuCgcwVXhr>f zdML4gl=Y%KHP(gX?{V^Y3NOvyW2q9orMh7=+rr@va#>~FjLKS$PF62|kXugi1{;vx zGN_#kOP&S0!mqvoyH$OX%>5M%t9i8250mSq=`&|f4X`|uq*F!O!|m!80dC#|JGzh? z4+L@V2Bl4{ae_NM!61&C1;J~3B&v4(BE2M?b2Hc!Q}5l4?^WI$M#8^X5AG5Lr*?PO zx5i_ODl>^X9VD0}5yasrHDMtSLSQ9|J41S#JsoNw))EWql!9%ML?>>SsoY`Jhd+HV zwQkmo`kLvL>HfG0Y9LElq&e839y|<#@nAHjQHjRl(0n|Kd)A~S9)=drMP^SmJ*YYW zgTYW!yfYYyH3rpGe7NPLaS@5>Yy}r4I^vONXG<`Fn^C#XT9VIjPY8W(>gWLyZcPPM zX(GL7D{dcUBq*vpMmp63+j(caO*A$BNh#JM>>O@YBDz5Y9qmTcs|65cJwEy z1cbP?1O;hMUur}k*AJT&P1;d&+Q#4>&^=_^QAfPx<5N#j zJw);x4Pt#Y10V?vt54Z`s))1?tx4#=#NyN7HK36I^4O`O9@(2lO*1*ePzvjZ_d+2# zpq9?;f#fxx>(AAgsPq-a&4qB9*Xx&g$X6dWkYLVGD&66tcBjHL5|D^ zPZi`nGTY5_ss`Co9yy zSCgu$<_1t_wNymWwH7ggo;z)_*FU>6zP(h&2b!r6AC6L z1syF5PYpqJTQMH*%Erk$-()yQg#H-&kXkQW$7|;J*0Ev^euh_*Gj%CR|8x928*B)G zD!>l`GXMeo=N$d#kMXk}Fbhx%Py^Ph0HXjS0pEW9zer#R;tn~d$zC&koE!;H6EXTW!PaO-LH##2@&ydb? zO?C&|f?O@H@{nS6Mn{eVI+iZxHgY5RTK)>Yg};XXk{>IK7p4d<;TmC)Q0Ly@e%XD( zT_}&0i{;_UIAx8pNkK&z8~%}LYy&%-j-#K^LbTW5_?@^--00fj`ZH?nQC?9Fc;4~M z_J-99`B)PmM*=wi4SO&59Jhtv#~M0!jZioEgI`VoorV*>h+Wy@}pV&*3I;C%L8kCf?@=Ic{)VB8Wnx zaM0N(7D?^WXVUN8PrHYs2g8-I%EO+`-o0L2@W-8a_*3RHrjYg1MtTjsp01(~(Czeb z`U*WnKcZu~67CY-!3X%e_>KHF{yl!UW31yc$2E>y92*_aJKl4gaEuTXVTo{uuvxg+ zd8u=*bDi@==WEV0#UF^A7!ntV>%A|m4Asp$GOaTpYwU=ba9WwyXLr-xV~~# zxwpCBb9czAlz)PpLCCxow7%+kY~&DM(zJ)$S#8RO-=ig$+hD(^h+P2O9)+r3YDU-usNlJx|+ z8IX5{xq-Qbd5L+8Im}$Zma;tSWvkh%*cP^pjkDeC5_TE;3w9;DhF!M>EAp&BkE7XfY!T~YE5LazTMv&gm+b`ai^2D5b}f65 zeG^`A2VD4>OO6dg^+z;_hUVp>8c(n*w|JQdLsAFZI(w3Y^FJ#CPr`prtnd|BBbb6L~mV4HE)_Jyjc6fGr_IdVuj(AQYSxSMo z&|Bm!_KMzWZ>=}rt@pNi+q}!XtG#QzNF+k`LDd1sVljHY2|e9`UhYMYMxzJC;GO~J zK5!iXzsvZw{Ca*TzneeAA4hVQB1eg%!qMvJbS!qPbL?{Lb?kS1;ut5C2$O_bp+i_K zEE6`s|L+$L3MYkP=OicZtaaAIleRjSJ6Af_IyX3XJNG${I!`)_#1fH#Mb5?eT_&y+ zw~9N(qv9xOw8X$F+oTSu8y;x6v_e`fZIZT1yQRI-e(9j}rgTU;f-zm>Dt4)v|BBF` Y5=Lekm`-LLvkN0{94r@w|Ae3a1ALLK3IG5A delta 24624 zcmd_Sdsvj!_6NRa7+`?W8Fjd*D5H*wf;h~;aGBxaWdJY8D9XhPVgVwV5`t1*1|3Q8 zbxPeDTKR;J}CD$CcTLNmh-Ils?-X9h;I@A;nZ^ZcIQA3vUF zy?gDo)?Rz<`&#>bhng*tnhRcAjbb9&mORm-e=;+@;`b3sH>}=pKv|9als&4z`-F5< zV2O~94!mDThX<}i`gd<$$@mq&4_9U){cg|Lz|}%JB5(!L_C4p7Ed6fJFd;u{$=#)_ z4sz?Cj+jk^Oc(i(ry5mr-Mn@p9u^?#OUOf@6gjCkw;)vj8t7P2m?)J_6^#nAA0(t* z3)&?@UT1PD5os4~8#X|u5s?lbLd-7`Qoe22;2=AYR3_p6Yk)RL4x*hRss5^4Ijd0O z7ICI3LJFfQiWXHaBBad>S_5DfU^|Txhxri^A!6h%&>Z9xuH5%@oj5ES)(AWve2>3W zm=aY{yma~9L@<)TSR#eM4~-|qV@2B~zIQKQMTqsNq~6rsLXJO66wmPzk%Ief!I3#! z$ILPbpXI@?d=C5$7r#YR2k|4v-G9zJci2rqdCnwdR9Yr6_A7jXD2jG7+sxTHxw|EV z9+Hd>{%|EB*N=!Q2XJzm>;&tNnYnz`O8P+F;C?MWtOCXjD3j*!D_7BB-ouCOCW_uV zT14&0yK6jtoaJee_wYN^_L%qR;LBAWwb@*?JyPYWjj3|hCduI+U5VPlENDcTqtwIp znS$*ih3=nbo9SB7bF4w!4gPh^04`l^%Tk*i8k?!p%nz3n;#j5TqtHSwJ=B&Jie7dz zy#;0{-%nsFZCOeWCXeapSf%8zRS~+#CoHM~EuPSAI9%c52y8_rqSbmsvci?I-Wajc zg>tPk`M*`sS9~zjCJdq~pAkyfzPq>Iown19KH=h|K6IFWU}{hhA+W63)Ge~5h1O?E zXPSAjKvRPzo@q-{gJ|Xp0tt~HOpB~bk3=%AE`1!Arm0WYP@DfCy45_yk`e$#=}KFH z(r~siko%CI;g3dCNkQX2H1k`TPIN*+sEa+`%?@Sk`vkVyR-ksV6>hegu}=%Nr$^SM zq4xA~b!p?cbWMGlhHG9}FmJ*85^{Vfn}lq_=5SXyAEB4K&HNWK*r4b66?Cj$Xupm> zb;O~VtegRa)ce?030+WMC2het64H_;tW18Niz{@-pSbe`F8axfJ5|z>9*J`48djWN zPq)ns@|F@9MHkCdGc~pLN<*U(`+zbt8 z>fD^FsFTQnZ#FsVCd)-mDc;&5hMjN~sr?{AKkYMo=wWOMT)E7a zCzT&uE9K5$KjOS1+GgdN9f3O=sIsp?+~H4W_8n;X2y=s*CaFDE>Al$`trKx;yKN?^ zV-hr*u9-2LdAXqd8dg;aSEVSaFIPZ7;PTgSEO4f4C0wSgq&`C-Kh$jI50wkuinYsi z_6Qo7VCJ<0qWb%k&FSMrm}%G)-VHcWYBRqb z<(nssqr((|%8^g@?9$c_nQNn-su(;b2L}h2F4J9)NS9VdaOqNXmsc}X@@D=rRAMHv z3VoN+XhWb#Nz)C({r~0*x;~q~x{P)z#)?Ae(}o~gXz=r&?T z6B#jl0G7CO)qJy5Xam+39p8T#eP^1C=Jg+787Hdrv98mQDsR5|cZUOu%C(w+om=uODfp8q|A<$8i(GoeHTWhfSq-&6?QwBZ7J3cWm8bM!;ziK-QX6=A{I)U zvDB+90SlYXo_9FdtT>XRyI%Xnx*Rrx(xsavK6NHGgy@`WX8r>O8$g!n5GLo;eyp>u zaaocwf*#{c9b7;8p;Uz#QT$)eU4+ss2B=U{5Y>K6+>D~c`5la3sR4YvM1v2@eYDJ0RtBPp%yEB&3pomCI|urCDP1~@yuhk4D`%n_W98Z%Ef_d{u!KFLIu!+ zHLm6#>Prg)QzdGCYG1l1a6GjJnb~>dahAHKS8&h>|Lt&W*x-M;gia1hp&tkB6E`%_ zb;02**&BQpOJpGvgtKsBx8ePsv#`zjd+%BJd+%A;HjDplFng4zvtq9X; zAYW391?=5%|i?Uq?n_7y4UCiOHrQJqBPBYj1EY4FJL%7!~B88m7Xtr@vo>{m*!j0{xT?<6yK zMSI|Ra2hsK6seS*RD~wYaDIS=8h?#rK1Dsi7_K+!{}h@J9b!b-=4aDXS<}UuD>|8n}yf1xWtb#5M zA4ESIo7#8boZh;=xQm8GO!ms*)9Hf|W5=M=`8+IQo4IdEODcSq+S8T3T&9%stM_LU zCnvWo1g_>Y+4RkbL?0#4h1v8*#IyA6@&1Yrvjx4St?udgM&uQdQsvnMg{!+hkA8$^ zjhE5Y+ModrbFVq83*fr^WTqR($I&Mv{S_}cdAF%dy_3qfq8_2kwK6(ye9(ZeGJ93d zn+KIAGwB|!*5a}7|H6rm!9jGZ6FuvDhl4rM1vj}cv<+jN2PB|kbGw>#3a1lp~R^eY_>$7aEgb~(^r z>%yqbtg<}(4HS4f&`*DjruR6|?M#=a18s4$1qb@D!1i#U3*BtNfgTR_X2E}UI?g3r zdQ3@uT1>A4O?Sok-@!xP6fk3c`eldXuU+IZF7BOOLdXuIly`7 z!E@waa!Q5+=W?AM@BoopB*x5hPQHefPlW>VRJfJ!2~5J& z#bqcrONQ1-`lcCvTk{pS_8KMtT^AqCOnWsx%(4?FV2_u)%Izhm-|i)6xxM5pmzS)> ztm^fWLFM27%CmK${MAdhNMJ%V+#;do%|AGjn2pS7U21YR6<#vpcfk?Y-l_n8PazaA zcMKi`;s9Jf)eh-`UM`530(grsL^Fl?PNsT zh)n8DGX71$HZ}(E$v$)%mwbs9CaOY1oh3Yaxk}d4&ASo@-PxJ{ATgYoeJycxP>%y& z&9k}%2Y$yS4+mcNFVNwYStj>5@ZtVv;Po=%a3_&D?@q6NgNt!;(yb2svWY_XG6#O4 zF-hxQ>Z@ZB{;Lz9e4^_FP`XZldwS14kGqs{pVJBE!2T<-gX3}} zv@Sgq$&kAAA+*q}@q#x+2TO-Xr<}cQgP-vko1^X<62-Tybb4rA8cL@RsY@F|&zOh1 z>iyfF>fIEO717T2))LO7z|M*b9BiqWS|%l~B0||!gbJ<%0dW-nqX_$Kpjbg@wNcFm z|7QBYkkAz8sH6#U&Y?g6no7rK%w#efGTeJd-0z>lwnOQo%=`<^LTpcD6Vf>yBVaoA z16Qa##2qS2Xnp*so=b|=7H*Y{JBe*NqE&uyj&$ZMA+Wz?1E`#b-Tbx?`A>^~7rNQC zPMVT>*R5-7SSOr&?f^PVi2!Cl`nfrsndMx#&cpn(-Y)G8bQ7nB_jONCIrkd+j}Dom z?!!YV;xx8ZNRrs{pl7Cz@PF#ub>v=kV$S`t0%ao zdP2>*A;MHwkt#OTPa&{$vM}K>*;SbIqqu%%B)CXKgt~)4Xuo(;B_8@dB=88wq$p#a(+!k>v5pfk-&SFrz(1yManwmMz=oVa^USkO*l@qvCO6LseW{Z(8{K(-*&{U36ol>0SBEVSgfXtvW8E%HJbekr*@4g7!M=~e;#~o?0Zj9(7 zwjqgg&e1&coMGcn-L~;0pY+^#$mjH=IlkYYx0uJ$vcj=+?zF|QiRih(EW~|h7=3x> zF!4w|ZJRknoEArao*66N`#BvoD?+^bbDBMCA@f9DpJfpDX`@$W4HREJMP=E8g8S&5 zYnZtif`fruFMiuOnv^|EyzCq;%#O4C@9x;JdHm=5wI8qvyEYG>n4ZnUefxG?*pc0v z2fKay{e;6IZk|L#W`~XZUztJY&mI(+(_2f0j?L0Z*gE$L_2C}QbL)&eD>T&aEE*a? zJ7@bS@3=4d&xz~9!8q3@^n$i$6G}S{DmJ0*I$;yiYH!_yI_6Bb?8J_M+sh-n*^8at zS0%^K@g5nRQY|9(`iDEr?$g=dZuX+bL*$(IR$NZ^5?Vy;bx^N7_EmQ2CiS?*W>xwq zR(nGgeK%+D;LttT@4Fn8eX;ke;rz9vNih{2>_rd#C1-d)_P)oqTD^Iqq;8U=#Vd5r zbE9%avpr6IX9RoO+m|cc0_pW5;>xtr)EwN!tn9X}>n?3Tt8@6X@O`omv) zTMtX{f~jUaUiqjZ{s(iMZ-V-|)ZB#-!h0}n&y$WPta4mV=WtchT!GC8pc1Z2o@>u3 zos9F9w(1>|jh!@OD!Sm^P zF)5(iRx5HHfuX>-90}K#Z%IaLawVMns=S}6i*G{qs$7xTbyZ%_iVa@6u%JY~%zjm# z-{-(S+Hd|K|Gk(-SLJ!$JNMDp`QwatP#Jft%5YDW3k#s#Bz5U~dVY+BDJW26yKG{X z@GbBRxNHd*;IawXUYl}V#xN`9KU9Z_QX(IJ7?PP?D>KkEb}@I0w);J`b@F8{ZJk03 zbA8=y%Udud4n?ia3S8F-{Ug}Y1;;?>DW@%$knORBHAd){vkS%w?YOOPA7f>E`?k)r zEQZ}#SZD`#Ydcb50&B-DBQ?cSTPL6B(k8Uys$3!%Qd=-WMCiVPa05!$r%AC~t5l_h znAiLhxMs&|O0B&Bvsrh7?+k}=LM&vHaorTu}@t9g^ zsskc)C}tN?{38Dzol?-sI;KIGX8j&w`=86=)1%!Mb3WWjhgph-XzgreH1%*i7o~ek zbgxt_6|A=;O_zhtEgWKLeV!;-DA?5LMjBj5QpPp-_8Co;ZbpWi5dx3T5>cs2V(%0x z6-mKJs=}Ju(ZPZ$rMraPMPV;NnnwN2#opzjGArq$Yx-JB!@- zW-hG;htC7udQ@7#l*4?yG21JG!Zj|1d&S7?ac3mRw7N4=WO#Q*fsE`0rxANq$V56b z0c3CLo6NeV=`YZNMM05nd)j`x)gEjof;~;3yX|Q#Uo=!KlG2Co{s7OpMT3Wiz^A-# z^EAm@?A1!mjqUQu@7Jsr->l59x#3+oo6@52K)fatIn1G4YwfWr<>pD^#58dgPfr&` zMF`i{4#d_X%(p6;&<$$#%C2Wf(E-+uQ1JW2iOydoO!ERhc^FMA84lu-lC&P;hbsDJNf?OdN}|N8Rn%|sXi*4_UaYc2 ztDKWe;j9;R;?yer9kYjzyd)5lr4ZS?g_EDXL3zSTCVU>@h-(?1+=#y)!%G=JD?ib*p1< z6EG$s42^qOjMQsMIKHfjT%twKFI=J%87W;dc6(V6{dmbZkVIwCAnD4qw6!dp+R6-| z9V;_hN^sefBR}*@ZhdCAEzK9ZjnJWU@CwySXqwJmzgAh7<+V9eQI{)jPM3JqWqFqv zj;t8U%?Yuk`$V+$bev3VOBK~+IIKU3s;*+JbGfxrVRD5ys^FxdEOEAsHH&>}zE1efU6vST!Z>CY zvuSXzO_&LrT?WzdOGAdKa=Ff1`V|K_>(;Wtu5P7Q3YD~KX|QN1wJp_(%BdaCrSum8 zA9Zgc@J07dw3Odw@yzU7yAU5s{Kqbo{NKB9^q>3iHiN7kLKo&Q`>(rD@;`Usn7``6 z&qI116LE!~$*q#8E7 z^uWd;Qg>bSjpf=gZdJJSW-|fBp$^wFlI?^k2<9+dvwR{x+DeC&4-5{$)hZTRr0%-z zG-D6Kw+ZqvLe1qWi*qHj`6NugTQ)OhyW0o%IH0h@Z?xa<*HrD=t>p*pBQ0>UtzEvW zvK;E#(sFFpJ?F`JmsC^8Ue^he=SJ4-B^KwIwBJqQ-G~Zjt8iSEx{zRKRRP8Tv;YHO zG9VL>18{G_STpN8BzW12W#jUsTWY)ia5xC@u4$-1e39!MInxR0YK$WB) z*fLX@D)PnG0GBuxT|jfW_ZLzfC3+z&3(-q^23fRA9%+G0-LhJ4^lrECbkQHK)Oy z4y=>>3Yr<1qvm(eW&^ui^AoTC^O;LZouK%NIy2<-1QFM?YH?CqNOfRzG!oxEDp zVyRsUl-4{7VmYu~o$OM`lSl0TfpdAG^ zZ+!uI$Y{mMOptap}SR89a_k;Keh^3-?ft>}mc>P^qp9eN#{U~7Vz#>Is zz`X!0UX%ok2Nt(p3vLH6g(wiTPGDi{2Z44CSit(ez`B4*L?Upzfq7Ydyf6tdaxyPJ zYfG&~0yM;H2v8QN23z}sEd!?UiUmypEXA4#ni5!qH40b=Ftyh(a6^F=dKCjx0b6b@ z16K`fwRIh^aA1{Q_kkM;EZdp`ng-Z>uYAyAfMs}PT7bp_O}9=2+X&3=^-pV)80!Z! z5!qAL54_k7ujr4Ef$?5H0?Pw-(fSRz z^MO5Q{Tr}CVEeuHfm;Me)zRejF3?gC4_RLWdnvH3UXOrQ4(u806QETBs|L2w zYdyGYfYpd=H?){)9^SB7++y1JVw zxa->u-y>=05MQ!@x~EJ02a>(NZMX{R{xl7Cty}Q0-e#Zv2p^Flk71J{h_+1Tl&rV+76VdwXeI2dxTYH zo8-%VRbR^k<=$o5T^^xCTDLKl)tP4eqskIkWAt}a$!m;qN0pzOF^Ln3O)%J)$~7lA zr%_Kaqd38K`N7EsZ*WE?$s*DuH z(uXS}BTU^9=PnhqDR1#2RkLa=lI~U0H!t+rZ1I*K{J7-sH~6Trr6iz@DZN~&9z2~} zAhS*M#RR$3hb^83vKhM5XhT2UF{-H=IOZbuA{L=?sWFZ=qo^{8Gj(4&$B3Down;b5 zxn;~4{?K*$K$T&LAE>#!5^WH^Zer~cK0OsC6g^cHBn@HFlDxK-{#X^_y~OBUSxo&` zCIseWJ430q+S3T7vLuN!BnYMEt{fF0OhIdhiaEFSE2oOXWc1UOBM>UxSUFt$SpXff zD#W*=k1#i>an+c4Ay+ZI-caIMx1h5`e#UgAZov&cYY=+b#(1_lotSV~KR3OIh!f4q zb(j(ARR+~96dW62bxa9xj)|0TzTBzO@~7~fqFJ+*Dyk=hUSZ#S3hgSf{=2Vy!)wCj z|GzODworO+wPAE9Dk(w0G*5o$a70&qt(qD1t_n|`BSA>lC2()3=&9<+kxZ5ojK!#l zpvh%pZ8#WZGBdscD)@z}?vGP4Erv8{Ro|I-<GbDm?Aif^ZkG;Q8*ZntU4>$M49OKttIxbpZ{nLx9k^{fWBSn}HgX0ae;t^{ zun$Ag9SBU{S{rLYV9LW^9*a*8yfjDrHv*`FR9BXHkx)lMc-(Lr)yfcz|nZ1}1 z)Ur;#JuZ@Y#zo$Oaq>e)5L^1yZiq7M?E4E3p`l=509eGcP&RPC1-InF8JBGf~ zvc5ydA^iLh!CF;_{9xNn`(~N8ZhEl4{9r4{6&+j^F4cL?$ClYSGuKgdf!#KGbZhP{ z{dyAqoV#CHmvW|%Y+Q15a_4gE7vP$My)JRalo)3)5sconW%$B|4LCwD8GSL77;~H+ z-)#uR4H(AUY;3u-a6{;vTW*I~weA}Y_h^RnUa<7mY@3GT>Imv* z)iDE5A8KVY40c%Qr44F@GcuO_Wn>(+%)h54xCrUd=T*NJLH2Dbw`0l*)0D-;n4dBm zJ{`EjD#O(oJH-%1cVkzG(>Zk4S&89@qG_i!O1!^;sy2pgukoIaiw{L_)BeJgKiNU= zXa@`WLwg65jf?Y!h=u5eKG?3Ge{hWGO?v9Vp~@ZjGCCip-6soXH;weEV}w3*^`;piM{%Tb#e9p21tSjrSL{$Y1TH;Ezuq)jw43_Xg<9C_5_Ve{ zI3Gx}56p|r@LgGDNNJi#~MHa}6n~m(QhrR2Na3=EH8X=WDSA!I< z{GZ#x^0nu?5&C(zibVLKnuzRX%;z>D*Wz7`Co{aodyT+FFyme4!pbCh_t;5G%@*Xb zDu^@Bp+jNgbnmVKARKNd92({%lxFOv`uYfI75eJ3H=jk9)JIwNvM#;M`hf7yfswxv zpDO6=m)fC`e+0W&o$1>~QQd-z*5YnrP1=c9Z=}+<%$G01ncU*d@^A|X{{cid+AE9s z#W>+hbvvLn3WqM=jYo?_-LxHqA&lV1%1PAWc;8m4-W>sQ4ZN9rjC$1=ey&rCs#L|; zN<8@a0+-c9Cu~;rJ;6@$PHQr$9Gb)LrOP)DwZH_OJ(W*DBaUodaM4lqEl+R`=Cdi( z%9?kMU83xOSgqZHJFClC8PBmCZ$*hZ(}muaiG`NsGBaafiFKsVT=yKqbs~E`Qzhl! zV;z;RJGRj-f8=l!cbI<-B7!y6$`VZ>ea@z&`A2PWG$994^+pn~vTRDf))a-ZBOg`_(N$Lu$}3 zEuv~X1sS%iuka&bU5n2SCJ~%32<&hRU}H~{wD{y9Z&eX%AwI0fp=q^C%zOz(BR`*O z7G8STCP-RDOv=p9W^|_oy@kzu5*=n6TPQimUfo_Z^KwWz-7c9e^BSLxl~|hRW?n@% z9_J=VFtFZDh0GSmNClGP$4j4l2%n2PVqr1CN1BTIrD}x@5Yg`X?D~LhT0qVw%m6l* z`6blnq0B(`n-{3^(%O#{?Z&kv$$4*=gqA*}T5?$6RQmFR(C?Q+_?MA4^DOfF2-35t0PTZH50J;1lg!$j0hyN81WH1(dKE3i#h-Ed~ zZ{{c+RiTcm5Z(rMe*S_Z{1_mpO;*~#X4VcyKEm%6i1Llwkh01jVdP5>;|YD%wNiZ9 z)a>1a0wR7I<_=#44h+J3Luf2@X8ciZ0V{X;(g6{^G^%@8c^C7?P}$hp>s6zi6-t=| zNGN(aw{$ilf=v?l|D6VWu&S< zTO2oqRUqZBBhAleHbYLRpF>@&ZtK@!5d656y)gCV-+|oa0B1Ayure@uu>H5T5hkfn zltyl2ZVZ?lKtmlYwo zTym|W(vLgE_s7d-$7j}NiQ$)uA8>=hL{&_bJ(y@fuk1zoG!14uCb4#eXY0P0#-Jh5?sjlVJxxkSWa&JkWWy?w)Skc{8{dodG)^at0eVV()wH( z`&}aoSGv|;S+cBn3TJAMT~=AVG@un9gq4Y6(~Fl?1+?ask$jJm0nVaTlTesW*`a0j zSWk)SlgQ_kWr%CIxVaEA= z>{s1*6Nd|cN6ix`wYa zt?fR#W7aO8DjnXNj^E8X!P+Wy7Q`eV*G-+O=NPrJzqM86q+_iSfu^$yKS9GZI-;{D zc!xlY?KQ_8BX?nx9V532&n?1pjqt1%o|YOR*(f~s3(vj6^MLT|6rLTzlNX*BglD_( zJTE-Y3eQi3XPfXmEXHhrl4Z$@$o6@Y^^cQF2R=GN9P%Pf zepDsy+(!$MQ@luPA5H7uhLVsOc@`-?N*Jekk^bw^_x;15p(^~`xYQTvzQ>|fF8$aL zJoU4FcIp59u|%=-MXKLvV2W4lG>W_Mt^CeJR@;v|hl}m_gy!);f4fjyexKHTRP*>q zORJF0lbmqU^Y9yd$H+RNhu*={qic?Hv(-}DL>V`=Q`gFW*Wqw9g=0Zo!gp>CK@4|E z*2B_E|Ev`*o2-YGmwvzBg@#`GnW3Hv_AmuS7N%i~OM^>6ZLfm2dKLWLjjAv0xm{O2 z)3ukWn&38uS>y=ZfhJ%>@l1M*xPVru#<7wYSV?wE&t-O8;#uu(LwU&jfnOvvO@0j` z-)(*;!Z+B08xMp zz(&xDkUjule;ZMz48Z;(e}0Vx4I1fgy)F91#hS^@6>UIVZ{$xq-zE(B>` z0Q=kHQhXix4dC%e+W@Zvb^=xc<^!ezi~tQl4Pbw7L4NO#!wES9g#C58(t;gq`@x?A z?@a;pYq4r*=u6nm>WG2`NGxz-{36hf+VD>w9-;-$1dZC?lO>9~78R)$Eye%#SX8-W z`7%PfdU*7SXC_)U?k9?xenjE_=>I2R`CnJO6NWaR5B@KPvMwTDV*p-uHr76eDC`S~ zqP)-orG-SHSVR=5fWo_oLQ_N(oq#rgy%;G#RRTJofu)N<2Q=Wq(hleZXqF&y0Bi-c z0XkW}4C4eyy$8d$6f%H9z*c}AK<)+4f=3%*>oO<=XqG!GQ@AYc?6DL|!DEKnSD_Wv zkbQtC+5ybat*fDI9drN`XjBbAQv+GR|7578$I|t%c*9>?s~?KdN!@vmc4FXO}Knp(?3bb~l@% zD&R%MKmFog8{10Wf2{F?_-3SMag5d68z^#Q&Uh1Y-wmqz$wJi6t@nSJ2@*wH&| zfhu;>A6^VogQCImbIRdv0!S+I87>;*6MFci0kNJ^Ogayo>f1`zA-~l{V|<~c-cyQ| zG=gLID9KvdhWvSt(ndnxdnqW%Q;Zd@L{ZuPUUOM@h9Vyc@GQ>c#LVn|Oxo-!VRxI9 zzu!e+I$4v~ApedBjnUa3E8!{2XuCjL>LJU@XCTk$LW74h?lpkBURH|zv4*PA{k+gP zy#}a2cRhG0V6;@gor<1?$`BFj7ySjGo<&2j=`z|D6urG2tk!bSGlZg+H9$R!W}v8> zhMNF_kJbr(Fih}YX9)hO2EkA634Tvc@N;;ApSu(Mke&4b!7sE4eo{^F(=vkJU=V!& zPiAFL&i0FvJlOr7rmCMVi z_LW2*5)PSgdfzLfEvn5pAS;WjE7kWdV^%V2*uPkC(yE1(z^=HWmazXerH*AXxW*9v zAyt${b9c#NtPFR4(yZC)yh#(7ObBSW9wAXq+8jp1t(LQ#lQtJ53sK)foFWv)?U;w) z6edU_Z=sn5InAv!K`!PN+H65C9<*L#W(#tupq=-NhlQ^HqlGh->|rez^6Cm!Db_AY zMe3rhsAiqO7_ZQie-DN?>ol{X@^1B%2|`tfPd#XJg{ne5X|tVj2u__Qv9hzBa`3Oo zPPq6{LN#i1J}fxs{BL4W#m=hPe-�osEYD1A?D%z{DS%+mmaM@JkXxW`pK2aQICL zTm*PdOIZcZ!Nd=0*q?}~@r-gc4I2=dEpp}23ve;W8Z7&$yH>0a#G!ODlV4miZb{J! z_5A`-B_f54Sh1qwZnY+w(F#GUVTznI?Y3bdH2l?YRm~I5^}rzon>>nixHlchwwCE| z&9@Cx(uP;1;dYnYhc3A@NZH)}+9l6Iqq<&sl>-0p0ZzRm*p&`N>ehR_M@~YwHp(V$ zALFc>)z5UYR0xqO6lMQ)|u4^1RaroFjt0{GJ^N$hk=jME7c zZ5|TsE{V=Y`sM3kqBuby9R9z%l6c^(l8o1dN?uN65+OAn5?fso4M^#MHcP(k zZ^Lc;HV-~4H-o#i{O$UWarm&&vjR_nr?(Kry8y;-v^i5HZhu+BR7i~g#$=~2lR@1= zBbYBS%q1_J*|+gFxp+>UXn!dbvBgo1)U6m<;cRB9r{dYJ!tNeA>(SzvZA6g{U}Zf2 zcDeq`;c)!gf{ognF5t2C9Je5M;2lh}0oaS+0(BaIC*g)U4J$ky2VEAx3|c?r89==m zP@aP{A7vN9*TC-Iz8qRXQ}u_AL_)Tjz?%UXlu3m=evl>LEZ>Q`8jMI$hlN0SIfyk7 zBKY?!3}?{38_WM$cq4mYB~tvvj2uM@SDnBMCaPdSDk{oAxmhs23IHCwWC9PHz9%@fRdkU@C_9|UeaX(&VrV+x@U!H59ugVEUOked&FASzWQqjI!DH51mt82I`G z!HJN<_a}%41Sp3x1_($5fX`1DAUF}gyacTSXk4%rDT7WIv>|1HphbWKFjQl~`L3yf zBJ=ic<|S0fGNd z5C;$ia76(Of%k#9f*=4Qh%Ly0LC}RcVj-*`x(cBgLDWO+P^MwsgC0QiL-4~vg5MvK zt>vh2sS^-p5e5jg1VFe&7$D>l0AUwl(22?so{+{ElMZ0IWD_A>>6M9|C>=DE^824nPrLJK$45NHdH9R0H+^J^}P; zA!IG!M?hRFA?pEcfUsjQ0%I1F$A5;qf{7|s#01@JF`;&T`RXaIZ%82bhEe}VD01MxWz-vqD=&;c;~3qQgD zGyyIG0>30=GN1^4VZQj_h*0~0Es;0 z0B-}NmoNt|k;X&st-!x~u>Vf~ct3>J*!$7)BNBT5sR7jgeQjgfks@*9pypB$EpK&F zPqhR$mbZHQH1<37f{0%G=y&?y$NlJnk5|%>Ey48C$KiDSKZgkEh>t^sbixsqzf0gR z`a~`8S<3h<1;268Ctr%`J)Z^BfhPlnwCa?SrH$u5yIUk-AwQk>X^elK37bZWkbV5t zto%&0e_lopcj}pFab8BF;as{u{qoy|H045iW8H=Q;>N8P`-wmaZ5(o`)W^cSWB1?u z4qy$~89ZovKwAphaSvMgk62@%g28dRQ(u@+ zya>d-5L9>w9_YkWZP+#}=>P9mp?z+-3Z>~+{%D+jb-IYY_{;3UA*7_DxR@Q+_X^jV zgbX4T#RA&+$1j6KH11a&4gXb6gMaPUSoZ50@%FBf19v+;pQw}xIhFU97cX40tYmp= zDw({SCU*_Srv-C`=gKbj{mj!{BLY0+=|{~2y)k5v{h@0-_=9fX**NuvLo8A?PVN3i zWErK6)xN9!K>L~Y8*Q3yj;=Z8)0nSgll7D0lH&{GeG)@U#s7te>Cp-ID4Fbd{F#|_}uuF z@wM@9$A2CF@A#mERWdlFV9yqxe;f^Xu`M4I?`;_*b8VS-_r!D4vQ@SNcz!xsjb zae{H0vD#wXZhYL>Y*Zu-N=i$*FKKns-lX@FjwSt)6r7xzoSFPU^2^Eg0( zN|~CnAm!ea*HSK~bf(-$VO_#{#ZS{;qtzHRlQlCnb2U|(hcz#0nl%5^oYs7$>CpV9 z>DB~BkB|N>=Cjy1{R{e(xM$;9;%>xkh;K<8Ww4|hmKn|%a+3}weU@}HsU-Ojx+Xov zp7Kq~zf(xL(DP(~CPXt#GghP17&Ru%3{9@4P*aLIP_C)eRBP5~YBU=)PiRiYeyP8h z_=F)n`Gw@*lufKxYw-R7Ns8uKO^b$L*jl3FwYl1L+CQ{$y1lv<-A@)>Ma(|E|BNpB$GLcOY(T{5$cV$A26DQ~a;-feC{Xh9!(n7?+?+NKBZJkdcs;kdv?= zp$MZ}nXo3IE@4~3qY1kb{+4hc!Jg2T(4KH9VS3`~L@x2!#Ky#Wx*QPP^E4N2RRnvzZ>k>nxCy5z*<3CRV?FC`zq zygipfwxSs#9Alb%wA-TLG*4>wqk}JMe$rgi_(UtBmqo9Rem45W=p)g8M2BeATAkLY zouaMQ)@UEm?$*AnZPdQ0{il}K4%8jheXILXcT*P-qlnR4Vhk}wF%>bkn4K}I*fFuu zvDLAgVjqe<8hax4^VsiVe~K09W%~Y@*+Ve_$LckDz22ywh>17@Q*o}oP+y{7s;|&j z>(}Ww>No4p>3RKc`p~%KxVz(CiffE}JI)fnDgLeaV^|H!gqaBsCw!RjbAnG|-^AF& zzILo-!*kn9y#83Jg;B-BF-Q&JhDd|akZQ;<6dKA6m4=Pz;H`$eh9<*1hU11d!zYIGhHD0i zQECh^h8k5ywK38-*_dH88%vGV#x=&R#vR5z#=WTL9pfj)v&QqrPUAJBEGaZem84Dz zPckN@CgmlSCM``WPpV9+OWKmOC+T&J6kHr~0G=a8#vGj&T^PMIdQ0?<=v~o!q7Ov3 zMW2mskM4+8YQwb}?R4#IZKbwOyH&ei`?~fMZI@P}lj$OLX5D;Uk!~ZV;_JG1bmw&> zMi!%tiHXU>m@JLi5_2HtotUFB=VSO7X{;hPG}aiK5nB_xE4Crl9@`!p-i=L1s#joe oLNPe;`cw?be0>oHq+DOAU!&iu->*NQC*-kN-lA9Vny}{o0YXS?eEbw8I!fDn0x7$iV|06`?|wHIO0vurjYD(1_Q-N4Fbcirs5 z(ptq9ky`o?5f$HvRI8$;h>FK8n@{TBX=CbMM?cGk4D1d+xm( z{r$SX-^u3tcFvjqoO9;Pd*-w?LsNUMT08&zrRGnqtz%VN+v<+Cn)!W8^s%+Ay%zp| z_k4ih%>e(p9^l`u2l(Rs06%#E;74~LErnqIjUgQ|4uPPB%R}mHfk4m&VZ;=$7@FWO=N8cUNcRvRp=+T8CJ^5+?LH{)`qTBE{(qqqr^dGYTf}TQ| zNWp@~LON;@1W53Mu8_Wt`3ZXZl#srD6n;kf!52b$VhMnxJMlNt(^yWV;NsImf=3Yl zBLM%4IzS3)_&pN*Y^kJR(Ig0hFQGg^-x~<&OQ=6V-vUWNC-Mrq;MtHaz8mEuEqYE8 zdC0F)LEpMTQqa{4l2+aTfuOZ(B*9}1)Cbb{r$hS6Jtzn1sRbcDvkXAc z<9CJhZPbmR#}OA&a3tzW&=J1~Y2p27Po%ELLt1ql1cKInKBVAs2n5yckpw@(ypVzy z-Yf~e+5&=t`d~=G)0qBgfag&!NI`2u68wBE2nrT2mIPlL21(DLJV9T5ETnJWj(CxN z(hBh74?^&Q*GPi@z6m6K^Sb~@!7=zf5`4EqQm_E?L4qItFr;rh41g3I{e&d=&PPB{ zaO7Q*;Kyj!qwbRgKfD}ykpAT^N@sjoQSjzzZ0|yu?ea_5z?_s zAP{sM>KqBafxdwh^z4G*(D#Nk?|Iba^H|TZ?g;uN`XN$q(NiH^h!_N&kN5BVn^K+qxGlHgYuE0KcpR!D-MK7+bM z`UTb*q~N4wA-(8&2n2O645RAHLIjobS! zX?AxGb|Tm4zR702yJvmp_TIr}SLgQbfzH96W}|;%YI@_)`0&`sRAczM@u7XAvm;}T zM(f5d#Zzy#6N%co8hWCkJy(yoWQk<;D@Ue#rluyQ8XKl2W+uC4#;zV185-8JytK2Y z+1JzG+0%HLlFDNed2|m=4|%iL)U#oOkwIRL`sn`7YlcS0hOQVJ@#cVq(6ivO)u(3% zX8WZsz1eKs8LNrGQJ-SU&Yd1{b5Z9^U*9t}GBnjcG&Qu(tC5|FMi?CRsgZpX*No&4 zuQ?`*r#>`1oGspR8x~J}-_X@rCD_#2qbVpqL%rVOtFn#$&K-JqsL3ykP*7_m6|Nd# z_4-O5rq0eCEwx5xm-tu9n!}S->XdN5lH%m`dd-Ktk+^VnLZt;q_{LZoDq-2OOQkYW zYRJiyCy%&rQ6m!>$CpFQqV()e+;G4T6`h?vLvoBjf%eLcQ!D!s`KQcBrxUGJ7ywlo z=@{yR))u2NMI|%pRIBDG3tL^I6P%QO5R}GC{Y4-|Tsb$Z@=yw-k zb@!uO`R&Z=NRdpAo|G$XxHE5BM+CO9(hue^~l5Hs7IdEWIgim=+-5Y zX^5jH9o3oWYig)I@qul=g5~5!#c|8J#`pt;p<2>5R&r^r;aVk=8Rn^Khic zOH^XtaLLDGjh2X{=r&26Gsj6@4!hsyO6;9;_Asb8;!2XYujgn7ON(>(nri@IR1tkX zKmec^oZjY2oZ)U1OL{(lLSsk6)NDW|quaNg$Ta6mEviuY$O#08ce^sM3zPP6FPF>9 zQw-jrjk6FDhwkSosU;n~oIJfh)2QKG04Y=J z{@^Vh=_;wI=)4@F zbeqQaPY;dn8Oc#BxOTt3k`l*4ZB2$)#!=|{ySmLt$Ym8Co$xq7`MjCQ zC_Fif#pT8Md4vafQ>S81p49dIBhxdJLa@GD%%Lmn)inDyCI(^i2_GFC-8Zsr6hqs# z>7hJ1_8D=l2)D>}-OSX~$hgcryO3sAGYU`bx^8+z+liQ2-?hPL zL2jAr(9H0_5UzZ4^JDP|f9cB2VaFOSrzn>wPT$bJ9Odfo>^33|ms8e-+_~*ES~gJ; zxUA89LUz=~T9BGj$jybhOzh8D*Nj|PT=j{`k#V7cZ1>YcC6g;x`)t@HPlIkS%#4q| zYG$N48ui|B`*qamr#n(D;fSvj>U*^%=)u_>tYLgJwr95DBz%t+Vk?y?5sHztSlla) zaKnZ)#tNm@uTc9N24}a9k6l-dBC8cDF_zP!sY3y;5_$FgY7VoU_G}|pEmqvE;Yv9%HHe%2i#i}4Ge9HPl3rT1LN$zKs!52_1+o&UVP|ip=oOXIL$_ ztCMP=ELZMLZjj}Lh8SDRYf^Zn1+qG+2Fh}U)|x?S?g(Ugp&`avc}<$D(h_8KQVo>l z3T>M^0$E;Yh_PJ7wt}S8Vl@&Kx^m@oRF`s1YaDUq(6oXe*57Fc$0_XIRVg;XS)wr{ zK~^C%L0G(7t9QFK4Hj?xF~&+<6$ID*PSXnozAD8gI7?ZB09l311Yva+jx<=_!W9I4 zyQerbT%Ay+y*QS5_3xckG#-n7VFY1SjYU`-0iYt5Re*1-NBqYXg zni1itjUN2((Ae0-o+0_Ev448F(TM(yuM;@Hxz;C36b^mU>=aZZtSlyNKvWWtkfd+T z&7LrJ)?pEkwV9&nKmiNGz}vm1>|YSMEFuEPR-v8>g=_Xv1N)Ftf*7u~Y+PIZbNOTL)QQ zXoxXAfyLIOIkc4^tCMP=ELUi)|EGg2FEqqx%tEo1DBMvSTS$P_NL1*`mD5pOtOb@r zMHV$$o5wFxp~`CZ9-|)2$VW2p?U|f3ZzL?WsIox_(EM3H=q#ZUSQ$Yayi;A=`aS?+NeM?9XH&T?zx+r^nW^x#hX001om!q}C z0^2jgMcL`)ELz{VVv=(?D~}9fIV+1bb2%%I0Bt#oPHrwv<+=YL;wbPU(FJYtb)wz# z{{;Zn|0}@t{|0dX7Xcpl3BVmc0$7T4!DF zrvZ+_-(SGbOP&C@6X_28?(~brlRyDH@W1%~S^!Ib1~9oOfG>OrVBmX*6@QC|e;z*fCl22{yxAxm}UWDS%&X&-1RuX zqHm)t@%zXCeu3q@AIteT@*TG-fX^e}hRiT^()fDY7C19c(Z&UqN$ zBYNWK06y{^#Df@4$MpB1jxNW)o%NrH6TjcQI)I(W1@Ps=1L#FvFX_N?wFmHMUjVQi z%ZA_IeHhAX!@r}fd-3nr9EAEfIDk75*S#p`!R`QlbVvYw^HBD40Ehn)VC6+vR+PQ+ z`~bdq9`bBK`}78I-{t^zY(m{`2;jE$0X)=~@XoUW`2HCIY&;Xob2{QV6?sn! zVD^*%9zH36WhbM4&JEyJ#PsAj$cy`;yDZo|#gKsXKh&)JFtwVXJ<0nv; zOO8eCSiT18VpmT9?>#ht=Mm=uwEsPb^C`r6(}gG#ao(^ZfU~gN4s=cI zSdUnzE)8HYV(mLSfZLa0c@gJ@i1)^&0elT{E=RnxOVGCv=i`WT4Pt!biv#FJz1;dM zfEB2NXAoz{FHrATp6g!}z(Um9derMp4fH>>^&@EO=Mdxli23H@1K5Q&eKVTjcsLeb z0xyP@&Oq)o>S_ z1%2>V_-l9poCzCX3(UYZa2q@bzXf-~Z^H-RRWJ#!gv0T%u*0Aeu7Fp-i(n_51jDc& zcEiizz3|U43h%>OcLc11tKk?p2WqexE`@91o$wBL2>uS<1fPLh-~sp(xF7xqJ_Uaa zpN2n#Pr@I-C*Wqd58ep(!UWt3e+h4azk)ZzXW?z|H}E?6FkBCR21mi!uo1Sx=ix{= zAKIY@-VOf%Q?L)lU>dH1*TRS3HSj@L0L!2SI$%BY!h7H!VLq&YHt2?T!QaEf@CNvE zxDh@MuZNGp4RAO79()vj7d`^x@cZx=a1-ETLU7OlvBf+%6!ySnumcYHe{YxT;QhI5 zb1>esp4?+SfO8}IZ64NzO#Xy}_T#eTfU?tF~t3 z%9l!- z&@VsOl}?`~Co?MC4;h}gTIP?5_)FIB5HU%W}O0BeXx-)M{ zPcD&ng+8gbB#F~2v^2huVI`ydT1!TlTuYHd24kOWQF{%X<(iN$oPGby1$WKha}X4+mi#g2Qd?FtHJ?!xH$CYe6AQ%tJ!COd2@p zJy^*csmU4wSlB2+7dxDRDCnPfEeu>yft8{L)#?gBd0u1BbWh*%$ zI|*zkJ#~{XZEHZl)-uDZ>0jT(~XSw4P{2zFJE8N~X=O zjj46psiHzqaWtue$tyq3czv?2o9*&6wtZU)49Q!?&f)~XyUWRrgO*Ps$!6F-BD=jrH zCX%}XQS`V7=Yr^fjMcDZ6qYvjr|@M&TXIb?UKh&=g)c)v5nKE0-KhM6 z$=#@O$Du8YkIa%)y#EmnGvWejg1DgMctsPWZO`QDN^SN`lvQpMDmtdvswBn9Ez~8j z#T(n5(zr@|2l3HRh5<%e+8olF*>Z zDNu++P8o~GmePcjX zr#!y-;!-Mk6UTEiP zvN<_^1l%!(k+UiB#V#@>)&ECOL~5eMj?}qQW-mNDn+|kExtTgCxDv$loLEqSCl87~ zt5JkcT+LJH=>oyTdo{*&qXaYfB-4lcE4)iW$dc8^IyPJioJ%0nhmz99+vhW@VLGKN zFvwbECe5m`>D0b@Xr|_+%m%FLB-21qI}>A5Vwh%$#i+@wMh>f(X|t7`PVZNunLcM) zr2xJj;>z@D)C!RfPm{+77df$% z7ma$2;}_Ho%lPt+ae>j?!xK_~3MT(O|Wl_Qa($p)0$@u>q#UX{BXrPYqY4 zaU*z|JU%#Gd(82##89r8POeXP31gQ=4E18;8KXwFqT^9x1gwmbm8@oS)0Y0N1B1=( zo^9&}HuVo~9cT{Ejx}dH+M0VNC!yKw+uqxoPK19L-8b1(dw_}6i)2G~zU0=1ry9Oi zw8LDRt2I!WXcIG$H`Z!BzRTM$h<5b5JR zh`Cbd!J6_Is^CP{RPsD|JM<*Par~7`&(GhiOWHbjw6{D~Ihha#=nj`6*0R}&aREAk zkSw6PH*)%M5Io_sdXh=z*3W2%ID>;Ib(9m`fKWNn9L}7QP3MlO82xh9B%#wAHCu!! zePPR)n5s9a#6%=WrOPdltTMVt(#LV;$Iuhu-JWC)=S!u|^gN1#_6Lh2*|F~M1Z(HC z^6!MlL<7cf;@C@~3F4e0h)ji-Tv%%)t~euiJ%s}&Cm&HI zk&Qw}RmgZRW0Fsym5_-20Kc8!&6R0b3^O@THmF>yI&VPBV-^8DM$8Lo@}zT>n-9n* zv=q|RkpgNpFkLTFta%;1(lZH>#tE5B-9&Slx=br%IJz@plc9&h6=XatM10BM$dw7k zc|F)W+93?PMn_Y2S77n>}W^_UIleiTR`S>4>EC<{!;Z+T4)>u_bAGu@riTHUop! z^_3?jGz8k8bb*fCjftHof6l21Ez_vy&ptbmErPZr27Ph-A`zh$Y^#4L$O|GmO_AUz za;8G#P9Kk;YXj;4v#;cKwg^G$&;+qgA^TN{`=;3F%CFDw7CUhfLA4G@xPV3{9%zPC z2P8U9;pU*`YrIS@O?Yt$h74R2lOyAzc4zmCnte$fDS56!8!48Q6s_<@N;ZUftD0kM zZ47x!N-|+hRd;41DyU0hf%0mXrp6Mr-jFw1I5en@|6Jm@0NvuWg;zE{G_kwLnou^% zw9v}Vb!gVMWpZK0Clzd&)!94Rs#5A?KpLH9ngaGtSHuXVCYGy8l$jPQ_g-j1xme?q z2budfjNsLe(-Z1vn zagj=^B>nybYo(S}P&J{2fEw<@IBgQ^%)yiDn&VoWJVin=xds4vc=BabX6GKw(cnC>a#Tcy;#x$eR9hgoYM#*hOH5D2L_Pl0E zbLCOA$;IMO>S5M$(T&quc1=M_AYb3QK=Mg+8fW|@dQ_1}5j3)th;na~TuU9hp$p;O zy&_NXM8zV7(#7Hl)jE89oJO_Lp=wh3K+{sA$q1t#%|@#=)Do&oC>tyxR4YFpCs}?? zDj#TCYBbz0r`0)oidwG#>4^!pR?XQC=>Tb|Y^^$^7Mkslc*=Ef;xj?I;w+Ku@|hEO z5lYPs*=7&|wU#6;u@FQd@wM8KpzuJ@;KuEJmo&RO2RlLg+lt|_vGZ$f9jn^fR(G`3 zmKr}T(Wg}{tE2zzp5GfB4By&t-7r4Ag72BgpJ2uC$Q3hJF54D<1bkZr-|A5xqTdZT zrfbD0K6^E^tX2JKA^r!SJrYj|$)AJq-v+ci7^Q2AzQ)&30PrcBIGy;u0ZSh|2!Aia z7gNN~(N>|(hU1Sp48IpL#m`YlpV)QWmeD;^6Zk%bf- z2di&ZiZu8|l4e!%jre|<_$T@ivH+i{Nq!E3m*I!Pr^LLDGv6wDrsuS-TB&)?LDF+R zi||6&;Pjl~q%87(n&(`g{vF;J0~8I$HpgP=H%%+w&ps**TI%9P3jyz zo#oY>r_Qa4lq8*5)H(e}t8**W_riVuU44jtSFYhaT0IRj_c|q4v+eCF$nBmFAS!Hc zAR^joS;|B5zma2Q4D8xbYf(^4B$pwQ04)9&MW8-J!|53sCx_*%%nSHgO~EnIyd2RS zniEYy#j)#zPjmAuti)iyQq5fuw_kd!cm-)u?bpZm3; zSf4ZNX}fB?u=UdQ)`5CEA{$A3tk=rd4rQ4*YAp(giDL)in4gU!kLer%);VFq?#HhnLZ}E;YZ~`QdnthKU2+sRVzie z`sffTxo0>!Z*FDDZ;O1seoO`iT-mEIwzscx_iEZv8^=aSwB5|w4(4icw5h?hWtAG@ zI4%DcBrat*=7x5 zIU&N5dF(X0Ccp+`ea_TNJRr2NbRm{Sd9hS#DW7&;XdiI2KrGc{w{Jwf5N+)l5su8Z_5fg6W@4dRwyLlYHAVE!&Xib^ zD_|V$h;Wfj|jv#q2iM66y&9nqX+p>fsQ3^?ql?&}qut>N*sE*X$4jb&>{O*vQ^ z68*I079t|TR*lGGvvV{=?iMEmqutMADTE*Md~LnJM z15&>{+Bq-8L$;CFovzxGJ#EB_2#ve7oC7Rs@y4p>>#&}mpTgp3H?twJeR(y}quGF% zS|UuDZRi2URWotX?dcrg^7X!2ac!ht&$!R3bS!Kmyy$$i*aZrK+ojvO8g}!|kHzh3 zf!^|Bu`gj|I)8^7yI@#q$!s%yD;KL2icH6yYb0$J653U(K;oN~YZpjZcam8au^lJV zLbVpvi7;om#ipMQQG=~Z%D8)>9Lp%|=;y<@+JTX_A9mdxN0qC<=(FmD5@YJVHAkmj zU4Ky4s=nUyMQ${%PKS2ORcS-gNTg{^!bb3SP1Qe+fA+f z*>!NWs)AOm-h_D8MtBOH$FhO(Yu-xtzKrV;SzRDIz}M{A1+qS8TE6BfPlGNGGoWDS zIOhd^7Jjzp)I4jHow7VtT@5&wNV^E6OtoWW6dTpcBUKBCW{cQFpI@ht%6MSyJ7zYG z1YCX{tuZvONdM7H;M6sF$Hl|ul zHB_c2?m|o(B&M;Ep{Xr1W7DI9GgIU7y$ei7jIIK-RcL+Aj;$WF8$D>5Zdego-x}wp z7;V1mE-g*j5hzo0zIn6F6c(53iQ6h|Fl?{$Y333a8ltb}0%L(IrI}s|%iL*3RY$9z z*1-C>B|(Fu`s@p|D$$MyPhW_Kb!Dk#9ov;MtyQb3j;tB4#IDM%0*~|NQf{;&0s!03 zeQ5hhwA^S_9a?2UNt# ztD>BCj}23|@!@<+n+56_jd#$4m#N*#@cL#WwhO#?ODONE+_D;6O{{)wM2qiGhzeZ7 zTNanEZ+uyVi+#PX4T>EpeLaGm5vsg52ist*&zX_MhvlUyEUMDF??l%{iZ?1b+gv?x+&A8J!eXq0yiNChwTa9cwF`9_AE!RqO;>zms zxQLmBt>|yN6)tVfEkko!N_iW0X?(uuKIFhB4%s{QZYZ5qwHI1V@mjUC8?|P4%fVF&SFs!3 zZD{;f-h*wF#+GGHar=B}Y#ju)PSo2g1-8@$^RDaOaf1rAFw54K57E_5M07W;niF@v z)_g2P6gJvLu-@Qpeq z99XCwvIHEqNBitF>A>Ui=jh=AOBMW{sn1TYBCyPvoruv-1O0bOU}3(tU@OP^oar~U z76r(h22y9`;pwk zZwqt|d(*nSrUHzW>9VFeU8c=1N1Ie*}Y+ZNIi-m318v)#2)ysxJ5 zvUN*TuL5}8ZIoE$`W=N=UTIlEyYY)1wtB74IidlL_B9k*u5PPC>#1e0HPHSh$AjxB zq+GpL6c5~O>=63v>nx-tJQm|Yb*(Lp_;+c|v|R00ht?AlUT>iNO^yjSQb@Uao%5LR1`BBkkHvrx-OFpcY=KsnjtMu>h}qh$ z4snM9Y|V#?-I~9z5cBRRF0Vz;9fogIn93QvnlX$A=N~w57BF)~IMw8>IWF9eHojTm zEEAThsqHN^%0G0VWNWh;l%AU+|0qFO#ycwUKTTQ&bA#s4l`xX*!A?>=R+t|G*-wDv$LcES=-yDZP<*RR&H?qee zzEz^Pl4w$EA-MGEgj1<@-sZ&PS|_65SlY_0yFTr_okTNt+F7kaiPfL&#kzTWf~S&0 zpj=(~&hWoOVl$raBNoub<6c(I_UCM?sf7YdOX9|)cczh03!msjbB*R*ZZw2TSAoW7 zrFW;%%pnrrZ2o%;BM&xZYn7mw3RkEH2;f&pQ<^-0_)jpJntkrVWZ+ z2YhEUJ`karnanYjg4;=&eXdPg7Q{@ys(IE}?~;hpuWvFVNM$Emd|3aKz{-pv6=GGB zX6CqBtW|taVU=B+a_8Dfz--^F)o8>Y@*%ED#cagBR`|~Z;`j;AtT#8UT4P6_%v$8z zmGxma5?A-u)iq&j#WyngNE*wpvETMlH<~%@E%`j=?lhXYMB>?R`7t+=IrA9b3rZh1 zuoUk@I+}F0XZvvexf3TdG`XkN*f@RrBJT-tsv`lJkG7YMOupNf{=$W2uH%7Pu(d{& z4Qvn91U{MuLzR^JJtPl-DK z$%mflo^Jfmb7@Wb(0$sAj@D;|=!jFU;Ez|RO|*H-#?_MGB< zz>Al*v-^fc`Pg>_c-1tiIfB`ZmjA4cx6B$wRlC_eD_Vc)!OPdKyPIGsJaf$8^WVRU z@w#3Vr=t?#4;8Iy(>TH_QL`G2R?= zv0>2dsb)4-b+^nmSKR6K4>6{4Glo6X7KZ|302=K-QfS%cCc%i`B18tXr~u@=&+Yb(b80lO~|7ytkO literal 79440 zcmd^I3v^yZwce*dDFq6YQc8K1QlPv_{?MkWqW_;Xp)Ir_r0GM%rhk(Z0%=my1PY=c zA|fi*7a$@cBH{}X6}k6vSzWk9L`6kKL`1|F;tLTG5%KPs^O~76d(N3Nlge5*Ywb4w zpV@o9*|TTQYoC1%JE=a>d-iK5pD;`QsVt~8HY{pfu&`17z9IV9IDf(X@K5U}0|c7@ zwyy@bcN@Uh9su|$(ob$jng{TQzL5U$5CBqeDh|_7=8E2kp6%e7`=%4K?;tV64HT}LBMFvL7d>XQ-D!$K#dbTz8&jDdg+#s z?w<<4=tqqqed7uMMt^=Wq`w{l!03A$IR$fWLAl8L+v`I5^?KC%dX)VjC;0ht;Pfw) z$LO0Uhx8+?lhOTmhxE)10F3^6Pe|W;8s#JXvJr&aNS3tn%xVa%6b3X)(=D!fqiPvKrkft0H((V^Rz-W($Lz+At0!F)T3~3V9 z%V;8wKSn#95z@|gK)`6~Jt6Hq8v;iAjBtYAEd@rwG?aw|kF5>qiSqy$y^L+<)PetZ zpiN&F(m`m$jE-mw34Q|s5EFgoGdkmfa`E|HFVB&1`vLcnMN_A#UR*dL6hJQmU( zsB1=hUJ}w|)HkC^(?Z&95CTRM?+j^Y)FY!^&J1bab0A=}_X8nKoq;-?f%DNDtONvHht);sKxdt|E?y0u5pWL!)d3R51%c{1nmhSeRTIcY{ z=+gR7-(dept?z=N`lf-c{e!hyicr`ofSDAd$i6ARUQ&+XUAV#TUw^^dmIN9(mE zBg12xTgL{^?dq@hi8Y?y(!Q*H$&%U`u}BM!>cEzk^XdbG^$mml#u|D$q$+ILs-s)G zws!J%8mn2lHfe{dI77ACU>Z-g&X(2U(5>(lXawh+ zhear=A`$*%E2Ubkm{^1+=NClFkToXEH|YH-%dp@<%P^JBnq9%-s0C8)s+M+13wZ@i z7?;ViXmn9Qrct4D3+l5d2SZAh)#)n)p_SWGiBt{E8^?N?SN z(u5xNa5~*l4BEL-S6J}+%Ff9-e7bo#!;(8OQyggLiQmkWL1$NfYIcz(&doYGlnXXCMPbTqc{1Nd zdy+g&CFKqCv#v2EC+Om$$QhavA$X!9Q*===;vB8xk)|hOSF)07ouPbYHX_Oz zCL;q!c5a{wo2CX6k1{h5MbT{1Nlu;&78lP3 zgdoMQ$KE>JsTJeNYkA_@W8vYXNeEAuoWx8(@RgVdtR!jY0fPjKX~05CJPQyk*-5}q zP~(Mk6N}_L#Z@sAO)+Twkgjl!BcfQct6~Zb`U>-!IG0iH^|Z(Yx0G2CQ}ys=w8ro0 zDo`7f^?gPzo&U=)Szd-r>PU@{mWl5{b&wr$_PKh%8Y4BpmCkY{5RP zG}cz6i=50+VP+oBSr%CGaXX9y`~|8LbcX_7`YYY%@~R%JBo zTiaw$Xv@khI_1%TGFh`FBeUc@7M&Fr=V2CPES>Q=MM_t<^pB2hW`f0N0gbM3ec02n zH0=;;K4zoc1DpC+4xnpWIa)7LV~6C|%5bw<7mtmM^bhgM^BXBwY0ZjfVBs9izz&b) zX%+jdN2swJGwVakO4oKsJz0jkOszr$ND0i0yLvvm!6{&`sM)2s0~9Q_1SjqR>wTpv zvu9+M+IqogzYy(`JKlv&dP#0xYkjP*tB&_#w)I)@F?(q(%%S=kTTa$4)|`&|rULEi zY-y7`jV&i13x#W2E6r?dAlR}-=PdbN8%IIrsHHF$)-t@M;8>GtvEr%@Z|)yr8pt<4 z(N$V<6`G%=ekn4cOAKQ}18*Gb?-__z?-+g;E&Az&R71GqYk}$pjGE(n)b6dP4GmsU zfH!n-QVdWd-aNJoKGv^Lj*;CLb#L_t&x^e3miSE4O?yk0$olgwmg975u@0gqi8$Gv z6`5dH=^n-qOw?f|U0wJUDqwUOCLu~4NH0>uMaq0On|EVSY1z@zzGNBdGDXQ3F#e=U zDBaqvEJuT zDAyeq=hPGOQZ@qUE-^*tuV*9Ox%aG}i72|?W24rOK&~?f)hlx@1Li>*N9EFq!iq1{ zRrwC&2c#S8y`#e;7j*UG!BS~a@*>ZtNYvMc;oJRT!nL((e&w7M}cX8ba_GPRy>KGb`q8b zH9Coj=By;{+DTY-^T@!^XdHLmJ~D!%v5-LV2^%LF>=L9z{dlS^ShJIiPzP-O$N6Y% zu%O#tE8N;~1(XuNT5rpUO&97eFQ8Ch3tp*<;T}l<6+HpT9OQ)q9m1A>;Xw0JUPf5J zP!|s6gz7FF%1MgGHG|j1*Q3cmEGLh=aIh4oJI!CiF1VG$ma<}X7Y=1*MLJ}6B5pcN z8jVXq&4q&{zG4>+rG*L@r4zMM0)<&GX}K4v;h|sl_{$ole5S^aCH+a2P`b6d$c2M_ zf*vWGzfyqk5Jqp>)%v;JrnV?m|P1*#jMGP0D*w4$_}g38h=3g*B51(p_kX zku7D)PFoo#$pQM27^8D*r)Idg&4GCr4%TK!p5?o#F%ioTlDM;V=;uV5aQfy=W{OZa z@3PjTI0+_KHsuYQ`D}J>=D}sF2MfN%rZ}B?SRN_~NFOp&g#LP1y>KXFFdUZ$r(fj4 z!5UvAG{xxD6L}X7w(v6O{PnDQ;b04mA6GN`b@QNXJO~F}{si(Kb?8hDFb~o=Dwj?a zR(zqZ$~#})gWB5xTU(G9c|Jv=zN8BWTV!Zm;*{kdvlkBbg3>XQxo{{Y zEPLTlN(^=3P)ZnjI+js$<>=VPjp79xEsQ<%ulTpp5?C$+m#WLMSI0K@;lnG7yA~Ii z$FRZ4@nfX>vh1eo9a`gfh+gn|Ctn7Ay<_Apc)e3Z26??>WG-^OlP`d{-Z3&3x!x%v zK)Bwai_4caMV^n3I7+-3psAU^C1CwzOl=LTw*zdu7jx`?4e6%QFjxCO z04_Z;fEQ;5F!AsJp8GYx>=^;v_%nd3{t0l~*8!&e5MU1efBT;>NA_O;)_oVC^I?F| z2LOh?k2&bSiTUvH^UL`8@^4{|ef(}4%DMz|i$CxyXU zu6_jb#A9CixtI_9iXQ+>$2PwFV{G?#0IvKS=J$UHG5!&t0n4v{4&WU8+a%1RKZ@Vq zb!Y$+UcfqkkNMLP`;~_T@a(|>Ogb@utM&?@3BSMjY19{f_dN2>#`1HYLO!H>5Z~1( z=h?XdobyYp_es>tVF8>nD}Z~a2e4tk0B)@Wu(Tn7r{)E4#qr2{TmbhU6Tl1e1GpaR zIA%%!7w#Uw!+QiUeR2RBcSYVw*pCwfIAf;(?$|kid!`03d+z{7_CZ;{!+NF#uoiQb zpZ5gT{W3rY(siiwDF+46cmzuaAHaR6i`f%Ur`WdHsE2Jw2QU-+aXVt{o{eomj3fI8 zFcopGZA3hX@!AstXhximAjYl725|ENYzyLi3^C3{e3$Hr*b(D2#5cHG0CytBiHPsa zU9kQ82Jir4oPk)MM~rtP#+MM|$-e-ehW)yKSNf)^H3L;1p)N^ z9rcNLo6weP*q56Ev=!JJj)Xa|08RvaoC*$r{oz132v)&aunjukZdeBU!O_qRZ7>54 zhSkssr@}sP1k8sTOoy4!4J%+Nyd7?XDKHx<@EW)iE{89`Iq(4(fcL{Jcs1++hr$W) zD(HiLcpH2U)U#C;X?QXY=w`* z1#lCb4>!U(cq@DcE``s+CGcsu3_cG-a1CsNt6@(#3>x4h_zFyhLcs=yO z8W@BR!MX53*c}dmd9VoH1z(2U;5c|E+yP&OQTQlqf$L!eJ_2uq>tHi{7>40mcmtdV zAA>Qt0qtahH!V+uU7!n2hIZKb|Eb2$hW8cH`c9Y)H_bNMg@+|#Rt1(`DM>JtSCC~0 z!pAJ*{MS^%a8b+}O}both1!yqHL_G$g<41zEK(m&wimaN3DP3ZD3vT}Qzx0dCrSBC zXN6X~TI@<8iI7DxeBv4PAjr{VeK3e4O5+lXZ70*^PHr?yp|Tkuxe0Zm#grhOUaBe5 zbJL>7IjCCWr*_pr$#olwp^Q~2qBX;?3~4sFnP34#a%K<_inf5Jrgc~(m?YkvO5A}1Fr7F{rN-?nmD4}NM6F^{lhwVW zK;uD4WS}NcTsaO)hGFhLcvl!YQu< zl2rSeMzOgt`}QE#M)~VRhR(LFgb*6Dmf-?KZkw@McXN6I|#)ln-y18v|Lp4q|(C$7h)_=s)?B%F#>b>$4*$) zdTwLI(X9sKE}JKig`wCyrV`yI@G7&cd1%>lCfPS;5Pp)cShWm54!=kwS&aiQWF5itR3619#AO+4)SCl~df;JMsw^XfBC>=yFI!wmbe*>_y-1LQ zuHuNeR9SAJe>fBq-Saq82W(07F9)Yev+v1xR52S&9AP0S6`!r1y z1X^R01*&1|wmM5f;dy_m(rm$Lr1=<|9F`!+7FN=qksv|+w)(=(jGq2V73MlRMS*Pn znxEnmog&ZK%Q3jMCUp&h9BT!OE=K4mYwadIB?z$wBM1@NWRFE|lpx9;Q7TG`jJ3st zV!}yOl41)dkrF>wDm|2Bi-|{yg{ZXhY|&}t392uJE}H#fc!Ic6;39Dr@8!mEswtgW zsN?lQ_`;)1aorZcTslv9sUXBO#?*8q!4J`r08(C(z%Q39l=dOJ9*oU7e!+Vz#gh^_Y++mU} zsT;U_oXAB@BPv@mUuZmPEPFT_HA#)J7)#Y9V&XHc^xe{$GtWpJa#^!NlCm*C`*!lM zeUDE7ln%+JpT@RqRQnRXoH(DwFGbr{X(?dYi5hXjRBMkdG71r%AkQA0C@GMdwf5LFtrg_igA?UN`zSZb2$V>nCq#qtMet>109NlxfsNTwhuj#yiIpLVD?{ zkBc+oAb7%?)U=Y^NV+J1)PjR(byO2Q>ZzJ&4sA`jVXJXd(t=v+68a)HgjE(v8muUi zv@pCr7W3hWue%dtDGkLmU7snP+wT+y-5Ux=8osJo;VU7dvHnsXU6&Y{2q%@xV^a~? zXK092MYL-uz@h0$Q&qX0T7a4EUz!p6%*=&G!sY6#!|6ykzp-r=oW#<4pRKPZ%(!z&F=ca9!|CmV9 zjg%6i2z{26T&LbXLGn+k{68-4U&%t%IcVMbP69*RCwiIu#LL<5;{WAPRZTlVJprkx?diIz>=2 zgxV+|55JJGe?WM7wrON3i~bB7F$OYh;lQ^Gt&ZBNiJDejKokj0Gh_yskwe$0T!x$~ zECa8jrZ|R93!5lMNzrk?4wljCG}}&TmnOlom!!aQ3CoU~M$0h5%jBxE9pHX)Jw>e; z@fWUbkZ4qhzURZc8Gd?^U=-r~=w+P#2t(K;>crUs)QfYu+d^a4H(3yBjWR2g-#rT= zZS|N06brqr%Cv<^%JkRY(Up6FbasWzClcqNNAyRsOJY`;6>F;@G%Z>P2!7G;F zW})gr-Gxt{)=Gy~)?w>$l~I~JVOFqolu3LzEzzpnU>ap)@X%EjYHK5wFXNF720o)lWe~r)gEY8YP4N-)9SdrYBCzvysNSsYiq5_ zyLCdUwN^D!OYPP<9=F9n66!B1P7!I{K6ytLp%l!}x*L=oZB}9_h-}w%u@LDW#`$+I zUDa`FPg_fO3kZLk*EcwLLS;dvv0+i;f`yH%TPX3{1<8 z`N{cDFt4wF!`NAKR)!w|Gj#*zD3^a~uy^ac0etyJeNJQimudJ5z77B|H9!B^3IDA@ z!}h3LQ}i`vYX`uT^+`GQeGO)9pMd{Q$Gqh1XD_8uN5Q^(?~30une1l@(lzU*t{CVY z8QwCyadg()uA^ryU)FId|Eu!P9{8CtG68^T$JuWT#4h|dr6#EL4sY6wn6FtE1pmf# z^kJ2Zi~TT=6CiGS4KwAlZ_bXt;f-V*JH_A3XJzn&{|Gk+7|wsU^yqoe`1#N>G(tRKeHSr zcU&x@NFN`Jm6H$ESZl7iNzhz4=J2%~M$H+<+=56++?d&z6Muv;H$VQKnJ>N`L;CTq z;UZc+3?Uee(pIwz7el*v;N@E>p^sN1nmvo6 z36H~-s_m_{IUd?d-<*V4rbJkBpO%WA!BoL0pL6w+Eb$a9t%zl>qFB84lu0{#%ZTW$ z=?>7&K1H#3)sD&APUVQwhh;Talk9m_#YF7wH{GMlBbzPU_f;@xXGskR1yruxn)EPD zz(B2TG!U%U&L%zVr(pO`=wW(@ft-EuT-u90nC6=OBMkaE&liG)@kUkgV$EogGcpJ? za}5E+)+$ZD>wpMHu4mr?SZ2ytXg}%;i(xHrAjgtEPpaUTTa?JL_zbP*3O|J9@4|%)azS2hPB(Q2#wy? zjRThW=tl8+i_wk`%V5!Xy?jX4w!Dbg4K6`Uvm;Eo9&iWaI$Xv@d&68942>U{0%UlIC63J2uQ6jC3`H%uUe9#$ zb5x8X*Ko%h$y@~qZK^(ynC7LU84|0s8%mF;hLhVvm4u+T)L1Yz%YzJqOQ5&Ru&h2?qdm8EXSUMD392d+{qu{q5RTaa1#)-T=*=#kI z9vn@a1%Hhv()k2ZOSOAL8ecZZGhz?g{DK%M_XkSUksrm{&yE!uZ<7hHAN5+}Z6@vv zSZvWkhBuQeh^{x^-ad8YL-vP zb^JCHJ5Uy&^ePIAPCYs>UN!S-9U5Xip#!66DtAsXY33vf%lK)=u(o+kiUxO{`Hxz9 z(T)MnYePI%8LpJxQSCanwTHCn^ZH+{0>DaxY zHSIcD7+UL$U#bF?&$+$5h&Ul%ioM+$BPx+gOu=Dog{C=hafHh{OPLDF+S*L_ENv00 zq6yGcFv{oLo-<)-&tM_kdz4yDsoT1@77;$|6ttp~BP^MuYqZOVb60tol}*T&P{?Ta z;1OA+Ay%5~XS-2nOCx0R1%v6SI~I18O*H4)uayS<%6S!HTxQ0oo4<>Jv>ufvO`bxd zB!)yWkcwt=N2^JbrVNsd{jXxpL0jUBI2ZA1!7tmV~XyytdmJ9 zVC*$!Lf4&xj$Rnxy$Q=x>5h)*&koexst8^D5Vw5_OckE;IlpHO=vEui88wITtv+ro zOnaF%5xO#II~6Udot&?=coC(HQTF`Z+87r;%-_|&Wo!^n9dfUG(b!OBET5+e&3ax~ zWWe@18e3j>dcoFAU~56Wox!kW@{tlLr{jF2&e}2|dc77AF@<_VWLmME86paoXm-h0 zoi(+PIKyUf?{8qZisyB8#$wtjuOqNzmK9M3SQU)&IoB7M^wOijqO%_YiuKqx>192E zWxVv#9B+mdA6Y|tsWU8=8FZC?Q5|J&KbiKF8yFrbbuE3Ap^vBVb1QCohO*ZK#^{-U zRh8CuX3}L}2B&dq(Zr^Vzb^YdVDzQSMTQmFMvjxtU~IHfo(E3tYUOk8s4<~CD+isi z-~FH?))Qk~0O%Fc@s^UQ4y8cx!zD?UJ7F*x~z^C`5p+VzLl;1jk=XkW=b z;Q|V&tzO67CtRo?b+A};2vJr*)nrS|y0lMt6OGtfyZ#V2$AFdd92PBlQHiNTCDau^|oJWh*LDkHo6-1`nC|OhgWH+u1Wcvza}xDyi9}A zR-c~ENGp0>u18(IJwzG5{lYDkFtL=j)~W&TJi6(RZhPeT>hvQzg^DZqO-Q6Sw zN6}WUM>J{Y-6Wdv)6SyU^(pJwJP19NYbtc5VRBVmdGy{KxAx>UeHSTMH_{vyWF|i21>-9)<%QxL(z^hh1 zn#D4X>k?D^-wk>s-6^Yx9HE^d!qCS)MeP zx9K@+(uD37BRX22$&32j(Zxv)l(EV(N_~p;^H|Au06HTxMFic-ke%=K^@8Jy_tQqa zbU*8(rkCg*60%+kR1BxWpHcC;oU^v;rxiuvxt`pF_p=7P_S*G@mp&E#T!L5k&P8K< za`prU-*czg6qm3E8t>dxXg&6(cVd+weD`hy_T52=%+KjDxh^4 YN>u2GqUr);iN<=D9&0JR>aL6b4{%sossI20 diff --git a/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj b/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj index 5b7fab73..bcca5fb5 100644 --- a/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj +++ b/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj @@ -21,6 +21,9 @@ + + + @@ -33,6 +36,9 @@ + + + diff --git a/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.filters b/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.filters index b86aef94..bf249133 100644 --- a/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.filters +++ b/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.filters @@ -48,6 +48,15 @@ Source Files\dynamixel_sdk + + Source Files\dynamixel_sdk + + + Source Files\dynamixel_sdk + + + Source Files\dynamixel_sdk + @@ -80,5 +89,14 @@ Header Files\dynamixel_sdk + + Header Files\dynamixel_sdk + + + Header Files\dynamixel_sdk + + + Header Files\dynamixel_sdk + \ No newline at end of file diff --git a/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.user b/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.user new file mode 100644 index 00000000..88a55094 --- /dev/null +++ b/c++/build/win64/dxl_x64_cpp/dxl_x64_cpp.vcxproj.user @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/c++/build/win64/output/dxl_x64_cpp.dll b/c++/build/win64/output/dxl_x64_cpp.dll index 5e967f141cca7c1a100a063c39a7e439257de4ab..b3b4301bd38bcd17297b06e5e7ab2076511d81ba 100644 GIT binary patch literal 86528 zcmeFa3w%`7wLd<23>lthP@(}*Mh!I@Yg3~&7_>8FLe9Vhf`CQ^3>OkZrI02w5|v6Y z#AZB>lwMbiDD)aw-*FI++Nl>)j`@6s2 z=h~7zd!K#wUVH7e)?Saj_bI<-y(7cnaAe|NEaq@*M9TlX^7q64xY8VsF_SipaXd2o z=`%N`1)n~1UhT35PhI`W>+2VP*|TKviWMtEo`0+M)Q4AimaXvkXV3L~dF9gT3r3F~ zk!v+w_jU7o7rk@)4*TC_-^|`I75V!gYT5Y(Nt<_iB)x6t<&u7FX93c_vE@51L3+_U zU)vEzy7r;3?<|t^_MI0?deaV-u9N%~%a+u#kK>J~qSWD7dV7}RJ7qU5wd?G6oaGsr zKE~mA0wv#6r58Pp)Gfc8Fnskp-QgG}MTyk$0G<-5_%Gd2g^YU1P6p>y$pg+b$NNPN z$9FGJb3DM8(aSz|geInHEU^AtpXRs+<#m6?Kf7#*bRVAIlU&~GaO45rXuqINRg^K>=$bmHp7(<5YnCl-a5&EA>vdLp!6E9^H`Fgd6~SGTRd3c%^{SVz zL`CA#0h|hagfrVfs6&ShIzBTcoSN1a!zyl!-$2>F1@Ya6DyT7526 zZ1wikQv*xAR{??oz1yGbITnk>^vHr-uO12I>c#=x*n6-uJyaBoj=mj_f`;$#CNiDb z2uRm^4|b)6PSK6IhxLxvGWF(8mmZyY*v#QGJz8?O{|tcg#AX3i>W)+||Lw=DU~JY6 z_GF+ZprhcrI6k7z&x7nSzW8{~RC#N>GRpXHo;or3H`wsY%xokGN$^LVu(epd>%P8;arylH>6v~QaPx_<7@sy5v(Th9kk=G=jkG77u z8jz1c*gS>IIX5D6Kr%*;89~E^?Ruoljej}#=iyuwVH!NwZPp{fT-RWlsL+iU0jF-H z%gjszDTB0{JKX@=ZI+!OlRg*YnVrWLbo1FfheO*?Qq)>jq#Gq5sWMDJ zQ;#gqMOUF*kIXCq2IM5+y#PqzN$>?+U3(fjkFEr&8uIkwe}=~E#t!q%Y=^_IZJ?Ae zo?}7wxkMjvx7^~A))EUGAX9OVHDd{0u;~j!2<2kh z@KHGI4Hh2^@X{F63Pi>P@V0KuVr8^4%cX`9$}O@-V64WFBJp7qknntqEGF^JRlJcVtUG=cZoniterYd(fyuE*5ZnrqPt zt5l{|sWk7is#KbbtSWkH72OP5RdlnMRdiz~2}Bp#=*xLO7PDvN6YurGcpQ2L8}2p7et`8Mx)Oah z=yA$D|KtIb`z!Q-S^%S=GG1%gz*;S;79eY=jn~?D(tx(K&j=R))C3nGBWuS;$txv4 zj_8rGK@fW3K|KP>k9-Ae`W25Jy*kg52!(p2!DXIuHh_*~cw1K$>5)|+l({90ParnYgjozBbN9}5hC9CSL)H_xex1W-)`j^WcYF@ z@``PA|u!u5B}eeve4 zz}W>|H@m}Qz`r?qK3R5@w|`VpuE~skp97li^&5YY^5W^}Zz=nWd^fjA0NEJ?3TuPt zyQ-$9Mw_$_rR)+lH;hVaEx%rvT>3?S+8x8v&~b|ce^IAW+b|y$_UMN0YPxB>BYcK7 zsfq6w&6&^uSrKse<1eJ+a6S$7>BW0O&P(S`Xt+?1mR=u>mafzz_!pg3X&wcs1Tp8( zp)hgtSFtb{)hC!|f;x0#;VLXM69J1?U-Ck%yEStJe`^~`uTSKs>jS|#_2a^!oAs%1 ztN|Rlz;Qom*;u%SaP;-d_&*wePl^xSd<$HigpWgUIL0bC4h_b~r!)T4ejy6%@#6u; zA49*Vr_RG*GWghd$NYmglg68sn19u8))32d`9bt{xg#5JS=sfhd~|<1H%=yrUhctb5NV;FG}YA6GA@> zjZ$b}r3HYX(#(JeO`3Ko6m~n0vej5vP!nmGh`z|$|5{(V`K>bt^`%(*2|Qq5THB5q zf8>^l=KTAKmsxqbu^;+cDLRG>o8xM_86s|?Hp%Po7ftg}z+E8%4m$Hmd=@hG;=Q3^ z{!2?dBH@yUnrGIgQW}Q}6-)P+Usse?@F;`|By&Ta`P_ZdKS=3Q>%Z1C2cx=H`q!-f z+4V!vW3olB(?sJS{vw0E0ULAbH(alccfs+I21ix=f+>lR{c zL7~jKX~FzXu60!)WG+4hvFv|7jOsDa7=#UVxJt7aiXB-|}RmyoYA z9miR3JPnuVQGYJh6F>M6D@+BN&NE*~p@(^@R50>^5Cn}FV`iRtHk?@Ky>?LVp!bj6 zZLL`~M7L@pZcpj<*Y^?y958{sW>g|qYX*^{uqmK?sj?=kXwkK{4eFgs!7@)oOY_@a z8vX@h_#1tqdx+xklXQopwD65m<9(%wT$tu?_>A{S-$A3)9n63xQwko?T|l|NXz}>) zB%ijy&F6y#&c|wf9}a=(@fA55E)Pc558&{{hz|(< zQn$~D>BWb&+nxhXQ3j0@Oz{nT3h=^a1VVS?wWZd(5&ukYH);aoVdjUxy#q8t>t6q>i`NY7Z&fW0vjJ z=|;I%DZjtG8*>z?_CgSOxxD!nV1W}FSN5Y)qxX_}!y`BD`4c9ChU4a@n~KsxS$gwL zUPstzHvNN>M9ZJbvvz^=YjBa=d~$d!kciow>(<&j{n1g5{&<03Yui@i>v$FR{Y+Pl zKVw^vz76B#pfOfD2*e&N0Iwv;M6BRz-);i=7;|!h#*zFv?v1BFDd_SwI>MTQZ0#04 z_tE#VAh(geggP4V7&a9LsQr~elvPk7>ZLGbmTaRfSJbjwyX$#$7BI@(rP_wfVfaz& zZ(V26=Ki?qo#QX^B}pUrQ!zD=jy>(EKm1zfy}%rqwq#_M;uR>Hwl)DY$2Xxe!kXJ~Yg0Cu(g^H}|D!>;49O%MTdoj^-ojp{&C8zV|o@^cxya z6MePj0YTq(4CtUgA587`MW<)zOM0{o7mbw~sA)cpN=So-15eZSCB4(M4O8I^WCIT; zKTA{3CR)$##WTOLBe3LoNIRE*B-~pr^=ms5h?^0c1XK-H2}I8z4@@7+ zKZ;(XWdj(oMAi12es6(EKHd!a@EAPs7F32X(B%oI)?B&};S#m_DyO);;Fm ztl2|B3D5wwP}|^Ix3v|X7dVQwdr4b~(1yS}gufEKkelgU$1v+$y76+;tT<`lS%M7#HP!eyqAPVY=jD z7{28WYnccaCHtT3($GKpJ@LssS(bXpIy?hey!OeG4Qk z=oXzWC4PxR$n$V1rqC@QKn1f06#g7gZf8_~B`&Fi{wm#+t$6B{BKEh3BwWB=?gjeM zNB9BGK#{}`LX=ypmE4NEyA$!C0-1ea2r||S8B5%sPTa%D#EMl;#AAuy182584E=>m z)~V2`ClsaE!#hDI7+sJ;au)T%>1}R;S2cOX0u&%_$evg6KsQL`>b>@fgUQwQ2Y-Be z@%(G_;`yIKFEg=>{@2q>^{`KqUSvf+F1>gxdJ%~=m|k8SnqE9+8l3nk^pbZRdXe~{ z2O0xdo{Xx=1%N;AP5c9ihh%g#%4W zWC&_;y!scVIuv$#z_krot!V?QTK+RT>h&T-89LS0jewpER}8duSD?5zjIec@F5xeT z3ra|+5@1P0u>y=1A$FC&EtuaEDBim2T>2!8o>=w`KV%aCEI%WVfjAd}TPiAOzg-S5 zSunqyVznqx+_P#fr7XC*ClI}8EYxQ-6w970tz3)YJs&V`MPo0MHI1FI?2+<>Z$vYT zDJY7D=mSo^5Z>)IpM!-?#6i~R`6rt{&2Tu@wTI4xDWV(KqV#e-AA?sdKl}jdqEWV| z8cqc~p)BE7Tz}+z0nH037Y9e4e}XoXBhU9rKEKC~Jhw>Riaa-}$~~rbyNWz#s5mPc z9;l8c$s09^h3!G?L|`cOU74|n&#fER0C5vo$T>tws6k)*o_1Nsx=D@|Zw7kEXu)Df_{?B&Pk5qv&mp##fmN7s zr-;UOtR~8fJG6CQbwJI=`X_5iz-SN84Hy+}rP=Go2#MKf;!l7QrtHOk=nP}4BmV=tzkYX9z#Gj20BK`7;N8Jj%kl&f988=BnW*J|BrQ+ z7Pj-fT_%}3qfGU~CO)CGElD&VW_|(9m@gbzS^Ow$FqfWY%DLU{3`p8$n7% z#}tDz^|eQBQl0@)-bPaXK1{Hu%q?q&BIVz(l%%X-=K^LM0g_P}u$Cg&I+75gHj|6~ zC!`~qpG?2n>r-y@h8IHzR9et^K?CrKS{FVwDgKuz4*i48c>6y~y-{gSLJwY{2Tn9w zu#_W{8CDM{+6qCTnc?n-RXk1l3pp_%{iDmF{goGYYAv+jeI&wwafK_K8Hmim$TEUc zDqP`V!HDka9}}E%QrH=cjOfn{Vy{Qg$S9xU4j0HfAtxrk|IC1qhDi~~vXkPMJ+`*` zk3a;vF5atfYc0R9I}9OEx-Af?aQDHvi|&082da^=N*~Aj3P+*82O_$=zn<~sfRP@E zILeEsxx>zY(c6EP1w7yt-~lLy8h~!jG$;Nza}Lz`&LDT}9MxJjNUagU;;mW> zw`=M^JgPXt^SXRFpuQRIu4y?a1;t=5jgck@%hV$kz&JLFkTfAjiivrhm_JF1ivg(~ zaY3604iIF=MjO;)%i|FRepC8EQ#ol2L;Ent0C?SYDYkMgM^vRQFTqU%Fu*oUmk4If zB0@HfR)JoHFP$T8c@XarfqlQm4;jgPHIfl(AXp(HaL}{wKu3)hjz}*V-qOSz9j$i{`w9UEf z&%m^jTu3a$6X&$mmjj3~1wJ>Cz~U2`hEal*$k@I;0uYA)FQ>phwr>l|)RgpXOaL54 zAW`*#ZD($UYt$ogD;^&T)dIRqIEUg&CQWdT38(m2x8Fc5+Nl;(is%()F1+sxfq zvP1!c4wOX^&AnQ-`BJ1uV4HSvC9!uBS?fvM-nEuWtds9T&W1A!U+TX^UmHu7wL2+m zFZ>o|ZRKk87OjNZ@cKUVBx=J>a~ex&^FcY-j;NK3+98~0h*ZtQYt$o*6;Mw4s5(`^ z|2Kr{^d+_r3}H2sO?%f!KA}3zki4ZjU8XAcn9mA4&nbb}5V-ixnUTrVFj;QP}*(fhL0 zP#G9vQ=v}1s8X#ySPhjvXU-5!=&;TWdZ)ku7R{oa97Z+b*COW1@S8&?1%QiZC|ARD z;ZE@UDarnVp18c%BcM#F4)iPO01F<^ZFvsHclVFbBM@=G24oR6Xxh|t=Kw44<$V0{ zY?4sW@y4_I|L}MQ=%>0dUR24G5K-t60|K7KD_rKqlxTu(pk9<;aDavOavSYRUmSpM zsrMoHRysS%ms!r`0OA9z*?v=_S0SYQS@7wc!h> z^J*K0`4EHBnlBmn7R(Csv(_tKJVXamd_|2DZd^>EQ>90PxmD)du=I7q5@Ggy+ZAut`A* zNu?)@O8lk)fd2c>M@3}-OsH88Wfb~9D+$a=`oAhEFW$zm5TL(Qw7ug24p<2L=?c*P zLgLeHWj>QUNKX(h5XO^$0Q38Fqrv3GMsFp$YweIhg=JtS(GxJq2xfwwz(S-a5K^Gq zr~Ky-Jn^j)vY>uC^z;RI^Eo90=?U8-K7^he)>}i+ljk_}^t2#kb6*lYc~a=JN%T}>6_GRLQ<%jw2H0eXTYF?WN5f>Cc= zKDCFO#z-G5iWC~M{cA6p2T&inmqmZnz=mn=3~emcuLRN2ATV~3vqPY1F^}M+fLfwd z9z;njO~$X{u>5&&~X8}?h-n~kR z^nHZ_u$_7&mgkf82-fCy7k|?L30SHmveYKwR!SKQn@zMQO69wCpHh21nDV>yN4cEh zzbv{|pkC+bkdT$;w*WPKIUA$&RXmjf-MQjfIW^Tm{@x}^;o?```;GdWyRy@2BJQnm(qlG_)ygh@-@ka~$-6t63FvrpePNRQ@LxnXD z>l@w6)UR`c`bZcNgb+E0n+4Iy+-&J1N!#wAk5ra(6Db_cW9b7bH@0D|6Lvfc8UVHy z^<0YJt9Exgi4mSHc!%N^%WDB+FN(EwUkCcii${ddrOsF#ZEMFb14>5;6i zG8ZPkyYGjntvqE2cwFu7p9fc&^ym?-)AGJtuKZn4Lv8!09|wheYN;P@?dR7KT!j(E zN-7Ncj<~Kh{~iFJQB*Ra;p_xR3ZB3~c>2eYP3z44Uj_|CCILzi6};|b(dI2)+chjw z$(A1$zt5X5{{bz@{QfgG6dm0YA-{j=YyZpd|I6=`ZvXf2yXXH}e)oI~es_H71o%B} zD#y)gLJ4;#PN4|RC&r8i<6pO(<;Ado7PMW?4 zzy_VyyK-Qy=Lmiq!LU!_)kI2=6aSbMR}}etTzn~4-wB?_yS-oh7{@)2_Zjtk(0RNu zs=Ow$3b5@oKQ~;aSC$gYSlo#xkg7l4`PiXr9l*N}%OdvZQZI&@thNM)?#7njVcNRe zVS8eOZBC%L3@7CpB{$p4({k&nxkMh3t?AsTTSryiX=c?R){Rq#kLNa_LI9@i+lEV z_cwm{{HK2LTKm9E0(_EqMu_Vb9-W~v+>94J~N&#*V{8I-G2cMI3(&9~$^v~{Ne zK=kkRwT^?{!OfPb5KKV)@T2xu+UEnMb6`z3Uj%6;0q_?V%KoObcc}L){0rC)amLx` z);|U|$>4rZ=yVbfB_=wpPVMw>@lNj~I~fcAhE7knJB3zVHt0m!>B?UFxZ|xf--1*~ z8t);Jj*NG#>RQhK*1Sd?KBqe^t*U~@j~wff}5YjuAGw7jblW0W}vyt z3Hly9^pEWS3)Ue}8{d`YKf%~ZgU*WgKanz0=xAXUWaUI0zKFuWBc0`mT56fTCwd-e zAbsVT+ft`mL)U8C`MV0=*jiDN=Zif_48*#*5#QIEIR;z0v8S=`1DFJUqjV)%5+LRH zU~+<=p8$k7QPbn+Ay*z0tcFg^-QKdZ8?sAD4c$;;#XfPuP2qLe_DwHfG3dkA*#&7;F3u|>LhONCFJ1)L2rFptL#zMI>G<^slbIf7v9 zP{g@H>~~?nDdkLI)`jhTi(r#-9CSwFNHRlCI86vw9yS}m*l6T_h4b|&&oS^kVVRsK zob5JSUZ!bum7FJp5kVOw=Lshz)mbccX3Kd(9P0GvHu69rL@pRw8aH=7k5;%mva6a% zf%yaquxq*|l4m})m^wc}z}{6%k-2*hSGu-;@_=+sdCNg<9ga=Gu=uq|Z2SBT=|mxd zHjM2j8FYGx=3)GlvUO^#k((^V)~b^Zf0#m}>S%zXlx{9djB9{8K8K?td99h69_tPi zAJgu<1u~!8`MnRNVdH-h1hbkDd#|XPulS0^`L-7M)P-t0sGbWI_6B2+YIYGk;VwEg zwKA*s-mGR-j^ACE6IuWj3X`dh-f^4LI#!5b5-g+_ncJQL@D|dG%*Q1McPn>nn=4-6 zz+C2p>+lwkuS$EK!vPl=3VVnBn`FTeex7Vq^!hI7RECj4uMQ3+L9aNximiFG2GZ*y z(yI)r{igV!0yt9`mcy?W7D@2ZKy;SQv+Q0)NiEoK#bc&%N(!MsGCX`)6Dcyk0n*~o zzPO0z5q6r_T0>Oyg>!fHr~vwkS@adt)_t3(hX$Z0hz!i44kz-pe}%r#p|3Al1`2&y z=R~i^lOgFVrszvfM(`Xmh|H!h`yi)6Pn^EI*5ssK2?T|7Ik(@Zl3XS1Ym(fRbX1X! zL^slrEBveR|1lSuVmvMCM_m8VmA)g?Qvf<4ivP3#b~-dkv=G;IUO*Nu928-}PTm!N zrtFyG!v8}sxV0mG!$Lx!HpIUoZ^(ubyop#h8(B!>Q?%A6;PbdSJ#;yiCd^8SJ9JUgE$ZakEjamxv1~Up{z>f3 zl*382)-g6Zhv}};V-FNz7LyLn#e0?hl86KMg8Tw@2JpyJMg`aQ-LNUeeu~3q9>4<{ z3(!Fom>8?bG?V>eD=5bM_4m45^ba1HMvv7X&wPfiqAE#*`@VL$YC>}sV!z!n)$!PU!5CVhywDtdw z+wnE29b^Bp)$v-@F%~^_F9bTqwk)|E;9nbTrTONoDTD1npGpTFt@`Xq8f?a=)MtHa zpS|%u@5cimxR-Zd;4TOb7emFBXx(s2Dw?tHgE)pGcp`_@0X|4%h$GMpRX>{cwdxXx zIJYImOA`D|TK;o$DlMmnaB>E`J_Wq)AH?f_5s#}n(`xa&oLrTotUShwP)^bjR!Z=p zc%NYT=HWamP2Mh?U=13trh+wV09atLlf>x5R^`AHe=e9T9eFC9t!U#>2kdAZcoBBV z$HwMZ_WAX+!4E_83{RAkvRtoNmuRbm?#sS?3t(@q#&tN8u)bnLh3{e5b>ni&=`;qn z=i%_`&r!`d+|sVKaEFbrX-(#_@H2=g(?YNHM{8aB60uozXyJO~&fJGkzvU(Et`cG6 zU*|RCP3@Irvc?Lp zjOhvH7w|yapt{2#WUa>r8LjOG9QsL!jqx?>KT31;>Ctt$s{b84?3>d6EBjLWFQNkh zAxd+YkT`abOXoB5pspPbEO`=#2{Uo)M~%PuNv(M^Mt~!CYPpZgJK_tXXE3JX_V0)L z8>ZRt4g@v;3nb6{>;QBGA!g4XQ$AEBp&>CD*`5dJWPANEaN>S4u2@h`;pn4*_8V{iVUK0shik z_7X6vk+vtawFD590fG`hPzDG}0Kp)~C_Bf0$HV^{*xLamYNz=Ue+)Gd>4GE!if_*q zR^8wJhs;g<)F0cA>r?e`Jq*^j;`&rl3=(I&+hEDo(1mB729Zo{&b&fFM9s>Z*aKtf ze~eh#UQ(_{^S_!(pXni}Vb*#S9JC%?g+90rNtOH(H_WJ+utdiqEx8735h2OLL$7!h zeX+Z_eMM<_Hr0!=$MIfi-LKH)t3;dF)0GU?6L4Y-Q2DMFB@fH8sC+Xmt*y~oifHH5 z*A(zKUh&Pt-4~xSCYpItMO(x<86rJeF)OHQwZii?|To%pv1hEp!MsVyWX0^_{M_ z-lP1@Nkac4@0yuT5lTTr5&8g9t~ZiWZ|r|DS?1p(^2}15&zf^hG))bNqQr{CQ zZt>y)%)FUy^GoIA6khLQ+0f@3FZhWV?4XTa0dklLcP|(-)6wc50op??iZYyND{ilc zcx2mymfxpZ>Hh-qJSnmYAdV!6Bf>6m(&7*U1c`XOfFJSUiMxvsd&TGV6oNph?pf@Z zMn$}ip1tguZ9vXJPbv~8En8GhI@?KG1Sc)5S2$_GM{aXp4|zyk`j$_zV>@Y+>O3xW z)TM9Yq=o*c$EN3KZL=1bmjH|8Nb02Y2AZ=r$70syWjW?}^;C~PEx=O+Z6t?|DS&TX zSOwVCbRHjHFWsn|PdM)97!p^4rk_+RG+Eb;g;or>Y7Darr{~vMOKuqx7bbjd_jVFA zm+70q5vfw$Tw|5yCza-zd)rYrUS~UVoB|mN$E4=M8qde^uN@AnAx`2_5cjW*MGk>Q zde=${UsC?GXT+bjuR{TSXMpt?S7bT#1*<%Sa)c#pKikW=K%oAQ$bwD9&xUzRIJ3^d zlICYSyiW@LtU^YUc|diCsdM;A-ZrRg;vYjwIGJ_h28sgA4D*=qM6+kc-FL4c&~7z& zNC5r__g!~cg=)}tlKn(S^W9}$RZ8J8grjT-eFe<+{gB85rK3*oF(x>CF>~S>8_%3!n5dc{`tFB%0Gz`&go;gdpwS&v*J~%q)rQ5G0b!*=YSB5CtEEn#?nYDl?xGg<0kIoH( zZe6%E7KUG-_#fJxJFwov5nhP{h`_0mMOgGfvBWu;w~~qgIheC^{PkrPycUdD*mH^f zyHugqV98Ed!`~UShI5Kt)H=b0xMaf$?d-*38js^?8*paL+K%vN>|}*wx2EZqN=K*) zvKz-b-)BbxeGtxHoi`);9N=n&JcX<4M`peM_Ag z)_qHv52f{|b1|U+12%x1AL~sf_{1J%~e^xlpp=_bYjP*IjolHa6^( zTaEBV11zjitt9sfD2aC*@s@GwTa=bkok)RVFfUhUbdBnArFjf)U-U5h8dwT{=aolB zSAGW{H@9a{%ezPxINf~Su9sRTopq*Kb$+MnTy>2!k6TsHR;TnAYZn*6M2C5o-45ksKIhuBZKFG_)d;)3`@{)eyqVUYh}9Q2$4{s$PR zI@}97(iuo+4C!VNezv%nJH*VFet?FO-V~0qU&rJm#YQ3%w0*T#=O5hnKmsumGXu3Iq4}*y4|PR z+7+B~L!P$IWINotWc;(-_$M|nWd&m0@O!SDp*8;=&ywta?kBLD*hA4QU?1219RR%; z>rH5JNa!yg0R4Rg%Z7e29@1EsLNFLrJ#5MmWdIjWV$T6!hKFiK@qX>jd63VX7G7SB zpsO9ASc3(T;tU+hgL0x!QMz#%ERrY%tzI3hSEmTKmGU1K?2+WLMqHg!PIaR%<&x@H z_8ADHrCKYa#Lg*#q{qFTxa3pplv+|l9jT$fvRKMRSl7n4mDGyGQYscpx!b$|l2SM3 zt8FD{CCOrm*BK#o$`jj4YH6{Q!eS|(VYYmc^I8sJbXYVP3>nIab)hrwH~HxMoD(lFc;sBd zV45FlKT0iiwj>zF4uGLC4#OoD42^Vzf01-zZ%NVGN`*YaAP>?(0qru(NmnU$rZjJ{ z=F3`3l)PGyvXt=7XK0lvcRqV6)$CiFPPBEuC4JKju{NGy!m*;l5F5st+`L=_Fv8A9#USWd_3}>bX5`p7UozxvAo#ACA6QIaFRcD{36N?;e&r={<~90ouI)> z@I+{k6K^gorW^+|G;;XIV}>)7J@^Uvp#|$v@(d(k`4v~H{}z5o8vsLsAI`C0I6;1p z`AIN^nn#N&u>U~OLi}QFtaeyWq0M7SmGzY7JPmlRtq+0|aDF-AKUH^HVE#^7fzpT-CxC~PX0aT5&nUlX5OWwqs0BybO>N17*RyzoAM8o zTK)n1PUq)~@K$%J7Z^b;B8_K%l3aU&VcVXkegfZB^8L;T38dcdT!1^U7+QeFlZbu$ zqP{e(Z8yr>p@n)S>hN1!@pdvU_(#-%Aqd^F74OcYwqk88vF2AdoUh_Yo9&)@3ZGnY zRxC{v;G<`A$nCt>NxsKsI3FEYzaX{#O%!@|eK-cv@c8E8=%^7d;;IwFxhm0u<=>1t zzjHOwv{zmXxN+}VEHoyT{p1{!c9*y@Y4AxoFTavaXJ8EWiBc4vD}`zHm*Aq#3N}Rm zcxaA?$@wiUBADOO@_CGDc@bZp=AL%GHr98(=AJQC8ylF4d=U8{@(Yk(fc$dgmm|L# z`PIg4+=&=j%fGsD8{-dpWUVB|ZTG31B*twIsGKANKJO;qs|!Yb=i^IuLEPxYyOVIv z6Ho^8w+;>HqZgvNxIR{b6)w%!>OksG!w+v-dDNS(!}JWlVSyEhDCiVe$R&Y=9Kj0U z6s;nFA>wylYAvbX%ezw4D10yP=XlxFzW{^9`rh2KxrbR6|6ZPXF^w61Z_baY>9R@3 zno%v5{rB0dkeJdN5QU{?&(H6Tk@o3nxL=x4QAaNqEvjfdC=&OFKPsTCMLk>=Kmx}a zgKN$}7;=x0Mc({=;F0GOj7D|B#uWJjO94I{9A?-oUn&Fw z(G|7`qTO$x-R7-uvuHXk?jrjlcxym1eqhA81b1KQgRt}^KxOcndff;%R*!K=Xzq|g=j7wL)DEmV@{qPt13_c#^;ARlg-63h92xGPw+0^V6{yn(3>8c{Bu;p zMPIm9TLFNgdqFMM$W@|)cjCf|@6+F8*{5j|laE!njb|d)VY!iGPz9uk>-y$ln+{tr zeDSM*q(SI8x`2woRut~WDpvvX5EKa?xy(Ayi(M4RLfX&E^=!h!c6`SJzJIu#qN5kg z2SfY}ZZHFHqANWaIKn4p1k^|1*Nb+j!r>3_`XHM?Ve>XlwtpKA31hkky#68Yf9b^D zCw>O`{0=YY1Tr$$@RbwIm% zbOZJelOer-*WPSDppA{L2S)Iq@D$;I(>}!`m9l4aKsf)@vK3otf@Je9~vJRrX`6 zY?H&y%j0p|?Wxw2JM1SKe#El(>+CzUirukaFUAA8DV0Nu?NS}{rz&D=qpAqSj4K-; zk}nD)Q;F}Is!HdA;Y#q8BJM_s!QG(PZBY*!?N4l)pYLTGhg2q0GAFUYgPktPOja4UWV|Zlk<47X zU!(^+yTF>9|EIQ*@aj$mQ_fXt?#G~DI z4}PqDbrQGNWW}~NZ{3IOdPXP2oJm2c^;j0t7klBU|3L5sfkik=x$xP0qCuhu=43sLP5~@UNenhoCs^j8(uh0wj1Z-5(myn-MmW zN(SMHs8s{dm*&7H!yFwXW6>}*RqbmozlQ|H!%({ zki6i}Z$~WI7n`Gd(+_(uJ*M6EEKm-I*$bHI(&&s>Y0K7Imr1-B?#A|}sX4K5R@3U7 zv{-1A?^rv_e8nBBU*`=L)0jhm?kRtMZ)wZ!ThGHyb9)l@FJc(GYJ9Pd8PUuM*nWU} zPun_LM@{e*cdmZJci!Q?1<<&fZb|=O)tTCcnHfz-j;_jSx+QbXs*|)09oWiKY=&-* zekHT-VpPMc&l0e+Qs;kLO{^2f!1%OQ&Os*ud&}F@9qUWOJ8}j1j#x$QRNSw+A6mTk z;47uAHLlazo#bxf-OKra4kSLS)rdNSnAJCkHUlGFn@Fv`SdTC2J?6(%ws+l2GCd43 zy%RqsTU6T9+_Nv%j=jfNPVz}qyR7>(01*i>Cpr!E*$Mh=2RR8nN--WIFZ2qycPG=` z$0g65GWhndP8vX;oy1SuHh=om9J0VW8!6rbOL}|nXTzYM}H=Vz^N?YEJ7r$Rw9WZUZsDgiJgOnV--}xlC(_uei|y( z!lZC_a^(<{qO!0Zn|=KbteB0Euw(h>YE@XNR`l9xg=ebG6%Wd`;IH%fYGihwAyNPTR9 zntTm)Z=CRtt#1O>)Vt$&mnJ~LD>aBv){N|_iH!8|t{vQw#1*jM9E_)VOKq|VB@iab ze5L<8vpeELhup!?3pn)8(*iKkxb5IV4x@nJU*vS)d0~3oa>HQQWf8ml!)K(+gcX4H zD}mbIx5wLui$*QdVhwyAZ5N@dDM&9%=}V@JXe<(Nr0Zd-YpX{udz`6ythB~t+4F|8 zB++A@jL5?gor%?qNS=)D&XGCGQ89iDAdk(xKUoFNLV|u}4Z^g3T@B%I@#^@wVmW+NJrpD5n#4pcT{6auxc#CdH55K01 zD#**dAYC(CU4`v6zT)nN^I2X6CJW|6n76%<O4q7YeE9C?3X3HBd1A52p0P8$IITP502HJ%*8ePX;hF2?Q6mVAVdMS>TG3Sjb6SoqI8Be1Qn{2x}6BU(j0)5^u9JTgL!z#ZNZCDf9wPC+qpo zB-S^u-vnoCh912Z=za zRmJbv2IPB;Jy;uQ;6b7J4#el7Peg#wKm{7On^*)cMp5e4v7ril&Li2%kHgDl^2Fd} zP3bBDFQ>xGWmX`DV4Fw52C!>7UV~uURTDW`flvH^_ym5ob3FLjAQb7u2(W+vcs4x8 zYLkX@t|9f1kmNfB!Emy1mXUuo+&dkV00Xo-)ILO5g7{RB1nhP z5|k2*ZsabO`Q#V>^!kkU_-KV5^muP`(A8X-8h^A>x@u%sgJ#bfw(9eB`o|Lrf0LX&}5#DOu$4}64e!~P&l+~`c)w|%KZorFg% zNwvt|T9-}$sxmXW$}%%r%Q6bvy{#*qHTZNyRRcaUO@kHwzx>|y_~2G+FnyR3KmFjR zfRULCw`0I~Az(ZOIZN3}z1i3k%YFrsuDFj>l(^Lisf0si%LI_-_^Z<~S|>+jAO0IS&6FXTI=3NcqmE+~@-32J-SX z$V&t~MyP=$%~xHQH~koVXyn7j%uL9VW=t7mixWc{hFwZ1Za7C|wvw7j`kRuUaPClj zQ}Q#51{DMr#fnJMB+2rT0+Rp($7vFy!ZPTn*r)cOm}E4N89Fm=cng zqdDu4m8GBEP2m8Xcne?Rs30R-OEYS^OEd3w)D*u=*+{iDkpH}GFKy zT>j%W9!vi75ODZ&29bZk&c}`>IZj8LlkxAf_;)e>U50<9 z_*ag9^YPD?XQIJ(G)xBxZ4E|G{{YSSHpLw9vrlTmUm6S!L`2j0VdIWIS4|-gP(3)K+scG(m3OsEDI%sM<77LGQYJ|(w)l~FBIKvm~#KpX#9KT))2gyzw6C}6g%WOxwfkDDf4j&4lN^%KPN<}Eg0r|a}hs>wp zqe#284c83wJ(h(5cf9TzxyNs8kCtEvpz2$F_zo4^a!sq#vpxu)F|BE}+x0>C6y}Ek zrA(c%@GxI&EAUD6I6cc3+sx1Fwc{gJ_%!C~Eo5JJw8V*VWV!=Oo|)E~d6F+$f^W9= zz$|5{oGNmmd@MZ$0`|0FrL8lZ7T8H%o~D~!4)}QBM+}X%9KH$13Z1U0K{fFRi@Pb=LsPh$C@P3fKh~WUi+uo% zzPkqB7n}wT?*V~N1b-<4SNoMx=o_|yqHz*99E+IT%o3ZppVQi27S#4cOJc3#rT_;u zT;|73p};YQ!7+=!e#&)-7I>N<0Raf$4O#HgGdl=g843;81TJjeWNOW~Ei|u!!fflE zp2CArlwakMOYzPIjXvKWM}iQN{h7*Ni{tGW%irLxg>|0r*4AVk1|i0@+lGVZfS?!f zuge#m@c~bbtU*gP>+zcM*Jg{q7M!>`C;bEQ-e!Cd9tBq{NT;nG&c^3zO5qp?GKXe% zSnk_=2o|_+F1756&p8}@CEyKjQA0*}D*ST8p);IZ}l@ED((wi>yO@?CH~sd=rruEejbqBitT}Z;0AJR zfPc4r^;;V$CV-8;r{S=~EXw@R$Gh%Zzye`<9MPY?-{L6-@B%y?5H^2HN8{v#X~)n7 zfEza+TG(qisM`a^7+>QDgudcK4FRBFryjlRhtT+ak5RU!;A3d{y4{km5U;as3Va65 z?G|^dR=U4`WX+*hPCK}^i+*RJs+NOccj>w}@Tn&Q%hc26E;*qTcNt;P;(~1XSVX@E zk6QGF_-GQRLa83$kEL@_YiT8MZMZ5cI_=h<|4rN?n!krvXM}EOI_eD7z$4pqG(9{K zb?~8tvJpW8>`Q~Y7cSb7bYb;t@ZD}Aky@TwAbTkP>?As4i^?*S{IjD_t&;oIz*eCG^EYqZm&|tT-NK&|VHCIUb<)Nvp4pwOdVM zc<~?OP}thH3&sH1=RT6_MvC!l{*^VJb-50d;JaKseqLXR#qT6Cs<55C*;Y@MZKOL6L)R90SNbmf?U5-i|;i+RLy4 zq!Ru94Qh&4J~SLh23&nvu%#Fke*)!b53OQ{!o?3D$FvoxmWN&{@x2dx@(PwC)YWbU z3#E^-16e(zmk}dyooYdXDq*;_SGa0m1&`QB!tVPXBvUZ*hv?qxzGRJx~XZO@5l@I5+;><`Ic#~Zo+Sh`gp)^4d+XYWYTuHx+fEZIMNInj9$ z1eE!3D+2MG51?(pce<_b+VXAG<*oivKzkvHRvN;<88kaQ!&%O|%d07e-CU7X;G;e$z_@RTKu^vh(C0|xbJMYCXhKI8^+E8YtKm;tKJTA2SyA@!}_$1L7yH z6ONw@9~3{i7~OyJ_z5&qXTwk81A!IzfBh4N z4~nN8M9_>oC>R(8C0sRviw88Nj|`{S`cgt4S9j}rw6+lUN4>T2SHJw_FA;q@^k#JW zC?IX`uD771AI|86Rv61(!C;-jm*wUCiodlnGdkVb3TvnB`PS=Tf%Ln&%CczwI$N(B zPLry&Y#0MZT?`n(vrVsVe!DI2H(=O7$B0CH4H^|{C_jkuZ+Dd{_qKzhh6)3hMUun9 zQV6Y}8@X^$yp8ly@}mU3BxVm^CHb)sjEq|bjlu7FizCnI1hJSh?i+Ju+(I=_RzOe^ zm79{}?p^~V&~5-CEGz_~K02r}<0v3nfD&Q?G9lRqp0F>l@`^WH5F$zn5MjOLJTupA4Uv=?6HqG|LE$(=0EelV*agxezN)h;lDEfqI%lF zj(=hPGyf~*|IF0+ANI-S9~Zj8wPEr9kwbrumW}}z91&jFZ}UI8vQ`btpUK@nUEa)N z(bB9|8n@4RTN@w)-f?x6WZecD$U29&v`<^#7EuDy(r<^r2jwG#fM|tc>D!Xvl}WaMgv1l?HHEt6y;cG;;lGaW zufTZVxlW7}l7EEXcz)Mg0mHQB{YEsLI!^3fQ1cE4wupWrl1}Zith+JJ3`^+ICw+#9 z^QVLPPtu;*fI}*N7ktWeXmdY>lJ~Yy^Y~@s$Q+2$XZZ3|wH+$%e}Ng(*}QoK+!vir z_+2w0FGrn=y=WP5S>&lZ3VM7Qdx6d8>)}O6c6nnv#1m(58~{`{BgB2)NlVB8dZ1Im zBX^w8P{IW#DGMaNBerMPTNaM4khYWKytQNu#4X_DR|^A>^9>wWh$F|3m0*&DES|CL zDST9_)jt8~vG-2^J$AeTYog3NEK_^N|9ZMTh+aH;__yH} z37@2Qbhv8{;i{zr;q(KW^^UFXzOTb|ffxEtwbH-C=ZSp$3`IYr`*!osZrL+)lHU9t zHV2sB&%!2kr@0CVpLXCWVtt|KK(KPH%$8t8_u!lI(BdlGIEp3Qhf`DUDlc)Dw+HVX z4QRhTtY_f*H=fqqtjD&KaqHO7se$}sWZNpZWz1^nWoPX9{=HD%JP8-LieC;*2;}3=iPen$?=VN%4ePPZ{eS9@tKZmC z-%w!fW}?LHdkH=T;^;4ML?mz%bG8lLHB7tG;sl#68?2`uWOM^9yg52JVBB#U>-Ii5Zj2PYoGY?{ABjtg&* z9&tYS9sGtD4I4q*At{^}GH*ByCK2cR_p6$4HaHz9>UKVl6875d?8Pt4Jj!0Qer<&A z>CkUzM}wnx^UdzeH1?b*H%4!QOBzsSdh9~@>_-2GU5FQ_OaO!qhL$i{bQXBkfjlpd zjAR!AQM&P;htX;wc6PU02RnAevR}oBNdQyy=B2qs;xvS@jJ*x=wO&!6yXZ-*lTDe@g5Wr7V|w+#kTY7%_m?40(%*7PMeov z9?a8G5e1(?VxG%_0x8J8pBRjez5|JQEu12-LC-atR5KpLb(g8sJnwd1i_SQW z*h_!McJnfT;awNgT4rI6%tL6IOGI;#BLw@d$GlC(5<)l-X6$zJ^$e(^hT1kxW#yTe z(}m^~B2#?eJksfrJ<2w&)OAtbJKi;%&m!hq_)<&znoM{BD`GtnXD3R`C|dX4aTu5? zYQC%uCFwSruIGrqjZsBTe}Farh@aj&cA9Gd9-PZ}>@e>aK(%`}E1MEaYW(O1{3r&T zdzB)GAck~&9n_LUUYy_L$1LA%*&WuVWKTugYdCMe1AY)sX+E5`>O2#>Ij|uMW+Gha z+PWxmK!KQT=8t$b(0UZQF9|Dx8V6c zUWFe%9uom6T-UcMMP~Bm5?o+4dJ16CBO`IShKo#$Z^q)wrBU5wULhRd49N40gdC;C zj$_|Z=NIJ(KC~Kj=E_fq9voti%URX_-t6PFe?a)hIrg~iXC>NyTN)X%{hN;0{@rXJ zb0P~N`R& zxKoH(A{7D^bE;Didd%0j-bAx^PDeXZaGLZHe|{FFa5VdpGW+>^;3~Y256J_#_HiiI zN_`CRWBD15EZfdAe}GyL#AjCPM&{%KkR7jj=y&42h0wUd_Wio{@aS<^9m4O(5z4&H zxQp!&$IEw@sCTo>JHVd(DDvFRyz8)d}p%_v*SvdL1W z-P7KGy>4Xhg3C0}+!Hf8AN8V@=6zqx?|CRK@JvszurnAb-G_gs=9UyeI(PYgZLHIY zW(GeSJNkofGBl^^9FgB+N2j4K>6-iQy$d%#im^J(I*22nmb8=;G&(kxUxRqn6ldud zvH#{KeTlOXKS0qJOESv6c1lGl2=Tg&Bk^9%6kkqwUN9fWgM8!k=$ssc`0x{(uSPWm zqoZ&@eq3&#cvmRLm@z7duWyeqrnxdYcpWY@uFkyvSFm>js{&CnuKDI%$5;7l1c-YW zQeHOLyd_8JGl0%>$6j+4KrY-3ERJ0F5)L4KE&JHLGS$$7)x0)cb~Xm|$ZR+Un z;JJA-0oaPKplSZ?5QPAc_h<+o{*0`DXwPZwhxWvHk3t^GK_4EAK0JDJb&f-S?7|0M z`Rx7q?AG}z);Ya+b9kjXKmH&iO}zLjQi|)w??eu}sXx!(jD_NNwA`ceF6K+2df+y! zj(r}z5Wfpc-Fjh%{wScpe`x7!WD4!hiZ=t|4ydGGW}lz|T|d-|Yz?y*#6sZ}E--Gr z`LaXQ$HLe%c`70c?Og zw#gqJ8V@@dDl%Gn_z-fwLXWht8_;W13Vj4C*a6Ldz(4(jS^jtP^@eh#npQ0PZ@VAFR$ve&H5zNF3dh=#{v;5`yKMznG zxE?9_ZJnFdww4TP%lA=jb#h%pdv42Cg#K=GL36bU2Ew%(&iC$6I2|KdPY{wL z;tb;#2?7WAloASenAjF1GC?lV!uBc7DpZ8ZK#?5(FE;raXpynWe)+pX{#MD~v*hnM z`Fn=^^~&Eb$=`YM_e%NukohZkVgAiwXDzqqTGl>)4&R)pyX5iA#h+C;RZt`tl_enTPfS zGj<`46+C-aV9Dkg#yFt1#Le5cGG@9C`ZBZ-j-mQ8n)mGwW?*qfCtI)W%XkO=irD0d z0!bV_){lgLD7G*4nQq+S1$@v(-F@q8Aq|uAO^JNpvw`GidfywtB>#66#DG5or?7|t6s((G?(&#y4Qf+~f(p(qW5 zYPa4RrUg&mKM2c*zyEpr{Vv#J@%Q=8Ty+&to^<Y>%;#{0+#e33??*CN zn9w`Tjq)K@b>G-NfhZJjQD8Wc_U0zqs~yx{ZfbkP3Cv;OB-(_@G%vvm((n7&0cwv# zAta82=`T0YzEuYLPpbdMbZiH; zX|3t29!D4-P$@@*sk9Cke8NvvUS%%tCjvx$!FT>_x{Tlgxkx$CTZ(^JpUWW!N{iMO zEou1jzR;-dQV&3&`qV$nTnqJMPy=`1eYV-xf-fQ_+BJUzZ|xmuOr9-^KU4FVW?->{ z76EGY1f!$h!5k1&8`75#sE!ICQUNI`C9QDl+9C+xcI}=HqXXpx>wo|Ie+>h*w6yVG z$V!{6^lmHtzLh>?rH@9#z@LS`y^7iw)to&i?`ED!ywv{$o=^`r)TIuCh zdZCqm#!7LEpfvrKmD>GuS^fOOO7{$aW6Xg1|JdSaVoUBGmD=s#?j$KMu+n(>C;ZX) zrfSdIrqX?L(xm;SD^zMXyWgtU^aoWh^9hyCUva~Vm8({GsvDP7*M*j?Tw%RX`xo_m zVEunvywtOJ`SO)Z7OTqUht;dEUwo5iMfEDr^6C}WhicjMjnzv+E9v0Fk;3P8`M`8zpL%ZdjptUC-)G@%KKA@3~E-1y)*RrFB-i-bx>^(q1dwXQkd|^?s9; zR;^R{b}PTn$}d=O!Gg&RI1{>5@y)drE9*o0;uTAmSJz*)Y{k-*s~Rr7bZ&JhT*n6s zJ*D;aE9*Tg>#A2QTXDUop}KzA;^m$?JUSBwHvYSIUgH&wS5!BIm!opY$}fL8ykeP> z>7Iu0k|os*4Hpcq$EH2Y8a&HZc)|_UXAWv-`r>8FtCxC0^@~?De0dqFu4o9=hnH}r z@YF3{azk}U-Z|cT*H?!;4WY%MaD!FbQ&Ye4%bumxH!fSEdK&iTL9c*V+rwNvUP;26|qO1+Bum7$eORxbA}U0KaW zG2Cz+C&e?b7QNJjR|u{M%e7ZDRtUyqA{TlBE9$}_&y6dWhZbL7?WyMMD*O+q=UZ|8 z@@miWWki3X*5LML-&p4GJ>Eth4yx%z`;B?jC#-=l@i(+WHqxId{BkQ-UMC~mNbN%M}N`G~241dv8&CW`HrFna0U6a~p z8>JQ;X*Z-VmS)2}Qq9C%>BEZ9gOTNOiVP#`CzM{~$IC~TQ&f`Ze5!n8zMH*nKMy|C zK$)x3$*elQ{N~E-m_5{%@;93Om0q3=DxFR*>K-mc<{w(Os%^7>9Z zlua3dg@Hx1gw6}()4agkz#OU$)KDF{1I=`8;Oc;vY_u_84_r!L39P3TR2+CA@DjaB zF9(j$TY=vOUZX*JKk%Qx$MpBWKj|p_DbPXPf$s+%q-O&^rYGnJfx80VqWkD>EK|M_ z_*$Tq+FEW>ZdJbCvPbz&%ePzZRQ4%PwmjGJjPg*+qe_?ZKub{hYstV(IiMJ*R9m$h7>lq(mv_*%9rJCz+RwMu=<)|M*e zw3aU^XDes46e&wv&TT1BOv<#DQ(I;#DJ^MAoT9WC+Y*ea#-z3!C^+A@t6^HvH_RF?c zjBm94!FbsCtG4&rJ}`c2{HX1i@gHsf)Ana$XIqc)VdMAO_8WiH_Eg(r#&+X3+rHa& zkMWka+l)6DTiODK8(VL0z1eVY>-~n^hC5mxZ~dX+fZ^%ZKEorey{&r()QE{@(Dj)?XM78h+AR(z?>H*083v!f<)(=GHQU$I#Szed{%b zZLJLkr=hadY&gC3oYpf9=eJ&9C^Rf+&1#))m}SUqO*BkxoziMB%!$7%7mqUOo%h7^ zhw=}^{qg{)MH{0EXr$gd?+d-0G4z_D$G6!#Ku5DjnqK}GdOME`dwrn!qxknJ%ES5Q zN73Ww0S>La&6-{Zs5!zO>kYiCy*CBQ_DoUqv}7T|_0{q3VSAj8>yPC}219DFj~}8O!M<4&u^qODr*pJI(&I-YwNdo6WFf-o^CdmmzxIEI)KvctVc)EY z^n95{>g|c5H*868oUT^V)ANm{w>mCVc)C?^!n3}>y+jFlAc~KEI$T+^o{KgM)6NS zu2W7oAnD2W_I<2tiSfH1`;q;R(?|BxUC=XYNp*WXZ!D4QaXr~2J+{O3tR)K(mYXF# z-5$#$`&IiV!};p=m`3{7|LI6QuCIQi*Ei1R$T;lz^oA`7j?)JuJ-uF{>6!43gIPPkdh&MfsvS<=XMg#2(VKq*-ed`pehd%TalXg= z@ps@YJ~Dia9~eG?#1%MJ5pgU{)g1n}dzk%VIa~PsINf;uYufdrMs<0JawTHZh{_is zI(o<3M7Z}Cb7TGe((ywQ&xzQEzKJ(X#0124<E--6O*4+;URKyvwqeBv%by>~z2I4&^~uv`O}{ng#UV~tvUtlz+(GhfsrGy8wybdZ zw)q=9TUO)V{gxFw8Y=7E&91r)E55R&`mD3IR5iKloLjDTH!LdLf-6wmwAkWouCq5U zDzsO7Jo7!yDv{-xAPnB{;TWwdDPPOKE8ze?-|uSn=Q-VA$pKl%Q@X6afn{`v$P6O% z>KpPb7BWMYj1!oUHKP+_JfgDZyZNd(@5`JFb1i2<^DUO@nysj3>?iVmNg3W&Eh%Ol ztF9wt8(C%x*SnNu6=AY9YFbCQOx3Fmli5@~Pq<9gYYvl@t9rQn6#lBdl&gB}kR8i{ z&t5KvHIJMy*`;b8W?5D) z^zy@GLeBzO^K|6XEPUyU!?;2|Vm}X!fVPWQ=+h#|Tter*3lzGQbws-quueXH;5=to zwvc63$fWiwWEnqu4PbGgrCr1_!n^|WG+&rk&ue{(wvXz-^Dy;YtNB$vpQ`UrXh}Mb zd$a@|h0f;mTWj1-U)~N?C!mOa==FK4^DGNk=70=;s8dy@`mO4Y@h>+wfpVQmlwFue z3Amj7=TC{uf5!C?IwH?k(T)%O33F$LIIf^mCl^kk1TMmkRvkOcfWm+Ol z^8?N)G_5d!rWIra6}(ZGP++j+X2(GbP{y91QZxetP}UbJ#rw7fi8UI8tyTeZCI17#ZzgL-BN zJKdnXy$H(ry#>noy${N|Q_)d*ojeni^HtL0C|$`Qqr+gEot{AHweggEFpc8<>12UU zIba$jnmrBmc083#N2gL^p-GkZsh$)^vQ0@g zQgT&-Bi@4aQ{!mr(FEj)Rq&}8JHRf@uDqX-lSt{_l)T^6oWp1{ShznXYW4K? zOBkpAu-_mx#=BQC8eTn9a30LWc1m=_tjCRP0Qn^9oZb)teYh@Wk6x z+vvwx=>J(|>7HogCKyCMIH{=ZqW0M&^jY*<^kcQps$(fh9Y11RC8*;{Nr|Hr_?%KO zB{-Yg)5&!?g#zcG51@Vzhy0F|VXYwPD5eB5AwLuHGZmx;_3~RWgFFk&dRMfyysvPd z!MIAtxJoZb@hIwe(#9R;)41jEfqjBa91qoL2WG@;7ojROoASQ0HIcTKvt6{eNax9& zlR$G&e1#Y1p5jmjA3J!k_PevQ0kD zTP|p%Kb&uFUL2iNHp4UBF-;v4wUDX4AdODJs+;bM>3FygR@ko4bW9hBbPb@qb!z*p z!V=6Jc*7ewgmJwt{=`j(jO~i`ljdK9+7{$l>a_0zqDl{RS77UgLQc8 z7$twsON_5H%SFy)q36&2 zqD=G)wjV9u!9S`=)PH)uw?^b^dPU?L)bdGLF48<%BJzC$l(&| z!!{$&%cj2wecL*bK5{K_?9W0TfIYRJXm;-d$uqLlaj4FHMUb=ZKD52uOt~MNy#Kb zKXmz=csvDlmqEcR@D79>?ansh`8=IQgkv<~80zovRH}t;2XHIv&q|v6XWw5`H8MLzx}~7Jd9{7D9lZ%^JMMxmw_^}_b!f+5()53+?W^l}^ar(1ziV*J z&WNK7tm)#hrt`Rn9tVzmtkv~l)H9AzmE`a@qfy94_^2qzz{2=PmpNP6l zAoG<(Wk4S8>(AyZ2*@c?&SM@j+csS10IIIKhE7!XAA)R)nqC~2_vJLP<^>zdZ>|&N zcp8+q%6hS{T%JakA5Wl)gHvb&d|Qiaz*XhRw7d}K#K#Olab1XO!g8!l;iGz8$a7l( z=1ot$MXeWSG7Wl&=3YgViu?Yv`Fh|e#(p`<8hMOsb%YG}mZkLaT$S@z;jhgn{EZx6 zgIa$GXvd!cp(SfU$&uCBvA#f=QiLP zXlhl`;1o}Sjj!_*KF^^&(#n#>xrgho8Qo|H(N4{-yszNHEeGsu_D`WQ*uu5cAY00q zo;tu32z>lAAXL^*4hu3#U^i z&I2hP3>l;kaC-HcY53Yk?R(`3G`I`n_3M~B|0C*H-d9dZrBnPVbPDS16r5L2K|ZGx z%pA-KPVdjniKnFJ^($hL4^E$yn9iu-}QpL=>TO)t+t+n8v&H*?SwOzY>XeLa6A zH<@z%0Q}E||G5Rz2D5@0{kf+lV@zgJwpYDBFp%6Y=DhH9sYsWCbVy$&(g}Nzp-xnr znmx5XVV~pOtN>ose3kdrHpCEC$9SQE($K%-okkkGkLb$ppr0$EeDc0}&F$wo4)^T& zn%l2kbMqXBYhb*KN~eAo>v%OSj7Q3}`LPl@)j+M5hrF-MN~Kv&0A-zpvd${V8Jr%> z9?0xBdDMRRnCOQ#Zom8_nqK=SN>g4^rUb*=pF<+g&Pkx0;|CSf;TM&}gTGYp4lEUR zqdv5J<$blUJTLl&Y8yYxJVoCBY65)~_e(CqIf<_^xNR)(LCl+pg!g6X4M6V~^1kR7 zS?Cv;H2u!-eqn_TB`2A3(1tna7ddFRoPzAZ%pmUDsq$3F#r?mWGEL6?6Z-1C8o7TW zZT}BYFOOjzWDxBq?<+HtX(q5pJ*L{a%9g})-JIdFe!rh+@lS{{UlmkAJ@Xn`;d^-KuT#AVHo;@v zjQb_Zw0PXVdWNPc`ze9-_+FqtiDuy5&J5h!nNeVZ6mkaJLcQu+-H!x!2tGt^1_*+X zC*uCRyqU1W&q#UWb0X6mz<+?b@J)Y~E9(_%dCHo)AGV0RSjPx>AdlvYZiAnd@+RkV zIEp{I{yp0J0{v6Pvq4lf<}f@qLOw(Id7AuGJkOnud}oO3TD~?lT_&z|0#313=KJG( zPo3A7yhi8sA+IfXePGQH2%xe&K*x2s-_Zg+P=-YV-vj6CZNA3h^|~4M`1*j?FgDn5 zAgu$s%rpAgCtOEc;7bSc3}ju?F?&A5J$2afeeRuWxa}a9@-p70W)M3VPoCtZ% z$m;^U+fEh$-%yaPPw4TOXMMaUPXjoH_u9#PBkE(WSj&0NfE_R7SVx#pRuk&L3QC~u z0RZ~==7Y?T1$KdlPadQXeocVy3tK$kZvaI{K{;TZal4e5hUq^*ZO>T8he3bq5NA8Qrt*5Y_0@<$!u8xA_OS)l=- z9qo;8Bvjzr6Jp@o6BYROgc$htL<5klX(oj>1FgU>fRBMy847I!z6Cr7{0Yd&ROkX=8}MD=Re-SG$^+H_ zR{?he2Y?_DpRLdtz*hi2@Br`&;6K2EX$sW<_X0l$J_F|C{ObVj0Q!Ls0Lu)8t^{rY z9s~w}kAb`#h01_$18)K;c(ZXCPzT%({0>-)AG&%DNIglROMr)f&w#>N3b}!2fRvN* zEE1>z?gD-SybGLmib6i%1t9xWg zX@v@H0=j|Y!0In6bRY0j;5}f@B84snb^?9CyTFojQMbT7z|VjoU}cd)yMfn%%<~jl z2iy<*3s}Bbp>G0j1LvNv(9OVG!2Bf&T@SnloW4|{%YcV~Pk;;YjGNEM1~O6{#Zv-J z!E<-qAE6XVrKwn2rjv;>Fa>7eowaE+oo3)1n@cn4B$`Dh<9&!z$xO3p4xNVe;OX=w znv3g-Gw{B|S$I}GkLJ@kSUWDD0$NCg^krH^=i>V0JX%cW<6ZZqbO9|RD;3jnD#1JL zrL>Y(;hy{&x{$s?YiS*=#|h6y7gHH+pmN$sn`kp`FDVZ?Y_~S}z@2)mB=(i9eCjKFhK$u&NUEGoE2tgeCqU!ZprZqw7vM+m)3*{{+fA zs`{id->{>hdYqNbna5NgU*@Y;NmZ`5Lu51O<)O7B8akHl$Sx5}b9@d;?!_$X$UI}J zjxW=&T47t!J6H64qw7vAWAS-gl$u+^!>&RdZ!vX74o!LBMK*3&Ax2ZwavdJS+NYJH zk59>BEPY$)@)e?)^=|+d#4KB}RDSJ)!Pv@CDnd(BFp&&mE04%v!RYg)T7|gS}_yF=mDC3_(U&CGkS`VrJt}%F?&fIs7@n`>el`yED4i~5sxf=uSSe$7#~3N?=f`! zj9nB}b4BUO;*D#|?aPZdt|%)mFST1^_*t-eIW4PHKl-+gePZBIyE^hDTVO5a6HA1V z*ba_r#ObtEdMoR#qfQF;^`&C*fUk2S)T2%bsy^HneukxqHIR@*Ez}6*SQ$v>H~5=s z@Wu7kP=&^>3k;^>3O#9+7oVwDW4URQ6URRD#;8ahpv&?^m>X*;SS?ykqZbY3^E<6p z?LQhVdX};M{UWl|u5-$pL-jM^B65wXYwD_z#wP51m@&0^%bPE1sN3-cxfjji;Erg9;lISC`bk;>|$sxV1s&-O9m%AQ>|JxmdOeGD49frish9}&az6} zz>!YyG5XSK9tE6ahu`HZ)`MM4AYlndI%)8iyX(iwj?ZiBwd_{lGojJX=WDdnIeZ&d z)@wgzE+vR%K0E;jhpB9+Msdd+L>r3H(wi0(s5cIf*NCLC8#*#+ z_@Yx?3dOiU;4H(nL-~h`!}p}y6QR7<@p=b-OZ`Yx?Pys`i{IglC82CATBiD42`%6C zm1FiSo~uym6dF!&j-Gz>yyf&f z4mTi*j|+i>#ymI3BXT(M)&#s>t@V#6iN|(XP3)E?o$;;jN2C~K)QT$tw@>tRt{Z&) zIgZKAuFg~SmD?g$Rgnt`zALDnj-%*~IN7TUd+ucs%CT-j#L|ye;8>2ZZfr+565BY} z5TZ&vCv+7OI@h1L8TAy(y)Vqv=$$UwRVtr}zZf$ikGyzbvw+X1WhZboqgK@d_AHvY z$(1wQ+=;AU#D!MKGs)D%JyWmQBvU6;Yic7zmQ%7g3HP{%ge(?(5$zh*Qz9)++(S4x z(xTKP6JDPVx321(WNPBhg<4lLCAGyQ{EAUj$>=0Jj5J#KMYQo6?l$`HjkGv%Ct+=* zMX6yXQI}!PNv0<5T&RuJa`IYWoJ)vk6Eb(@XhoHbPQt@TqvJg3v4f@RI)x`F$%RSO zH=7F0Ba*4fm1fwK)O3^ZD%5t8nMrsgnURV%8Gpj6DXcF|#x2QORb%6c-1lHhV#tIU znz&QLhPJ8;vlG3si0kArOitX#XePh7cGb%*S)8nk+JLHW+&($|? zmtVIv;hr>X3pYk5aOcdvUOh1&(L}ElFkhiZYt@{q;I6T3Aa{+xi4e}9f!>m@zbw&(NXVjsDo&vYSf7%itd=h zIovd>k2*%f)hDPr4yX0uI^q7LpX)*n>Xs(lM8lT!n{MNnMEzLZit#R#$5HPi6O2)v z;R(j8tk=V&YIK2mB9#iKTbop^3Tuene^ryq&e6&Fb~#=*81sI)1#QB&%S(%CS23BobZ*u>d1*t1mPVd!rmlG6=_eZqsew( z^&FrTS28zQ=hz%Jj+v-$wadW|;JbC}u;$eF$ARB_LLXtTl%Xv-rVkG_V@8=EIAJ@)*e?L$3k;vcAD~~I~eZZCYJt3lh z$8Y9!g1R$ZS)u+M(3(c=*Ij5%oUI8z7Q(+_L_b$nx%|v&4x8dHxxLnXMm zC=3@ZfqXsl!V^;#oYta4O+< zv)HEkN&~*Oj6*KGzpm1^jVvQ9mozrvXRN*Simn&(?`2)0vpGNE{Z@DlZL=xuyN{DzC&#lM9TI;dTZ(z*?sN^A=XEyB`L zs(01%T^W2eX7@DV*N|WmUyeaqUF$`R60+OzmZBZr*1H?H@QIL=*nRjh7=Fvh;&lA35!N!iBr^^+O z7kR8k9K$zlC|R{<2b8#;xGwQ?hqbhohU*XY>~3)TS%B~KLcHCDuk`FbSFOFqUB_;7 zL+8LoV?&L5D;mb$P>J@u+Kyks*^Zy87b)>8UhZo`hg=QY-QLEAdb|~c$P{53jSa45 zx8LsPAJjo)1+sfxTTz|JM?0eb*c7*ytJziE z{<@M%584+4A499zPfxOJZDZrMCeKRkhqOxZ`%mbR2l&V)x7XiPS+}tPj^jJ(JL5Mt zh_37m^+ilDs362?;yEMc;dBGf4dPuaTxaobLm`4exjtTW5qXSjeA-T_-ezi z8F6EoM%q~8q-;rwQG)poLVAm(8+M@W)LE_A$MYc1A2dT*;r4L@3+1)$DsQECM+rKi zkIIc}(CI{X*{~KZzZ&M~O8B(GRn@e0tIMnVl7`-mVY!lrkM^?BLNO=*_y5QmDA@bQ zd3T?MIH#AJU#mIH5h+BB3_hzHfOE{@X;|KbZ|e6%{Jz8dWyPEP`iy6_Mm-)e;j4zD z*$K_SV(yQrr`qG+WVK_GvWt_3o+O%GUchTTLVgV}ru~?2xgkYV``TTK*vsD0)5TtW z$4EC^o+$5Vs>K@npNZ%UpzdA7PyoF|5YiC571RxIj5&@ak~kf49>8<#lKp@Myc#oPhDgit zOy=dF?2yaxqvhDr{WzY7m>@-if-VGK4xZ^!zzLpXhWz^!gd71c$B(umw#A)hqTP@) zy&HHKdYh*NO@Jjbhu&l5g#+>0i}rx;>6Xg9!Rkz+k`Txbt)_P+)7gSUcbdJ|9% zo@0q@LmUw&>wspTiMS`=Io9+2z%K9|pl6(oSdQQ=pf3Oizz=|4GGE9Ypzi@J$0zi3 z9dHPISPW+i(G@@ta;9Ct5O}7K1F2~De$c`NqAYSOXO8jwH{fjOF#Q~`f;SZ)W(Qyc z&vfxZQ1DjJZvxzxIzXot3f>I52VmdixXv8!`Qr27FZ7w-0PF_e&irEd$UNxF0NWe@ zO*&uj9H*IMBkzZt>Aoe16Z4*+mo3$N15LR=@EpJRQQ!#cfUaMLm`lfT473g4cH|hp z_Z6cbL*4;;7+`r2^qmrv@qP4d(3}-QZU$YW@dKdKN;NsCOXEGDGgfPI&`oRL1ME0J zr>qrnj)A*!9qR7`_yhVP&q{WdYUW#>%l_IYw-0 zIqDNSOsjy0!85G~4uF?qz;bNZ;!Us*In&L+aqx2NSB?pru^D}4NYEMJ&EVxYuN()K zW4bPZT#oI^F<Kb6l9;0&1Ou#$SfxkaH}fxd6*Kme4AV zw}D;<9DxqU(9vVH%5hjZKI@_@5XbH#LC*)j8a&hGKm~Y?Me{nK<_oIFV^yggV;4Gd z>{L0fD#uryQib}24%1BF2zaJ*fn(sAE&_(Yb8MU40O!TAlip?iW3*{C<{%&+d^VbD$hN(^SOcaf0W#JWhap;8;>e06*j$Ppa9CehXfX9m+99r(TKjeJW@c z_-ycU{7{Y~`VHW0$eFG|tf3X)=l z4Qv6=v7uJ@#C*9Qa*qF`$K90UX>y#+H@Blq zp9}gn_!Z!pz5|ql=U7;OZARNL530w|WO@YH1v%5d0Qa#D=tp10oB$p{PH4lm7(d`S z7SnG5?n{pA5K;?J$HnzTw+B!^&}j$V53qay^z;_g&wtQ|KyL!_z_)|WYK0#x2i**) z{TB39fXf~PEoehopu@4Lt^(GA=Xgy&(D;7Pi*FF^!f~a31(ZW42%2@Hu*vbct_0X7 z$J&~8lhEP#Q?GvwV;A}yUrLXq$@KD@(N7>}x(nz7&vC5Yy%l8x&vB=o19;ui5Bghx zeG7uVd>hUU%!3x)jy3?#F~lAOJ_XOQwJvMNm?6Y$0=*aDIEYL$??4*xOuq!I1Jf=ns%H{SZhrpp3ofX8`vNjHgA7D;kJD_^pOs1~@M<8eV2jCs>9Al5;0?g_ zJ96Aij-UAokZnX-&_4kA;0Hl7euy%H&jWP;JU=jf8CU}OtDy6rLK(qZLAL>{QwQ3i z@l3DUkG6x3AM~%l9`MINi=Gy1MW)ry;9LN?6ZCE12HpgJ%6m@EjM?t?>cS=K-F74uT#9xc@Va`?287pqBu=j@<&9nYdq860qp0Spxymg+n`*1pv6DI*aN=;v=(3;rgv%l zZqUDI{87+P0Ji@rXy5awf3^eqGl1oTpeZj1J{$CsgP0GXvjwyV;Ckx=eOKd$K!5xa z<^$+(oY*@6wzC`bAHaQ(n+{=a1onXE-&*+yD0&Zb=*zec1rCAd-x|3EupLLaLEiud z!1Hf(7+-<>eas7>3xPx6t)LFT@`0cM@O!{>Tvm>^I)FaFlw+qd&y?e$GS8G_pEA#s zPI-Ht_!!wk#B45wHrl5Lge`G`d-%mxHDN|K0wt*MRulx*QDE@RD-uKa8U& za{Szf`ujMJfI`l|G-VzN&7A83r1BOXuRz$6{Y~t*gG$H?Q7Z?QQfm*7)b) z>BizpU;X^;3+9^f(92zeXEWN@n<6)uGMkt9y-hxRLtE3RS(`J4wS{xkbV%vLqXayy z+oA14qCQo_?Q5sa>)wug*IQk_&_VfdsrnQGpOLP0ZFkj~>-hiDxs|>(4ci;Hxx91D zP441qzTLibZcSyK&o$S4PRP!Zb7JSRRgg0XJy#Ze9U~b!M z*=yaqdT;yQJ$pO$_U+xjw}0=Uy~p+r?j71|>dfghcX~RTI|H4&I@>$E1`?~jc_je!a9_T*O9qc~VJ=i^ju!@O2rkF~r=&9}T^fdPbdUo}+_w4EE=;`a(*R#K;zvocTK+ln$V9&9h!JZ)mWlZcf z_2%@Nd-HoOy+ys&-qpRf-ilsFZ*8xqx4AdayQ{aocTaCeZ(r}e-u=D(y@z@SdXMx5 zdyn-F_6{MWV`87FFQ?Dkm)~dUE9$fMt?sk+RrERfYWqBW6vVj+El{NT1jeQyHYWBv aDmnrkeH}+S5+5jf!1F-g0}%dy-2NYQ`@WC> literal 77824 zcmeFa3w%`7wFf+t$t1(`3`#U0>YzbKqc$3C2ZHSknUFIuf$)-8QA0zp zVS=6UIF?#%ZLjU6UVHnvwqmOZQhV#=8V8*6xU z#8Z>E8of_VURbxh$=1+Ve?#Nan`|{pSFWu0+rC$8YYeQkEnjJK&s|`0 zy|}_t%c0wI6T;&c|3#+o(~Dl{MC2 z_&rj>BK4WyA++*y&`1G2XBiARoRka=^p=o_UzVX75m87FhQ>uo&$|Xg)#V0*{T!oV zGZjYBL)4JdXjn6v60~1~(Xa{W4g2v=Pa7sYg!lKPrpHh>;62gr5`XO)KVGiX`$>J* z`k|Mx0jf(Hmo4=#H5eNI38^vsTY-On#J`lE6Hs3wvKa<)@uCO-Q`-}%L&={LHC)ml zGIAf$R|C*)m^37x^O75U%a=773>Q)HO0B*NhsoF2)L4TojJs+r-$ldat6fo#jD$-= zgO=}-A^B!dbN_$%$)R`bk6X}F^^ZR`806@f;>Qp~+yzB)#3Dz`kDhNd$e|tf?R&&8 znSZ^=zo0cO|DBonqvoZLQVyf2L5`Z|iMXt^BMEVrh)bLBx|kh*^`;-Tnq?` zb4EB1dNrs$1^HJ2_f9*nbv4Y5g;U%6UhL!v9W%Wo5gpP)iD00y>JWPv9eJ zzVuIADAAwEBChq9dzt9Yo-YS~s}4VpOeMjX0)KS;vy{&85Bw+<{(pNU6@D(<&mBA= z{KLQ_%gRx8$4J!cRm$ZGrMp5wTMNvH2ChN5q`eXG=Q&>3 zEr*U;nh@{ec~TPtgcdr*Fk&(Z`mOafb8cB{Jjbb>d!zz&SrsRmiiK1U=ukmL|aA50cW zGT~JujYX2wT3Qt@uR?Hjxcq8aDXj+N)w0q>z*nXbAH%n#0NqHKnI$X7 z7_fs38^Oi!0k$*ph;r%yT9aKa`Pe@}R`#mr0o!h=m1e#2EG0Y(aFGkpHaQZxXiU;_ zJuGse15I)w*9%fcu7ljE@+w(bq0OLhDY{pFb+{DWL)Rkcq99NQx@SwwEyBNZ0rkkM z7>NRlKt`D5phxv`pjcK$QT}WC;y*MPC^LR194}x85FC{woHa->6awZku@d#xwAOGFS5Eyj;uy+o>oIx070|b zsDW=(Wey#~>s)k|99>cHh}`^6nC7(N%9oW79atjx@p3ujv8=xAsE=#*Gc z{o7px@XTtr@)oC;%tU+3sJ+Pj1wjVnX)jP#=SADqKA%rIy9KG#ByzTnHij#1pw>mZ zXivH$2aBk*(SX0mwOqIMh2JDtbX4Sd%bNi&j&jH!4q5AHfS*xpp;X$|S&2 zE!R9B?+Ry+q-UwM?1p4~racp!)4wVlb~P&3W&CrK<4@d2 zxi)v0{th9(uhH%)>Fr91cBhJVCB46{_>L4(;~D2t_Q)mO(uTdCksN{<q6#nmRMHHu1RM_ar?%7~Uno*}uKg8ncpdab znlS0hFtIb5Jn2Xe)1qCSGE9qNcF)#Zl-lETL-ZJoY@Q`}EBIW# z+cCpN9Bw{yI0y-+P`Y20OAh*T+|x>JO~U{ns|(K@+GQDCwyC$`jad34P4+Fu&a$f^ za4adPrscGb))d!u*I$+_|SE(0|V z5h=RB=q>CZNumnQ41>_h|j;uZexsXK|j{TBi5E5w=fREk;yT>Rn7EZwD zH6);eZioaJcPGg}>fA}`NZ?dPLI7{5*G^fPZC6jnd|`07R3BDa63i<*%LQsuS6Zhw zg`A`^6zM8M1I@5Cm`%Li@?!f4rb}7z5tnjAEWY;vCoW~L7qh@?Y6q#If3gLAbUSXI z5IEZ=BS@#fY4t_|MR<0kR#zaMjrUxiLv2ddw<)7O z$VgltLaL9VRG$;i@(Jpb)pL{eIWy{mY{m5Urr+T|s2T{+dOjN=A8@dq5B zD-9M3n4dQ&^YXpQ2Zi&jTTjCZ(dnu(1V-y%HMp*WutPKe8m*?eSVaP0B?*AC7irG2 z;&(|bbGVd`y*00G+%MgA6&itv<~A5Skk7!CvUBhtyTdI7LC~?R3=;9W9m^*WgL0*i z>`{ndluit4kQh|Ct!b_t73I7LSt^Z)&=Z{_tG~~uN!q2!WA_wnLId=I=jl^;iRSfY zpAc^$4{FRI0YZipsDseUJaXa}g5XeBPfX<#_Y}}v1qebc{5f8xfN;Nf%d%>@9RoId zl1DiW14O8_b1z)+y9rAhV;Jdpr>Ep2>CVT%DO{a1tBhV!T4=!rC1VhX&r}h?G3nLO z+DCvJ@kaCSwfeZReQp_SD#W<-`LW()6W`m8j!~&zBpNpA$Ei5eM zyqtsZd3oz4+Q;nHG>Az|-(O0es3TrmL}QDt&b6!MOtQKP0X>pZL9Y|loA8FfFOu4> znIyG673woeEw2FI{6M4~I-2FrEspi|(;!6aK?YATzgDwMgudPA)RDpuWW^AjW0Gt3 z;kDE{DT}kTziv@q$}-?hmUx3)QtNc_a@42oZ&}s9((9{$+NZoV9b5=`u(nJxpzx?y z)L-DeT(g%8W*bLs@4rEgt_BQy1q|!)T53ChIKVhwc#ObUY}BjL>roeTEl($FnM@0( zsG@|cpl&=@2#GnDt$A<@X7<&;GaI%V#H3Y>PEVA-)a6ML|^JsnK^#g0r zhrA%YEGxM(^LqryP7$lzRc-;kd1#zzMmM4jtbKkGlGhd3n4Q{S z9`GvrJ&My(5v{U-vwDZZY zMYk!hzn5M>XZJ{Dphls%o&hXoO#{nBzld4(XOs9Xv{qOVuzHug;$H&3!L7{!x$?^Z zERyY-dK+-0>d$(r|D%3eg1ArRr3t(OZ#~?w|6PidbOj#tl;j5_Psw0lqz9InwcsNC z%c;?2gkQoTM2J8c3`JH30ZYE#p};qQay=s2E46SYv{z*%-h{VKPNMdDi6n}sl{}yy zZ3H&c*+HsF%dFr* zUz=Vg{@3Vb;{O(UnGFHszn@;-H2)*%1;RlEP1ND(Wuite(Eo;`m+uZwFB8?~OnRAg z0(!|8Tm>dxuoCFXQp-rzrB8u$XYrKu1mH$6%4ATb=}Jlo7ClS}j{<;UEr(gGaF@5R z+f%Z0^#!C)Dc$kB13x8pR*F|9k159!nQ8IRtV))yfaK;aj1gONcuKlgFCZ?5^|sp+ zy?mTk=|n~GyeQXl4O)KAqpU||FVoaeo{r}=@f#`;%`Tyd>KLXCXnlT^?NOhl6+u}5 z81~AAr>g&kwX7xPpA6AeR<1$nx8*`~Uer8+YDT40pQtz;a52%ezX|yVypLq{Yl$xn zwdm)e&OMN61~rSmnd61sx<&uvpU`{FqOWp9=~hp_)nFilz6mB{3;w~{PEvd-0Ll3- z2C+Eig=dIt^dInuMO;={`7RJQkrHVPk>YQXn?Gfb!?_TI&W8nMH5>{1?gb3$PuEcI z<@4pxtA~(xuzwT;I<=WnVT_K9l_O*Y9V?r53(+bv$4Vmu8BLNvVk%7Qj2|yt5;jsw^EH0~(1SV;dP@v}$=;Igz$A72An8ITtb%02 zj!0AwNxG<_qNH7F`94->T7Q_Adz4sUfk&yd3dvMfMzYOUV*L?9g)s7dBuBu#`!Dq9 z65Sbi?Is-?tuMIwxcFa^B|xV^W;T_6X3AOKRjybXuGF* zkOy=6kq&kr{q`OvHZ1ie9ppZ`kK=_sa_AVlkHQ=e9b@;=T9LU&R(7FYd*8pVP7VeL zjq3L*^I(75Nj4vk(jjAlhX##Ji-_XU1w`YZW2B6QJM|?Ddpz$hI1%@FAz$JDct=@r zjLPj(X>yx78wS?VCP@1cxa634Qm`x9hcXV* zA;YANhhO+!E0mtVQpjLJ3c1j$06rG00;i|=50c6LkEj}F|HUM?3CV@&!O8SM15Gt( z!ih=|%I*=g<;Mas%i0fBZU(pKH)BBh$5cT2swnA@HvSgm=^`TZDDy3WY)@n!dS>!Y zt+WJkyb;;bKh`_-lz`bA8QGuhjm*MunkuGR14UfMZ^q#FPxdHA3<^V*m*W5E)}_Ud zJQ2v6C|7BfHq!P9Q5cSvU7kp#wGUhi&AY%3L?z>dJdE-JNB$2z5!u?`Nd72~lI4jQ zDoSQp17?rX(|?WzJm6*E0Vs9V1KF5DFAL0x{x~iDry$wlMHkQ~1NDhBT2R0O0d__{ z{>b^RuoM4gKh-<|UZlTsJE$t(NNy|_#uxy%?B--Gw(+RQ)afK}jQ|GNhUyT(sA)t< zm7`XmSKv#go^E^qPM652o5r%= zgkdFeAz~ps(U^u^`G6Qh;Ia}DDEZ3_!)V4zWL#e_14LbbRg7UD*SCYx#E|rDO#&QP ztha(~6;^?32{pF7<_* z3H^{8AOqzRizXR@78J3PM4%gX(n^wQz0mj_>zmqA$!qV%{ekS_7yG{@H^)n_W zO7gW16`fw7`hg)`blS!7r0BGb{B+M@${(UaT-V4e(s{$BBqpN_O8wc zCGS;l=9f^qpb!u(Uq_nP*MM)L`mO&t_=G+RyOY|8M#*kOJj!6G0LMa?M@g;YT;Xw^ zE|;)3f>6@+Nw#-Zra2Gmi0w3ZSOxRK^^0Ms27`mBev8Eru*phGL6D*lSM6S9glmgY z{Rww?d*AO^i5XW>k`=fF5}6b3L8BD9iI@A7QrPB1rK+`3O?VHfHgE~ayi#k93mzOP z^sUTNP%G4nwIZ~m77a{wIo8-#EhVN?P5S_<)pwxj%ZkP6xW(2~=2ehHBC4z$@F=^9 zqoqObw^E%4v#H4TzIV_m4YE!x=^&D*2`NPKFJ5v>tP}(mCB(3^y~HGioG?21ObP(n z@4pBcg#s|qw+X^1BBi2a7r8Y6{WO;LP6Rk$A=u9pfc6&?KCN2hywpzG zyfA@~=K}~(e+lOYup>vH3*g{qNj;pmY#0W z>P(?0pO&Q26QKE@rl*Ntj-LK1=9i$SEn4Kn^z>~qqkjo{f+nx-C!UeuPb5+0NLG_H zj>M@X73uc17u3VZ?~OVW^cVA+l~FEeAgS3QC_*pTM>E?Gnr8I~Mheij5P9IG&?FhR z@F!--GZ1(>kXduVolf>9qdYYWo&%DFG*3l8Hk`6F1fhoukl?8Oba)R6A<|O|prOh` zj>PhOsvN=E9JA0fDIgwAlth#yOPH0?JA*ot_1VyW_2{yHP<<|_^84h+7cSx-3;-{X zWinp|hpbZn1yIA5V{ai_PDeA@av)_?$?=#cGQ(04nN9jT+07(xq>7&-`AF$Mrwm3_ zYei%NzqSNU^G5Rf$5lkGhT4Su;B-*bs}P|Iuo)pAs_&{ByvMvg?TqNO=`7Zd^vz6F6}0~hhURf(1FBGVVXfoocn%~0Y(?pw z2Ir@AcZ`S;gbnLZLSuQ&qZ~xC)Pl{#5HUsuE+Cn)fkhY8LhE9sdJrBY6q6&lo#hq` zd{^JEkXsnL;PANG+P@H{GH%hvQm1Bp`L?ikK@8RPqy9n&8)B)SpzQ~i;oO80MVW*f z@;x?POYU9(Z*pL}+__1R1U#Nhc>2fFG;L4^mx2Z&X9G$Q6|C+wMMFEB!|W#q*Aw%d z#Ap0+)93rcR8e${BS`aoKTO^KH{S(CrgE77o9|>B{NFj>C;oqSzEAuL^WAdYmzeJf zRXK59OoqoqEf|eGD8rp^dhv~T98wN;qyFw%k;MUBBIO8_L*1%naj3UzS?uXq?CQN* z7Q0$QSy0~>oo~v8UlVx}CcRH?p?K1y_ZG)Blimv)fj4vn)l7D;a;#O@ygU5)CNdZd z#X%)8Jld@>?D?g(*9Zq`=a<~?iX`k3)6XwmswH6~(Oj7f6S6wzoj4r>pz}*GwN?Y9 zYN@TX&KD`K(>QV^ICAP94faQp2^8>usq;(M9Kvdpd49?FVmuC`g_~TRe10kKJE?SBmbjzNooKb?KMv z$0xwQFkODh^GL0415g+MGtVRaGLen}AVZ^meo3S|!{R&=&LsiBr`2zaU^?Ta5fnhi z)AZ4Re7(rESU-?-AC`G95sAkFv0rS7&AuI5VsoUH+o4N)uw~p+QjU{DYdAI+1Ac$O zCX|vRkMhP*+GE*3s*G8!`7V6-ICb?z0ajJGGFDeBFGEjWU8mRLzf{@l+vHIeTV>Ne z52#G-`5Ttz?NXb?7iu^AT*kQ~Z(+Gr*^Rx>jR&x4ZEl@94mEo~X>R2`sw)zx7eIBA zf{snIYdq20uyNLp9ksNd`v{3834b0+z@#!BVoh#1{lt>K-!NsfEX1tz^Gdd+%jvul z??@_JjV;-$RRz>S1~r&3Y&foT8^6Og{y#GnQ4`nRCWqGA4N}V)01)k0yTaokN73fT zbOOZA7{Rxo{_xDG{1GMu{def%i zn*PfDb*LYwk8(WG=p@l7&`In>zy4c?M6)DoH&d%yP)(^0O)R*_P> zEB+*5Al^k=(Ou!}u^t>`h_!MngAaK^&}A2{u$ z)_9n+89Z!EU=+42!?5SN9w)B=EZD$8oFmZAKYEnwu|*%#cpWy~7q-XqOpRb`Lk?M8 zXJpjolW`SCG|7cVC#|SDQdZU^PFk(ONh`1=oU{VItm#>GjilsrG; zJUDy<{>dk;)`X3oI9M(wG*_-Z+>2UhJ*K97ks|e%NWd;;U&O9{x)AU(2-pithim3P zM{8u;$8=yczhdJNsRdh8peQ}WsMODQ5}gP{kWQxCeTJNJA$2!#YEwJSvxYWpvhLWx z4K}N(ghCrjbxQdS-mu>W)bR}*ov??qB{|;ZDLF3PxfVR12Hm;E=;|!50%N|vAjp7X zBogD5SYTOhSWR@ks?by8$B8F~g@ln7&ev)9umEkELHZ zQAORV&LlZ?ogg_njRW~GUuM}zMy&W<#NMD4`M6Vhmh){ zDAflE6%r*2kLOW|NPV@i>4583W2Dj#K4#jR)1=lpYcVoe{%>Px!l;y5{g(&VR`JQN zwK(|&%Ol0m>-=Bk0C({fC!cM54e35?m zQ}BWe{cz#Stob>@B;J%x4VO;^uANW-osdGnK(MN`mCiyqD_s%%>iQo|k|FxvQyKbS z?JKOafw+@88vrYx8ZHH37d26n3S`@MrK>pw~<8M zPL#PwdEQNCQh4;E^T7vaJL6q2x@H@~?va=Zm??#&R^;%O#2OEZZOiGlXo8Q|FR}h& z6GDoj_#*br-a0a1VId2fs&F#^uUP0mufe=r5yVbjvmUGibZO!hc5omgEnT!qp=GLL zWVgMp}Uo(~h${_&EDaKF&VJs#fxnb(MacoiDD?jnPb8m~4glCWb1E|lZQIxh<&oX1c*q*a6hs1+j)$Zy z@~ayJ3bbR{erKjEvWYUVEF$C$ySjc4!DCT#7*IX6cNfVU0E^%w%%#X1yemF^F$2G) z^WGQ=ST$JsNJz@35zx@~Nj}H4(N?rAh!wvm*0bWBCtAY?2Ny1H3kYdtgWqvE`t zorM}sx}J5F7XdKjo9h&lV8DY|SGiN9YWuLTs!&IH`M?b0`Bj9y?`gz)7WPDAy|^kd zSG>WsQ^k7W)Ygj{_Cn0Y+M!JptQ)i7gTeYyiWT5gA8r4@OUz0)&Z))kwv$wVX0O?< zuOoPbd_kH@r^^Aj(PZ z#nD__)0K2%Lp90zb<{N+T%QAbC-_@ZDO?COfaFVfv(>-g4V&iB5Fgg2;}WHG5O)qZ zpE!uS4w%xg6a>6DHEV@BAeVeD-RXro&^gnA9lq$En0jF8KrlK_5**PtFhi_}f5Y?3 zIZf%f#0pMpemwJt?nhxt>sdY#~$aaPngbSpFuKA4in2%0GS9NYHBY)zwuqK>G!nmAV# zUtB>3Rv4X#0C0tc5E6O4z=aJ&HlY5i^DF4?kn~%p;(14w0M0aNeKgDY4%hY9UrTFi z8O!Mq5U_iasG&%c*eh6KuS-bmb?FyS{gNiJGBdfi6Ra(e7rV^M+sYdZs#(Z>mWsspi{s9)oc!IZz8lD%04DctgmoCg;{#yRRew z68aIwQ8`X>7f=EESxC5N;^BQlLur0Eduk>OmuA4Qh9F}Y7Hcr9nE~SX4$+BjQkB}u zm^=a?52Ax2(poSkon;QvTD0*>tVZIz%gOGK8id0w#b_$EJdEz9Dk~W9O2}97yq75_ zX)KuggatVj3mA@J?oS#H6S8(403Ft$Nq;`LVd`jbDr2I8O=wGy4=7OIzY@)}m_nu6 z|4JhT&^pV}c?{W5@2Ajb7myD$^bYDc0r`J&bqWHm&DT5$PPibL_LBonmf?Q715U-z5{mfd*sKQkXD zXTXr059JyRUvfV1_#`KV7)NbR;C@a)3+dN~DUklLr1E-tHr7B)etv!cGXeX*llI-@ z{bArqw5hL`Dd5EShb8I%1owy8Rr}LGK6ESAnTR4l;!wjX?CKo6(KtN_VPG2cZZHEd zaxp-;w0aAXbqVdx2`;<7$y;6feO zl*=NLR#*j3v@a{>eNb@{3M8&jHQQ>F3Ahw`GBGhaXU+FjE9T#2=Kp9}T7K6xDfw}W z*gm|zbp#r!LqQxpRLnOdYtZ!7sQDUNQh@?$$YaIT2XX({c;2tci`P|Z1^b57YCeq^ z5B7m1Ra7JzInk)!lpQr&sVb_6HnGy-jv4s~f#4Y+8JA6&VUM`%l6A&K(m2;el6BT} zX`E*|;$FnPh%Z5W3F0ddUxD~K#Mdbs?!-Vwn(42sY}iCWq?rR{1B)n;W+AC;*eu?0 zka7Jr-{ zl1z_%uWyqN6X&M3f%M9XcM?);e3``oSRCVdf1%d|6CVT9o7~&7eq0)AgDc(Un zFG43L(In_{iHQ<1dZXrBky0G%a@h^9Qtg;of?5Tc67fZvH=|)tVzd(X58<4h`fZ+O zvoG3)DT~7u04<((m>iwt8t|f_;yvnjFGn1#Oh6?oMrEE|j#n3H^u+g7v(%ZK#jjKn zaM~ZC5&u1c#mt^1OP}1pz#E5IX~u3f>}{{vQN7k*{<(fh`mNsUU4O^@~0@>X91xMprW&t#rrWDl~4~skuWCnr~|z? zNQEd&bPEe?+wd|L&wCcWE10RGVJ?&1eL z8=x{U%?eLW>SUzxO`*So0;MAumy#HUn-WwM?CLg)F+VfeXjY4HdL#)X7nEeCS5mxdaqcAdJjuWTB-Nw)!tRpP!Qw2 zB2mROu42Ci+*Mq~oP3nuN7$Rr<;Q8*Bdpsy8ND?2Iy2V#kJS};UyLi<1+LA%c>-_} zZ)zzBqJ5f~FcBZb%!Hg6oqZAI$E@0k*=DB8sd5PdQproI2w%OR?6s@ zCm;x@-#LcMAxT$i49|bUtTHZ$jrXs{aQc{)K)+x=wcs$f?gch<4 z6R*yPVvQDqGwd($$MbH|if!e3W?PGKJ+Mnldr(W;MpqoT72H1c3EWK7$Q}9{2@mnS z9!~bJrsk+!Tu>SV-xR4!^;8+-Cz5bUp2!IEF(DHWRnnS+NEOaoh)fq?!jc z@_NP$Y(7?mn~rXq<##q8qkCcfMa{=%euU80e5{;8Yx6M~VStwN>oEwBw#`4#!ry3N zmljGCHXoxqUHz9gA3L4Gg63oS6pqK;JQkGQr{yigI!ATQ*1{Ss{4s@z>6tdaj)K2O z$NU@>s8{gyOu1P3arajxL_FffJ$RGC^2Z_1o+BMbZkFh0JAEF7V0d0cvN>{CL@XRJ zFXC)gj@U%R#*t!*5WEPFbT|XJCdh22qDffkDU}}_m0AhlKJ-X!f$WYwwo;ehlkzb&5RbXDvf(wt+jZ~D zH65-aJs=ZzI2)`tH(p79;Y}g2k%*^~tb#?(X#@TVbaHAdQSA^s5o(14$eGHmweco2 zia{b{ht0LnC3axi$}WpLFN5^>2F4BdusK_CZPQrXIR|Wa5yk-qg6G|ZG1+v$6`v?zy0fBl8HiJ~{DkHbZ^&*zG_&x&SG#GXssi`3R09zD@j(y{Ih z*M)<9OCSLT*Jgdbda~3y+Y~%{Y;}HcZT4-ePmx;NL$T}<)qiXB=Ip*JkPStjA;8W_ zAOBsxcn6e|3C1vuK?ec$wlmlj?=zwdUlF)BURgIC_b&}Vt8gB9r7Y~ToDnk$ZMt6IoaEYrw5PTEx9{_>$8sgzZX1eraK99gGb?ad^&*phpx&2 zB69l8+i(Wm5U;Fea1;6_28^^6<#|wTywag`qvi>4RAo74W(8i8m4%Rc!P#?=lpW4e z+WWJ`@k4gYCS2AKaI`B^g*6k$*aC3TYq;<|Ao&4=URik?87lBN&lMaz-k8gK2m05eza)QqX)}|J)EYPX zP7=UOk_O7N;JkLaxohami~iZJ=scW4g}y_Z7@VXUfhco{`ltrdEPSL3;H*u2Qy5@~ zvg7Hl9e{!&zV=rwzER!2$S4<`#l;zFT9Iw%qd%b?b*U;HLzuFL2z|s{`{zX0!FSO0 zBI^33q>(5_+O}{Rb)$&DzuauV`{JyGCW+2alMZU~59e`{Nv#C+R{^!=Wc@H1388_t zlS@&z15Hgucx75!JYyu_*P|QF6Q=&(9?vagpG#M02 zNS=b`&gU`97yCWX0XtRq&J^wdRDS?N#9t}3!O%-6IENKf5}~RHm~*qU=rWcm;Uxv< zVFoAzbosbf$&D_^!GO6y*~DEc$w!D1gduJ~Ni@I{O`BgjKgZ4iwuM9U{{T$&=;OyQ z+!*6QkXk(N{89j?^rrH^3fj^ESf9mwamD957!0q|u{MkBGbEVO(SPvP?69Rc=5v*F zHC;mK)hOjH1S@ZQK8;_XEw8~GhScJO8uGR=@E$uBo}57~gIS91@ES%li8*Deh)4Z_ ze7>Tv?8;=lr z=4OY-0zD;9Hk}RLgDw4X;Q?O%Fuf+4!zMX;4bTCj*ZUaTcwVauqe7_A$iDSll6`?5 z2)_7tBhFg9F4mBgPlbr_X8qde+C~C6Os1ID@yazxo}}AnF+yNAu&%n;JVZLYooog| zn+H0aSd{J#q7w81VjfsVn7+)+4MT=nSixs}mdt($Ho2Gqh?2U5C|Y>O3~X<`zX!DPxPn9rNs2!)A%J?n}->( zfQQN*t>UJzAq}L@#-xwB#$j@w{)KDVE-d1F|GX zLY&5xAirTEFh9Z)55N~`yp_07;GrZplG>ioc+gQV4o=WIpX}6Y%KLDEqFeudB`%Nz zt_{(-_`t(JV)44d6}}F456v+_kjgf>!mG?a@Yq6GX({+EY67@8Se)!17Igy_6C-*^ z3>H0n*CV6_d~C0ic8A!QaY0c4BiT#6^q^&759K9x7DP^Bpqo%T`U>wEWYue3ON6Tj z^n!iYgnTkcfL^M_#K)ZVg4t-(J-(?|lunU^1lJ&Xqw)<2et|j~h(3~}){stWheTCk z5^?+3X`R|Wvx;`rf|_8R_+mJ?ecGw*`inNdsePX)ee;)xL+616j~mPkXrLL5f$eaI zDcb(Fl^(uFRpXN~Z|l%eVhtnjOXG{`2fV5EH&FdlHC5M$E@XnvP14IIjfH6=gQ=U2 zPjF{TQr|n-{L6{wWtE(8{$>Az=ikHAzV7_{7;{4twH;q#{-IliXzQf&FZ;h^{_UKa zHve{=@rCp61mlGdp1>y~PDs+JGw{pTz%Su|nUCth6>y>uW;|E0BOBbM)0uVL9j+vv z846dKF>E>5EQLAPWaDLvtT}~HF`Wj%FJT-?^2=OE?c^3BM#7vkg_nHp5F=J4I40yc zKg^a88#Ikq*prg)LHzZJ9-uIMICb7(w2RLfdn3BHaYT!f3n8 zbkJ9_w^0St#D`csWKgLFpN!|7%RM6r6-O*cjZbRzsS85O{#(c*H)RGaX;N#4v~3_a zG?=@3ksQrix(Wt?`;txRKUD#&7#pVcmEmz>81R& zPnfZ@3k(Kx5F$>t6dY+lXgMQz7KNk78^%$(wK(`qijSXem`d?{yWwIAC!HTWhth2| zK_7($D-6pi-M+@~eF`sH9c-lZqDsReieG+x@VgXu%nr_>aJn1!5FvDK4|Y=Ay~nVV z;&QLyZxni;5ALV*$^pa26kiw*9;0|wfABpDm%L$kmC~y>8-7jUvWJ7er}VnN1pkA= z6^|Moq4b6y2Y*6w|NVxaQG89<5T$V44}u#EU1h;g^X;+l@O{Q#Ah`3V z&37Yl(-z}nh~4v_&D#*W@86sMh~WMQjlV+T=0nCe5j^;Q^V>-L?WfJh5j^yf@dG4o zInewZVvoLLJc!uVZsSu3p6F`sKw`{kEJJL^+~!$`bzjqb9fCazjq{M$)6~2Qv1is9 zZ$YfL&Uh1omu_hO9ug0o+k75^H!d<>fJD_{yb{4X-)g=Li33(+9%3Jz-8>Po!BNd) z5qy?yG$PSp3gwu(%CbkBMufV`EcvE05sW@PbP5u!MW!nd8~>fqG{o`?Lzf_!RA8En zL|e6~7C}LM=%0{iUmIGF;3B{2W+WCZ2wjEPnd|U9omH?`Nh!72)xgj_90*8hoK{gE&R-M6tODR^e%!WZ-rh%V)eg<{tdyhhfKdi zV%=8LUlFWm3;hX+4Vz5&BIf^>(9aQDqlE54u&%|_9O~K_#BvV+)>sxZ#eh zu8kzD|MP}l;)#rF_hkJDZ%NMi^M+QWkzM$StjCddAD(`j^#?rNkEh>kcmQuV7WIc;Cn0pMbYjxM3xp zUc%F|tfhE+2v4@GDR_DVPv6*ZA>OKZD%tRDJiUXb%d;-U+W|bCy5TgWeT1h;Srd>p zh$l=XHPYIBJKKgR6#i@n-e@Uq ze3o01YuG%Wci>WV35(E+>v3fo)>nLmG~Nk`c(g5?J(a%AwtZbctmxr-vrIy1IgCAb za_0$!e>|1!0QVOVnuHJRMkp+=r+g?;!{@pJ?9rZqk0|VyTECm)Vnoo%ie9&}J6d{N zuE8p}-i7a0z)T-pmzDc@;H(+Jbymygfzv3C9*?CEUCwdEccQbTJ7?v(1ZHAD0X}85 zZU?P|)@Z4j_NiJuH3w#dvrlnFOO0|(H_TL&%BTJ;NFPU*L-fcMo{>`)o@Lg|2n4Ti zHHh!K1aGzA-dPxa55vLgKW!LC5Dc&62_nS~7ULpy8#XHdx|wGDS)b!;e+%0EAd`bH z)RpTi8C*4rOwjBv>c7?4i4usPH67ZLdUU126lcv*UpFGXB8Z zUXrjmrsS}nCC9DcsQz;};R!zrs`iVj$;Hy2Mb;(&M4BQ@7@FHE`DHD!0w?HQbUIaU zv=tx0N6w@+d;;h&DZc+X3e@YuCRZ3j683B1Z;{%zLsWVn?iL6s>}`3Tye&RcFXrtl z(gri893-0q_}A%*&iWi)jkRKbD2l<~;)n|$^h zJnJiiY0phDRI^uezZ8Nc!2Obd2d`88FAl`vf0@Sq7oV%Jw{JGQBu>X_Q($KBw(QSV z!zfXn^EgdbOy+X4)Yil164$66U&+4J=LB!dT@;w4bi>~48r2p8$i6A1H1^Uq9$e+Kgh{+Zaiw|y?t-}?3;H;i{Ay$SzJ3<hYe)m$UPjadQYqe#ol~$EsDC&D594f{ z&jZ~YM~||n;SsvmAq#}bX+HO;_Q%N`f>DV{Wgqn4sq;JRhZx4+F$l63{thzUOB**5 z`)XaB8=bNKx9_tZS#oy+jmQ0U!DD8B4d^gR}d(^C_cZe&pv`k2V^{5WB_yz2d_ohv_R+N8tvg9!>^9e1@J}P`uw6CU5E1 zZe*ubsz}X;Errc5Sd4&kKwWU$WB~7iS^=Mye}o&p!oG1VhUaW+_yx6#VX02eFE2hJ zfh7v+U6-hsX1lT%QQ6cZ<~*ooFGiV(JOH<_&*Iw{4~*POG~V|ZIDt3vP(dB~1g~>&-RL4_6r(R?H|^-l zKKGA=Q(8ErU-qFN-@!8&!=AzqHXd1jA=pKaULR81$v-FV6JgP6%-g#H62)7j^-@Zn57#5<5$qa z-b)#A{#U=9=W;rRQfdix9tOzIpkKJYi`Hw6-;Dlt*gYD<(oxdM{O0q(CB?D+siDr# zwd^-ARq!e=X-!_1(xg`rC&9F?c_O7d zshz21;nF=7(b8^e9f=3^#<{g@<_{1yX7^M?XZKb_7Hmyz`Fj~H3#P#SJtunn=bt2c zT%`H;c(z08M9UYT#fvjo7w;w=Eo#LjwY1V#lXI^Dt2KG@?3$Gkwp(Uu1?=y`V$lZ! z9B#8Cpr_;#(C5RT?L`|)3NB3d{9&m|c>bzMc;QR%z-egMel&tniKbKd+Yosp!~e%( zbHe{e4&5*5|I5zs|5?6*|8K-l{~w9`WMUVcg55}*V&k_F-aSa~-yOGKccD zziWXHkP@cC{6)UN&By@8g#+Dgc;GMB2Dt=mpQ(@s^jld}Vp_Uy@Cw~GXwiLx=O%oE z3Hb_|!Nd_m{DVJ%lB4+tdB*+(iVpb)D^Knp1pdB)y?1mx?-aBJ$p%IhnBQE%m>JF% zvo~5sRzr&i0IpU`FUZm~+UWE_^UOLjIImEn#og$b@&|3;iz- z7Z6o|626lEg{a}0>VonvE3$+RU7bX?vGVs2b z;iQ2=)(7=v6?Yh385o1-P~{dQ^on6EsZGf@3k7*De4|D(q9m2KS2DzsPz*$9^Gr^r|%D+4h4n=2?OjPDx2 zDdlVL$K0*Vfg|8JChvxD)d**}Ze&=-hundJ9pn$d%!lkM7ec0k{KNBiw3xrbzMhMZ z*+MB6LaovZVH}5yu?g$RQBvEp0BVo)@IGi8V#f+B=?87YQ32c3b!CfPtBiw;{wMrX zki3TTcc9nbL-iPygueseakstEMY+^v^qhJPvK~pCi+V0FkPBA`dfzZgbA@0w!&1x+ zWMW<|paW9Jh<|DQ7yjcf@`t<&1%UO)ujdbe^ep@#Sfh@)l$SxaBjb5NR9Xgi2=0YZ zR57AgnW$?ieYqQ>cf1Mww}-TY!sn9klm8p?Gx>A+HU9`mHsSx~0h|xQdY)^TPJ^DJ z?*pQaP}fMGE7W0jVLt*eJ^E7YT{K}v6uF?byGM1qOh+*#o@<2r1f&PQIyq4=3vhn; ztgkTi!;Qbbe~Huxc+=^_@Z>4_1ne1zxdGL?qvfXJ{frn|rpkdBRYQyuWS;wDU&-@L z6Uk>(xSQ+;t){Sh0`NimZ{A~k|bb|>D_-m7P^Ch+w)JMbM;8@??G>8R35N-f<)gwt9AM~6F|-6(g=BRxDQ zn{Z9_8n6SHGI!Gi!?*YQc2Qb~yMh)dC?vp|;yQk!3|3ptA?z&hq9c6H)MIlK`QC zFo8iMUBD?01Ul)+N}e(i#g#t~qSj*U5=S`(I=>W8=d z^)4tG;PaH&z?(*Cj$mU~JZ~h5#k)fBtaXo|L7WH{G=lF$Lgk){Eq;DG{W&dk48ydQ z`ipG#?P>?)8qo8P5nv7FG<+$S!ah2NQUL?lz3m*m2!*IIR+HFnW)sF@VJ<7)seUtu zzIPtTEsph(%R|MbcZNH9Nh@@=8ADgj*@Q&@$j3o@`0gdtq%N}qNd$}fDY9al`3>rS zkmeR0V}kOlPQy5;XOcb@9djN6^#V#L;)J}Tgs143w-Kn1I6q{nc^2W#%{}om7+4<9Wh^q z6g7(4op%fZQ;yJ;=M$JZnr@&T{~W!FoN1+;|A|NE9Z##b0X$f`?%1pTi~*JI-7eO) zqJ+(x=C7>4pIpWK2<%A4*Mc;TVOojm8bzX$>&#;yc@`FH~C* zQF@`L!AK^xVA>E0c+a-_uXHw1d*xr1NcIA$A~_T{1`5G9&&Rvs{Xm&ogm;NZ4az4X zb5QffxZfO#n*#X4wbq0)wF!K1M@ycZ0IENy_(jlTk?1(>u5{`y7!CJ{{kC8wHd#3{ zZvrWagXGn~w_slknBgR$FDK)kQV<4=$>dacDh?MB8(N`mreHHMp5kU?ss{%{Kfr_v znEBg~R31fP1x%P}!2z%DTb;%;!7OnY75o9LQjWlCw!lJ@7~hb>myGZMSam+n0Q2wo zy(!5@Np{Au^Qie>_zgb16g9W-BUld((I?g|QUBBv)qj}hkNM^k)_+5?e(#CvKM2k| zEc|y<{R!?58jPC%zih?a4gjqr=(Kem21tYYnuK~fB@i(|o4=0?#Z6w~GLtHqT_jKa@ri(><_^vIYN#b5}$ z$45Br+i`c?C*bpd3*RRZWpmX#Fg^PxsIw6VSNRW-oPAlWKUZx-ginFmu~fce2LpA1 z7vj57_X<9&*Yy|V16!p+r>K7vkzDoHc<6s8rM&uMq^Nh{kCsT~1;0+42Oi}pO@7dB zpZWymBqr(Up-+vFaDeDffl8j2G!Jled|^Qq8}5gh5Pkh9ti#yE75PD)W7g0jNb5%* z($p-#gBHx{TZmDz-q$y^c;8ES5VR|`nr}qmjXQZ0v*g|$HeZ9dIunbN`WUilSQxMV zRzyYsXTQK>|J!%y(uUUOMY8e^km^(phK?GgAN(6ePkkCgf$=QF#6KT!_C%026{V3z zxV;r=&rsSFPLuA5_1_>Xd6#Yg&j@wLm5#@qs3mmhJB8g_jGhDC-r^2#r0fv>sgjjL z9FetF3`pb50aP>e-MBF~Azjb2oS(;yxfvnRHSK71Uc3Eq^wpp?fE@v~L`(TzrG0C~ zccJ}GHUD}Zj!fPn*O+_p0E)hsgVEOJsg-3Q#Ot??LOI`5SAJljw-CpHT;t{FynMJQ z@Cc9n=%6<`8VB^p7kEnc`SX=oqrLbV-$-SK#nevM(L&6SN<3&hC2@W zvs?BD#$xeRQ3S!O2=sH%3I3J$pFzUNL0lzJoL7i~p;x~nAJ`>_j=`Nmy!xjoMIN;S z7_d=zuii=k?8L=cl6yB;Apk_vVjlj6rv4|rXT(0~#ka|c{CG~-H2Sc~p;~+`{x6q3 z@XEzME2L)4E^57Gd!SzC^Xtb*z^A)jB4yTi-W!Nv_w=Ro+#{Z&6*dvCqj(uaj|!{Y ze#j;lIrN7Q@;=OJFf`_i1B;(hZwF`!jBC?xQ2pfZ{#%I>Ew2u*q8c7TG84ixWq zZSBD;^)a%eAR(SdvbwDNLggIy_7V`vZa%tvJ-tCC({;%{dG~5UO)%1 zQ=Rl+Bjw>du6koPy#$}Hlq0;g2J{-`MAz2)s8v<~c$1NO7J;RR5|Cr6VcW0F1G_=E z5WE%|$YrP#(oSM;y%Qe=8IbPbFU`o*XgmBp)S5G%_eVT}myJB~;u*2Y=0h8)?)wXR zfF}5b2wUtB%8(P}=$SbeP!(6i?VwwHc)LV~umehdT8&~^1D6eL$2SaLZhSLCaG>=l zA#ZDo<(a!s3F_KDq%POV>gu3%4fR0`#1TJz0)%Q+%pKh5VXpqZ5Rat?+)8_wxdKr_ zQS%2it_rtX+2vODyP7|!UFl!$YCgPtWv$26Jh0MVyP|AVk6U@st(XtAz@*#!p)268 zD;srCIp7|3u=#L#?aDy$PTU(eYCqGg^gyI+z^&|bM=A!D?#Q(tMHYRA1Eqoaa%jw( z>o6j&P}2LI$M8z`7)-g5La2&uN!XUJG9=s#dZ z`q%AEqfp$4lI18_21Y-j`Bj57AT=K~NY#c$dYg^67vSyIT$G6{Is`!8C>dN=fGd{? zG=ivN5I{w)Ri$mOkKh`!Q0C(h8LYRxI=*RTm$?X#g4IH)xDZcRSNPQ#O$#W;q$V#a zGxo^sui4~Ln9z%?;2_q5oas4%%M|lxYe8|{mM(KY9zdUlBW0>BVtx}b|EZyFTbFr1 z9zjiph`9$(L=}8WcpcPN<_dfEFe*VG#j&a881g`5AeNl?#i#sfG;lfPe*W9Zf4B1A zTlw!Y{=16*-p7A;@!yB|?;rWE1xizV$}xU^hyT9Je|z|E2mk$u|BCzr{QLs{y@&t) z5=z{jJzI?10jJ={6^aWY^)8RHPetviT#WSNG6m|^3$D=XFd*-A9Wh{!^gjQoE_}nX zqNXzYlU}cBAGS1k&)w&#**;4d53H72>Gm(vY|9asN%G^^sml~PG~hL1aYiFMujw=4 z!$AqGq}YQ(@8Bz;;|shrzbcAfq>}*o-ol;=X~uzCuQF*0I4Qo|dEju<={{HUYleY} z=sz0cjgD`un;3K0zNC|C@RID|Pxg zloq%5*_L3dmp;D1@7oOcK(bP?23O`a;1W>Sk}9gzSU)u?m`Nh99Kj`XkqV%o4F6!} zslZ$Dkm99Wx7~M4;-BPJ`u<8Y;rtiW+HjjKw>f9pH~K>7I6_9q9zt|E}La z0j)>|!)ID(nIhs7weUPGbZDVl3+HR$N-bQkg?DPv<8g=>@emq zk^VIw)*KM^9C}cM1D6`P-c6T@P_K4C%V+y{k?%n*T(t7WmG!Gv+G^L-)He8+*RRwH z)IB5eW#<3h(q*=#D^}FkEESp6FUr^0xbzm=%G%Yo6}2mG@Yhk*t7>cf^^MaPe%t1+ zueYtJUwMOQ@TR2=-)O4!4|&n^tbn6ooCt%D{$EIR^>y(usNr*qMt@(op08StNBLEQ z!SQ_hcv^21aYI0ao3-$e7FMp((zVdJM#Q(=D#A@`McAN)!F5`?7V7Z5s%**v6 zJfww&porVFut5uBT6jnc@hwCyzgY`oT3EC}q;Ju}hLDI?w`lpb@Q@bTHj4BHE$q?4 zqT5CKfEMcTANqk-PgsO{`qt;PdbIiBJOMs~5s^>F=ax-ceLvE|A8Ym8qlFqii|!Ti zfuD-7@;(v9w9xr85x4$agom{7AB9ib{i5ChEv(k?w^<7hY2k_RIq(Y&-d~Ea=U=pN zvk15RN{c@r!mS#88g3GCXT1n3wJ@lKo3wC?7RI!2Kno2GqFl8WZq~x!%_9Af7B@7C z_>v`;ESb`T3yGEqet1n~eWPDqx^mfy+Q!ApS1zkx-8605f?9u|fnHo|D{E}5Z?x4n z)UI5<@&;Q|ZR7H#D{KvTH5pC@{H|HJX8xM_wM~H)$Xr@~(@lYu%LUK2H3e#FYMYua z8Jdr(wk>b6EnjI1G}TTXQqRn#%U9Gcv-umBu57w#IkK*7@;3%*XeF>UEUme**3V^5 zRPKgazpcr?)E{Wla@%~3^*7m;)vj7zBU;OV+q1H!zOfN2#)(@>>*t*M)iz{bjtU7W zsZHsCrR85(SKC-i9bQ?VnL90C5{@Btrsb<_toPT~)UU8DtFNU>(cM4;4T^1H9a`}P zRx+-1SO`yPF9?)nwGHUPQh)8TOKgjpYHjB?G%jE1_t`Hv-v(;1oew0=UsK7*W*VRu zG!C^(m(j>iY0}0&Ez`9&&&q~?-?plLg@5S{wYFNK9x=Wd`CKb+SW#K-lMg8pAD3f*4&VKO6zKCZfpwNq&GIC9<;Nf9zur(Oy+w}3JKQK zFH7wjp?64o^3uj-tCwQbxjtKcO-%q423#{BHh-P|23;$yU+HheXf9m(J>bNiC|bsI zZvm6n1=?U{!lh4@dRs$dJxw>R`U@ruLpv1SMJt!p`e2h=mNo@2^_LGfHzp71Z|VF} zrpA@$`)xNZ_1Dy$0A5T5+p?wprM6W|R|I%Y)TfN#(0UX3g=m+gcy7eDvdR zGSOfreiG$HdnA6=E)z%+#K-AF+g;qa+)tAm7?=-|r$?T@e%sPj;7&YJ{(75#X(Mr) zrOTEz0`~wRv;BnJ%VSBDBj7y8{No8^|C@eD7)c*|O_=g}5Ef};WJH*mZ@QMR?j-rT zUlkU>0fb*vU!|6B%}Mg@0i0w}97G7qG5?JCn+c!ykjS?NVP-xuRc?7j^tT%!)i;39 zhLC=GeU#6p<#TBHs)xzPg;M@d`GLPB>!bP!K1#nF>H3fAcOssNmu#d@dP&bEtg=qT zZCX+)d=I{u%t!6S5YNn)%psnrd^jba4&QM3>b_(?IU}FJ5d046b82;JVSyGpMde2gqQA$37*D*{!tym&p_)_wjQ|cQ6pE{JThJ#Oj>&wBHKTN&^VA=!0H<*GK z9lqi6)d4=6_JZ=I{_g&>4PIj5m+&Ec>3RHnQsmIz!7OjU`EP@}7ymlb-;qK7QFOKn z@2WE1!SR*$yC*I74~!J0+avUv?Hxk?Ez&|gJrNQT@zVl+mhoMR%?ChB_;;co<=>j} zzB}ca%1|BpPk3;}0*PYrv)t~y)^HADWl(9YwyLm>Q)ciDO?Z~75 zWIUe;2FgQq63p~Vg@f8j{RK1P`IjakOD$)6F11whnR3VepZ3lMI;!&8`+GtX5(qGX z0Er+Chy|-)2vLzjnE-*Hh+_yCEjkmD35?`poD7&)wQ2pLt@YwJZEcNY@?rf-TdT3x zzBg6dOS|;mXn9-iEp5k^+tOa`idXwytX|*ux6e5Ej9NqMP!!1i3@L@&GDs>gmEApOKV z+n;NhMQnK}$L6SJyWW#F8I2#6(XhtR=X^UDb~zbaMoZsoi`SMS{T7>yCSp%t__uAt1rApr>qw($OYn&FI^R6FvRcu|q)h~Db%S*RBvf;tfj$d}p zc>X0#Z{5lryom*ycev}TLv>BTh8^pD&3i&kfgS5x8><`qEx!7#>o46=bMCo2cJB4p z*Y3E%-*{ok4i?b7bM2^YsrR&8SmLP(1eOMBcUmbff-3Z4&%10~SGifw3VI1I4f$F^ z3v2xZ#S5>!Gs#Ba?1&9k{ttKH$ zi;8OMc2UmUXX*XA3U-67D^(d+RL10OQ=U6s&X|j;;&_{kxZZf4A-6k@=QiX5@jOGW zC5~5V$hE;U>@{quG~^DzI{|ZPQ1fNZ0kteF%=?8wwO8lI5-kfuX5o!D-dMYn?23~$ znUUXMs0Js%MjH8XysM2g3hlf~Q*Ln_&y*{I*PBZ^Ev7AzH<=qq$Gl%iB`}t}#hhCL z&u7XkUf__sRK~2AVwHIYUfvLIx$+Lfv(+CO(7n(hUu1D$#l28@!njfnS!${`=CvM& zbx(2ddw{WEUb?fn*^qb9_E{{@6piu|w?od;_`B--wap7#4H>V)Y=^<-V9mlJ9IDU` z;kBt=lV{j%$d2--pdeEUYO^J;Bug?Y(gOeSed=L=a-$A)yh`@`#6L53Qm)4HymaDb z$Kv+$%(&PyrO$Ko(!$Xd1M~ zdhW=}l03D$5?V4*@`{}SM`oI27N-^Eo|!3U)=rK~H(;gfw$kxh=?0*xx6R@YP|<2% z#!Q%8XF@go3!o}@8I-0g*Fsg!F)dxDIdWx!H_bhNTBc0fogtH6o+=rkY0`#F7zB71 znm;pBX0mC+d3=gwl{gK)bC$?W`V4(4XTP_{b9{HRfFUpQY1&pF1~8=2lLV*(FmYJD3rf5J>ZCU6)(sa>p|m z!4)CC=Ie)Nn)gpI_!;@!?3B&#PL%aWvSiK6*|IV;NiLv_iz;*E+>$Ah`FdK!F(XrE zRA$Qz+R}{TXIBf18Y>G)qcrr^?0THz$}C$qZz;leNP_ zY%f}9**7ywW`?q5W-XNVFta!};+T{!lW3dT_8gPbWiob6E}j^fuXR?NNgYiTCp*OM z0r|g)+Lp+pUTiWBXQntw!$}&>;+#k{j{~0)x%6E6p`nLy#dhz|c2PS~rjbZ5MSKpPQiSg;OTYcz!C8e}m6}FYG+v-!L8dIA ze$FKS(<&w#eedKynPqjrYU^eVn|~b;g|=~}oB3|wf<~{0iL-*6c1AjF567S?cg+Rn zy*}6LF{tV&n3Se@acdjXbd%XLVA(Tp3icdJu;-X%Pryq538>n$_C=xqC1oNjHaDvPaF0`uW0&_NPPNUbVk#6S?PTXs@Ko0dzH~EFhcs8 zmf63iGM3Vp?=|Ovsw6hlz7cOjFM4%;E5ysD=J!&lUVmL_-p~28dH=&``r0lk%yyyr zlcigfB;8{P=|-${1L)UuzhR|Qw%WYk1J&!TB9m)b>HGky*Xktcs7^DT zp?UZybGTlS4QBkrdAK+Fe53jN46Q`2B~Z1=1=W7zhidsIn^X6r!@J3R{s2_3C!reu z$54&`YpBkb{{dA!4rjVJ9Wx|-kol5RW#@#PGV{n(#?)Nq#p&X_gmp4#|2^Ze&T-6_ z881&Wc)x}Jg!0j+GWL6WJO^unO6G!c=GmNkvj#K08E#{oKAt55TNv9e7fC;E>apKD zveP8HIK!Mz8LRu)hm>pOt3J>1|iAtOvVQo+FOg?`E;kbxIsx z=jzIAIfic^7Uq%keuSJ1l8JtI@j(0RBbD=^V(_S?l)T(1>304==IjK3YKS0hy0 z!Ce+VI#0H9{|flvS7!O!@2&Fp&d*Jk+)$QePzSCmYymI)o64uNcF;0S;A@$}b6>?j zCI!*@vft;<%aVDa$*grJMc1nl9ec$pr$ORrd3?cm!w`8Ls`tj4vLda>u{B4wzMCmq zj!%?L*sz{DTvIYl$4alc7G)h;$()WI##&U{N3qd9ij2IIZsZz~+1FC%e;_Y9-&c~C zM85W#VLbY=EpB36=fBSS$z$4^SkHsecHlLi-w4&~ajzwxq<#+*$6IYae-NtIQ&6qX zS1i6!F0ZErjC>r)rjL?8p1lut|B?L7og{PLohY;EbJJOeOktgv!Q7(H*X?9JQW^9m z-rIFJsOLldQf_^cxb zHFoZ-OxDp;B`cU7n82D{+dw<{E%clD{V%9q?(59^Wa~~B<<0&Bvwh4NT1PmhXUO!O zQv*}HIqu2WSum6LkziU;9%*nZ4qfYg(V~=rV|JFz-krv}jWt>cYd6+u1q&xqUbAI- z$t;=fm@bn8tm%p0rtyt+Nm%w_;@)|P)T3MmVyc^ z-hv5|>sTvkZqsJ%W(7;KWlm*I+MJR}X>(}M=)(f@d7%^AwU35$Y~dT8zLSLF*Zz*V zIWm_G{c}lcE@{mz&L5l=$s3s7PyV#-ziZY#NlF28UB2Tb2d%i@DBYqox7sXIsWY7u zkH6^1I`XQ6{XCNQpvb{Ln{{cwH|pR;(>_Bd|2lD^{r+>A^10e6ayjF*u4`0(k)~~w z^$f~-y3D#azN}sP+$hsL$-8%Wnd)=14s)nO^PM`s!mL9c8Dl~&Z6<$bUSxV8*Xty~ zyLgv$@a)_$K72u2pGtD-Kc6zFb2ER>PX}JIhEv?k}gwd8&iUrZZn)MQ+O|O%*>$A z{Xk|q`Xp23rf16Z5Mw3pebb94^VP@Fp%tiMO>epx&UxIV!ndo$D-A|Id{@FVCw%>F zK`))xl;(rHZ)+(2iv9*-mphU~E^5dAgtSzfuK9Z4C$lA*n*PS1mpz?Ol5`GOzpoYl zm2yB{t4whc{l^AbbG<|T@Lfp1-9$DrcWvS!>la;wU{hd?S3Bx#=HyXZSJw z`6sMPpa*W^TgXGu0_@#FI#qmMsKu7M(Z@6G@9q1!f7HAmI0U@{nO)e$w;5gk=~_kS zEB3kx``(1Tlfr&KVQ(8opfiXav`t+z2zD0%CpO#Rg(vXr=xrcfbg<`BT!1~E()J~6 zMIZY=4d{28Le&dTzftMBTi0+pZ?hLq*ykzi`7~(Ye(YmjQm}8-Kw%s4fmjGY6%h;l zP=)IYCi~A#6k$sR-bO&YfO#tox7Uew$>c$?* zPuB`^fV4k>{AY>ZLK^q*oIJ4iPuK@22MD{GO?~W3l*pavXot>&RuZ3hZPyWx{Pm*C zJs;oO(m*9O+_#VGS13&mGcp4l9 z8GjQg1~uRT@Dp$nobx_oCb%0M25BFNoCVf`-QZsE0{AmH|G!wOgAVXZkp7{_h2VN{ z99+o=6b5gDb>ff*z$?JvaL7`y1AGZQ2Tp(j##29d9=r+8p5Tzrg8kt8U=W;}?vU$2 zANUZIWjN$!@DCs@(;@4@o#20gcR}$)hXg<`7zF2JIiwDBfd369G6$^zd%!{PGI$#- zn1n6h8Sp;XFxerugO`EiIAj(03iwxW_7u_pFM_ zavwMh9Qh7e39biW@D5nZuAc|NpTW#C98wDE!9nmlaNZn;Tm|j`N5F!)4ygw1;8)5?ItGLhed_5#B=N|$s? zk31&dmdE7@c~YK|r=?fEBj1(p$ushOc~+j2KC%D)SzBK(Yt|HP3^wfztle9`N4M~~ zYNJ1*x?ES3m6p0n%hql$TIOTDCSyyOy~OjA)A6ptl=)WX9O zST=H}G>ULYCV8u}38iet2{I!oN}1Dbv7%gNt0a4ECYMN3jdsCNYbA+r>JlCjE*Y_C zX%{-&*?Z(rgrvojGDfOGA2GryCy}x`v@In|B1PStf_RdON*Qa^S{p59>MBeT({oYE zqPTFai&+bSp|Qr^ER#G=lGT{hs98&tOq~@&a(&r`(rue7J!?z1t*Gk1k%(esYM5}U1Z?WJhW6HRl4Dn_KvS0movE}c8g*xo<1aPU%^|lva_Xrg zML}u@U9-?Ue(NeDXr1D13Q|$cp<0*A`b(uHPcpT=A4QVZYOt~;Rz73SqL!Gk{Mk8N z*_e%wQ)X0eWy|G_^{pR~dC4@6-^QBVdd_Ohjec0Pl#4(bezZN-)cdM~2}vbe+g9mJ zpG-JuUr8#RsvD*h9!)i)vVF))GWKdyw$wK@`*e6b)d+PAbxpxm&RqJ4GwRTtqR*7Y z$~mdNF*lJReVm6{TfMiof}@3}kfn01J&n>D@->%6k5-K#;yOK7*BGkwH;k5?j&@tD z$gtwxTM#~(RudwdiY`)vbutbr%%BC!?ouo$V@vn__%WwmTL=x_=XgU1--8>;stu2T{%GgiOa zaFWOl>mjLxlVxBe+0=^F$HFPD1I#Q2PHUYWoBvN=%|`mK(FfvGjogTmy~llYYKAOQ zrv}OU<;ctaDlH6m`5wn@zO) zCTbkJk!TyP(N;0zD9bqGY^ug?T&#|beCnuqiVLBnZ7)SuZA!;sVWQGgoa)uUve=+* zGhrO%t*T< zz9izq-V8>NPxjU^iukDN$NRfM(DD*C^5-<;J72tLs!YU-Mn4FQxhKb(WYoT>rZLxa zR1+Uu$M9v-v&9&;i8R(X*eYWz8&AY7IzDJbJ_ViPw-vqzf3qm)ccIBMm%^1IBKCTvMZwT&y! zrZzlnUccApQD1-hg9AUZkNS&45hbQSIFyyjnv~H~n-mv4fMW+AZvSG*rjDmWhOHCb zpc~_i?-QrL@-S9JDHWzRDb>$n8;2>htr5mt^<^7lpV{m-+Ek9m!f3NMR9Y{{r}vYw z^;=g;h2yZ&7}4ztZJ8cNImT9)DO8Tf!nks@-W*T295?98` zx6!6@JQl{4-yEb*>HBQwT{(IPLZd@nM zX5V=~=Oxb4{paRY{7KFP^m7)&#`^$X){i&?v2aN4uEqF%gV%54Jq7P1yoinWPw?_z z=fb|Br=PDj)wJi=norC6f4mEGpA0_!PYXzu%mt$+%Ki2*%AU$9ltU z_ogPxOR_9TckjjNuKF66R~;LDAq`nS4>rp+8C&%|#(4SzS;zNnQ&FibOTS{TFWBn# z1=Y2hu9!9ieJr3FYg*-%s2+8;j0K;Ub@gn^F?W}9qG6rxMN*xHOJ;gqI;rUWW!24l zq-dDtbxnKu$7VtKSyV1&-%q0)E2T@zDz=nuUS7OZk1WVn($;vY_}3R6W7C|uQSK^Z zpU~a<#PoseF)gvqicC$brNP&rUl}+Z;tA|kSKlPCQn@v|IrDaw zcs%UJ^I&Czzfm)t1!tY78E4A=I)9CaonGn_UQh3ulCl5X;i+i~wBk{97{AtsoA#zw zPQG~7wX{_34mRCTHuUd4&W@(o8qh^+U6aR>_tg8FL&B*QY~v-ABaiDUwr#20bXi#} zHx~;r@YL+D^#pW-rVq0{jZKD@#-<=O9^?$9kV17$Fy!$!?ewSl~nbK(V z>}xjNoO_x%o0Isg&V0s674lINXhn!~IdwrFEuuggj5-lc>CmY3Ka*&QX{qv$M|R6D z87fIi+~4RADT9+av9QO-xg1ZkZ?~t;U#}U^D$hqpQ)8Wf7ggkGtj0_94IX?-@5A$s z854i|{u^VDe2x43!KTIrc0A!eB2J>I(bwV+c|z)%nlqZ>3Ho+Xu%u%>iMoZ?n)9{z zYW9YF(MM*adDuef(HKy~sU%O05s>PDe@R30k{kSuOL)E{NZaPu_$BqrmMmLhHn#)` z8kWCl#OM63y2~z*mD|t39{e=+_ru#%9PZ|B}!yL`c@EmLXv zbkGgjk<1}3xLkYB$JhUy5{Ujk*;lVAe7)|7o-8-dy6Y^O2F@>xw>5rt<%sh^^ZCI9 zf5%JLlx`12M_`vrl08qDfDA>+V@~n@lvn^!|pmHuNeh+zY*!bNT8M zGyr`MxC!fd|Mx(EaN!J*XTbr&{m=*UI6qCe9r{zCK8w`H!1XgZ&wPxt-%$12sQw+5 zM*TM`4Hb|l_)2dD&k$DnRq!%lJ^z1rj>r+hc0Y~kzi|M(t9)Dk9k$Y zP~Rs^d-VMJCG&YFfv@M!_X4%E4LS(a=b}>A0(?~vR=OUv6IQw%JVV$EJ$E6t5mujy zPl2O^d!ZM9lJnn$UC^I{9LhEV^)EL00qBHtOupS$qWV?*3s{J}(vnXxzYq6?9u+o1AhHcPq zTx5pTH{fShU`GTQ=x;zD;RrPEVl(gRKkvLx<6Gwq?1a_;Efe)`chhQYfZqmv3@E=B zdejPgKSO?j!H53U3bSmI?ox{n{li*p_#Nd2eW=XjtADv)Y@j{DSHBnkg8z(@8iwA0 zkBj`@lP+}oCbKW7Z;gygXm9ZCKG*F2*wimu=N5cLA*1v~aGbExSHZi4?S9wPAKRmD z(mHO^=Lnxi*zRvl{jgns1#K3-(i=b(VY_d&et7CfEd<~0Pfh)-{SCCkS2}wuZJx0D z()dv&?T@hfbGT@mStjcH;~j7kzWNbSKOg!3X3~Ny&2muRA`b&MeD!}3^=YPbNfqq@ zzS8C33Bq<#cPe5HQ`S%0AJpda%6BA>AOpZGj* z6K;e4;||J%u==3LzsAgq`sz3WLhvKdsQ)pgE5ZHnmA(yn2rJ#}q3j7Oy#X8{tiDi| zd#OjlF6i?>{)im3qS|U3&|{zoegyhHP+wq5*X^V&6IS{`4L;BaE6uE>dMP_;pkoUM`=tUrjEon04+s-( zhrVWoBhc%wH|s+Ei@XhhO6osHUn8u3TkZsEv-)poy$M

aXSm zs3NR>X0E=OIwh<=S0>+rpBuvJhvgUG0AcmP^3LaJON6COWDZcBh0q$HbrFE}0WGV3 z=&yjvM4-iAFlAiOhk(koL;oJAOg~ipzo;Iioj_&OS4zXJ%&DZS{!*^J4Sj^Y(0hQ! zRlh68fXb`?m4e$X+n}{T`Ra$|M;2fGu$*^?$yZ-8ZvoY>{$zf0r>S3k!aTBHaC(A% z=q+C|%T|59^xRE9gs;AR{`Pn1BCI}Vz6~}jA9~+Clr3TPJ@d$Y)Q5(Z-fz_l^y~-d zFYxWYz|=?BPak3&gRk@ic!jX~7P{=9Sx4#v=Xr1pzWN7R{x#YIVfB@h@pal8VfCN$ z3t-e8bjHKXN&ilLLEi#KexZN)Ci6CY^{4a0Z<&1csq^DUOuqWZIoxjMeE|COqh^`( zLSH&$@u9bL(4WzB0QwyeAp8RKB+&M+v^q>5fnN*#33!-r1Uk9Xl*xg*tgzDDF49IO z4|+QoAiN)X6zJTobV3j106!gi2XMZL4D{y5=o^IFphtj?lS*^HZO+~5A8RX6+tfGJ z_pI;{X!heKpZ~!sJAwAWTIg*++mh0-74C<=2h^SqphZuZVWnkOxEva=!b)$q!uz3r z0&3fv(78{Vag`QXVWq7=?Ys$E_7r9OCcdYjZ-Cu|k3+MbHf5A9x56dRTdnYI&~E^> z^I>RtFI4qF_WAoSX2C?90hC*3ljdP<;Q z1+TzwhrSJt5_UezvK$;HtbV0`3ikh&`h#XaN1uuy1N|&$C#*h>9|whRpcndctzTq^iRQy3i87x38>j zZdkf+*&_ZQWTU^1-v+EReP(K?DlA;ZzjbZq+-qHvrES3|+LkXc;t{i%57_)l)N0+s zF@DYAqiL->=-Njr*GR_=1ZH_xej~ z^ds-;MRnEn&Avs2=g0J{IzM$PtN6#_Hk($RAIlukSDha%H*SVk$8b(Rb1?O`_)yUy z*P-%52M!%P)PAVvP~V~cLx&HYI5c?ZU4FMce*>PI=!8{I|H39 zoo$`_I}dao>}>Ds>Fn+7>+J75+&R#Bv@_CqqI0nGBo4f?x}074U4>nXyNbG2bh*09 zyWCw>UEZ$UU4gEauC}iIT?e`jcC~l)boF-ib@g{0?i%Pi+7;?{0SU2a?UQ*^odfn>V`~*s|H( zZgxYcNNcNzSS#9!SP>NwZAC<+ib}O2YOUXgd^~-spY|_WT3bpfrL9tIzjNl^dGE~J zIdkvaJ8$gseEU2nn|I$iXMS_$%$YO)&$+xYJ9^`WMVBnse`+0FYdbpDb#`^=e{V}Z zws)>w6MwaL5kT}ofPZ=#;9rgd_}5;5?>`FgU-uv_gXrX^V_N(uL_}}AGp4QUAtJhL zOH6%tLqv4!{+PPn0TB}X_xlA!XKex^_*`2|-}(>$(Ptls>Fad>qHq6uOs^aQAo|i> zF+F!C0MR$D6%;MK2n4<1Mu?E$yBEduJmx|4;#Xt(@{<5W-+dyc=by#zk-l2MpF}?ga@*{m=NlY(X0e}=;acxYOk3mGVX@em6;uk^Cw+B#9 zNM9U`=>;qk(RUWc^l$igqHlaYrsp0+{XGcL63n0Ifu-=J| zdv8qZu-=j22agDf&VC8Y@e=0oSwYce#7lJi;+T#>of54-LlFFM0}w@Tx>XQ-c`4Ql z(s$6#i2nVKm|on6^@jBQRRFKvhjsjnAo$N)LD1J80zisR{fr>^7M2$&I^_d`;Cs)3 zp#MOuNYSZXg5agYKol)`SrEK>8br$$34-r!Lms5Bpst9%`J$kxXFUiy{V|A$7Nees z&cwPTsvj3q_Y_1#yRp3xUGhjwC!y|$PJA(@4gU-g(X#tvs^f2>buB+aV%4Y9^)yOCciKxH_hurx7z!C+dV~Ey^X@^>9qXS3pEG^ju6= z-3AfSAmSz(z&1{F%?UB>MqLxF?u+TocR)mR@e46sg!&-50BwqB71}=0d9THEF7gqr zd?2Rw7a<~Q+Z0m`u@NnLGNy$KAR=0W7?I#L^a)52OvZE$$|72RZ%kLd3nHSoz9**5 z&!Zh8oi-QK83Pa@!B<}s6m36*di-=uCu02)9lau^1&D!Y<8v|fqF#tPACIYH2qL1Z z_r)}fWhB~pcT7WAe?)_yifP9fL`2s-5!0UQAR=1*YD^bn-b8P?C#H*@MO`ATS`yQR zSjR-?W8D#*`$|mb4We$5F1^GuVcoLHi&(K{|bDOlP1iAi>wpCK?&px_xlR z(C|oK|IUp=TL*`C42_H(o*X&cv1Vj+W(Gz^26k=RmQ4ijR#L@jhPUh*xN@YgXSfHs zCJxMubocdd>e;nzc%-*ySKm<2aQ{esaC&xbOJizma(uQvcFR=bz{KJ4$$GtgORwbV z9_eHfb@bNNM2*p##%;1FS@#X&bN#ck)3f!>v(xi4z4Mbd4UIR()GV*+@97yC=pXFw z>91ca<@&NwK7Eb3hC7?B{hK#yc@$>po;cWZs4+3w*f%-u&I600X5!7)J$HEM@SxDC zJEJXon%eSV>7MnKUYr53dm}H(&^YRv-hzg#4Jg4>WGdE5%l9a*CQfIJ&#roDI2-&G>57ZPenwXg;D=Pa9z{dEMP> zoXC0*SX-^$)89+K6ab!Vxf;mkkfXAcp}V{0EJHmt?E)#KMl5cgd~TwUl`HXsRVBsw zish7+GwGF*8gu89a!JiI>Fc(V#HugCktaRHAPSfaT%l~b`Q%p37D}EYS80CE{4pKXkUh(6{kYRv zBBkB46LaHcV5|jsv2~=;56fYVm8_|iD8Lphu{_G;3l@v9f_$E~hP8%P^ty$_dw47PS3lM3G5ET|||Dt)f5~HPE2YDvEd7 z?lNWg^0kom)_U*GVpH6a?BDscii=4DJZq83D`!T4n;Hk_xRJBwAoPJ_9-A=|%uAjq zMjs94F&Ta?FL{!OK8(y`GTRWB-rbDyxTFnn>8doQFfwI(a!JcH4QcN2D9DSokVd$M z<;uy@ww%c`%_}dpwT11xWopzmH3>pS4xSL8Aum2Ze>=RJ9$&_{a|{l@?qV@~x+|&GpSu_gU+zk3_2Vvv%$Sf%>=+WdShAxtHnnST z=43L)W?Wh{p|mCHgEBXZ8A;kwyXVeb9MZ?w(s)FVmL4>OM2qcNM<`meQD-Cw1j}Ky zK5Ob6^J96kGZHMIjJM3pM-*VS+q)f}Vvd;wBQ`5BhhedJYZjRzWz9Z^&u04>7WWX! zS`^8mT7O1vb@Q(*QjLkM!U_aM#rX0y!3B+01qd?4)x1+IXw=&4+f(m~WI z_KR`af@5z^u|AX3!`0)n2PdYd>iI%wHhX(o_oU;}GHA{`*Ko4a=Y?6Qgj=T$&NZe+ z#|sp#X+v7^N(xY{h&S?LR^-XASdp94WkrQKT~@>kDQ-piG88LvC)T{1G`xHks}=EV z1+BvQw{xyhD9-`S z_myI&d^gU|&W=xs>GkNUMgQ@ zZ(|wQ#NK@~twI;DUDEFsnsZXjw-hgqqZ(r+Gc3bOmfL&F+_7HxxCK7MT7(=+2!q=y3LsJc>Lwqm`xUPFZf0G(xiYT}*q<0BKv zSOB-UCu0ac3TvZzcpOjm_dxf4Ws!aOZ~=-`0V`}o2U`h=xS0JsbQA3{uGL*>fgK~1UswOkl-U7)2ZPlV%frb-` zVaE+(dTbbvTa-6UJnKQ#UP~js;BpnD)f!QP)dn?`;5d9-L-AEry>2DFrdUO68C0-_ zwWew@l0eRMK5Kf)U!QCd*=kVFU_n)hbnq zC&?dH7lv~&qjS@GD56Eym1j88F3pv4CQ+ zhWAZRSJ5LGUpl%8C9WGQS=~0_ueTIa2vObpW~Uotqc~kTI5BlYd9$OPE!`^*jgtx2 z`|-bx$;s)_hWJ!JI5$?WC;v9DnK<$pch6KRB3Y~vT!a%C0Gnd1)p3z9b@Oxn^f%Ma zg%4LEiMjMblIk+k?bDTHjVNoZ%@b+WC8nETE6GY5eDfq*Re7|;CXe^U7wQy~NNXgD znN^fRC@6%%9uNDIg1(0!D67O(L=@WgMB6IVZ9vWacD&~{SlFc`e(Pg_r6iu&(GZoO zg;`1}EtXqK@)nqxswbqDrKAdi*`*|JndIFRrE*J2rRCa|l1d9pqI}CzQfZOwQj)jC zOto`MNfjj9mXa!nOY})Vhx8#p1)&(YT9%T$1r}UNsv=iGs?C6wm6`T)sR}{~j;Cs~ zQN<)tE-xX@2&=;j*05I9sp9Zeq#?w{II}Zt zC3I>Gum#eff;FsF3$H|#D$)>QW1QMtSqXIt6II4B0%b6v5@Xf!+8UCvlvK9t)Z&%( ziE0fV<0iw8wnB7@w-Q8MiJDUT(B{%yb7WOcpum=0?0eq$&?8S7=d4tXeNtm_dZ57(>={qQ(&I zJ6KP~EhUw(!e*B%v{$JfnxYhVVFU_n)hbnqC#i8%7iM2d@~;6SgtRUtm6ysbCHYGv z50mzM%u-Tmu~@^}Qc`I_P1_42&Rk0J$Cc{LSV}4-idjnXmKAC#sg)V)%QfCPLb=j3<(5)ubvM(>7dwymNkKk<_+E^e6qk?CqxyuXS z7x8%A)7ntcMZ98Cm_@vN=G;ZRVj`49Jf6W=kt=d(hGZ%6s#j;bc;RdBqJIQ{r~e7y zIDD6?_g?`X{XW1w{{^rN>FJXrcyw_DcfK)#^;;v@a#;j-_eHS(*a+Uy6~X)e8(`B} z5wv{{;6vX6cmUscs(&5dXZkk4p;rLz`VzpI_|DR`-vGF1X#_XEA%cs(i#+(g%vbU4 zq$j@&@C1H-7C&G26@bZa0<7qd;1!hr>7yff74tar2lzeavH$Y`=f8|^k6~U!F7zAl1C5W`ED$7hk}+RYIxJ|3SLIwpcM z)}#C%0^Ith2$o`5?m@YC;Jak|uxzVPkN4qwV9#K=Z~aezhrR~znNuTJhQzFJrO*1I%30mco^{=SC3$-JA!4q z5!WS%@uUb|JTZcQ-hetl-uvTo(R!4Bhn^8X(BbJL$=NClq z)T#(xI}g7*H-ZONB98V5HnpL=S_DsG{tFhO%r&T6d{c>@W$HU8f_o9uyRMAjJ#UTR zdDP|HX%P&ZfpQS%q3u|wh;u!bX9d>(lZf*<#Ccn91dk)mp^galU5#lG=iNK8jEMD9 zh;wX51WzE&>-M0{AkOuO@t(It@GRn7f*5Bm#PXew^@=zL5%0a1M({G?+=O^%Ux)fd zoUb6x=MiT;Lf#b-yo6X+ZHwSy)azYaBKRoQ^)p!4%TOmvu|8fv%x7brelP+!1x|*G z;UZWA?Qj{agHz!&sKW-h5{6+2-UMgCIj{ou!(q4|M&KXeT38BifwgcsoDSWv3(kgf z;Ra~Hb+829441-scmphhx57?16PCj`To2d4ufSi!Nw5mG!XW$ud>EdBABW$8Tj4=C z9|qu;;jiHJa2{-i?Jy6A;BNQ?ybB(HAA{e9cft(31CE1UI2L+fAG{sTfIaX=7=web z7v2WH0sk8&;5XrEI36~_O|Td)gc@7{SHaD2FZ?R}E&L7q0{l7rB0K?i!Jokg;BokQ z_*3{f_!Ib9_!zt&{uu6r$6y*h1b+d)1b+!1gpb2L@Fe^M{2sgqJ_;wo1+WEnz^CAK za0zrmKimhOgjqO%Rxt-R!n@%ka2xzCoB%7K4Z2_xY=d8izlTMz8akj4ehvN({ulf- z{2|;9kHAmCAHYw-!|*=%eRwZC1XJ)c@JDb5Jc<^!;E2@4LO2FSVK-b2NB@6cFSo#N z6{?$~@GXJ#X7(YRLr`yep$k=%>rHZ#VrZtFLS`S`Q6=rRy*I$*YESE(?Iz`nb%F9a zlb6a|Zb~VbIh(v#=HjMCsdDaSS@qSLytL{qZ=o)jP0WxjYBoT89*0GY(bNI zXPYGhegu%oAbmQ)>Mw-~(=>KVQ4%@5i;<2sc_kfZ14@!2V)zyj3u3L828!bO2<=)c z)zjHiSS&|Pm}@nb#C)ZuiM^j)OBt+Hi?*e|?hQwNvtq`nfQB$-s@UAZ>xy9(%OmZzSkCQh?JEt+V&TktgYo<%EwBQS`lcDKT zLkN$-Da7l&NaM2LUU~b9>I106;)->I9plup;0!FjQrpOYHLmnF;tDf;%;JQ1ZIC4v zJm>0NhTS%$nOCg?_CZfmr64UnnPifQ;w+}TUNiy3{X3%{9FN^f<@HQL~-sj9Onm}3Qia>9K>0(L?PM^@ihR5B7bg83YDRUbnF_yT*6uFAOIj$v^+BZA% zY?wN?P%{ttmhm;H&l6EU+A{6JC_%cb}%nED4s)yWaVFqVSXMdUtX2Ri$!QIi5(l z+xgvj%au{$FMW|Q?W8MpqEY0UWzL68E2-HhktlYtO>KyH-OAx;wejR**=vt|o`kog z&2;t{5sNEP%~wXa!8w=SR$%!ek13nd@<6DJ}Y*vx}7;Peznkb7gF@FhCkysXDB9XT87Mb!(YS5BA6C=|aLHzol^|eCV z5XF%^SA5Bx!0GmHF)Zf>Phys*c}0*&$_+ZG+)Q%YxPwVvENT8~Jk#Y+8xmXA)ACDM z-jvSjz!1SlnWS5YcSPP)~L)R3OI zfZnqVIqK9IiYAtND5cSw=t$>+o=mE6MC4}LmYEzAt{NSQKA#onZ8iOyGXj-3##{L) zPTHZ0Q4v`Np(ZjJc~{k=2=N6*o4^t%GXj-Dm(XK#46kBTM3zCQ=`k7IR@Eb2Z4}>| zViQ;bWk#S<=n{Htj+2ERvqSna2sJ%=kG%zus-3*@vVcuqiBjnXr_E55PP^^uXS+Xr_H4UhEo@7y@Fb#Qpc(8$=~$&teyYeq(AX7KxgUE8*06X6#V2WCd( zZftI3q3o3}$bhz>Z53np>1XBb&e^SBl%pgBS6|QS!O2ts2p1MOfv`-)fQaQZUCGSm z&APhLvlvIZ(X&|kVvt1(Pz{+?0hd3^Pz-=YXC%?jlzEOaAlP+(x%a+C1YmjD?yU&&uWj!y}WlNuA#=CbmGoFRXEIkuoo4Ha8 zl%}-Xs8TO+Qm2Qrre>Q|CN<|?G6{=|OYC4CNv805{)?N9XPSABz5+rMzeBoF_B}d?3 zOFgQ(39B%Z#e{QsbM3hpKX2Sl{*g{rQ60VYW>163?22I%SrlQU%`Lb+Jzr2IeP92k zo?Y99M|yj9^$qn5_v3@VcKq#IdSxMvLmB>Kl{BU@MDdWx@z}PdD5A6@7~F6}?gC3% z8{U9oEc;j;lHkHfiDquBoLqB7Mi&d0SthHJt2+tSBmd-xGh^>sCNEU*@QKVg;CT>U zq<2B6UTM}!5h+Zd>fA&@xmEFI4t!86<7~LO1e_E$!_4+o*l6?y5cNT zRjPkAXQYNbZ_-qORjfB$!zb*wzb4|X+jL!0!7FXA${wJMVBC!Ec@8B(M2uxlqonNq zXHrt$!Y5N~EK-qXNS&NdNm;y3saV;#tTNsg)tNbV!kbO=6h`XZYyx<5whPdMZ?VkE z49L*#uhvtGLnNsV^e^>K+!+>yTM3VIVJK-$5Xx6f#NAYcKF5UGBnH1zEeif*G~s`? zC0_<#snk2r`IuCOT%&HqGhA*Q^0Z5erPP@hg*|(Cg>N6E2|^I)8o&g_#KE3Jjfu&| zzR7X-9t1IxNh8n0Xs3NxnREu1(PqUX+ky!>J8lPSz+5sJZlq4?=v4g*&Ay2Nsp7N>E~`+RV5Oe?wHnV4 zX_hVlD{{-i)#O@^_Y7Gsmlel#nvTK3loqxVQ^_4kKl(NQkMROa|^F{i)J&Lc!oW0qV$K;8< z_#72JiqYGb`V0SaMzYM=<3ZkTCNm3tFe}vC$5@4m7F%`Uudw9mn49Nia?iLV)sbbe zIw_?Q>l_8$MV6^R>(`k|F%&LLB?pr>izZ|#&$~+XxI{UtQ@lpytZm!_6t1BxTOpO} zYM0&O*grFeA*D#)it~p zwMTZYtPmcaMaWFWcYJORe9|h>5G$519JfVCoVT)wRiZ|3BS}wPxdoR&t2a}jh-9v% za>So{6IN^q#7f+timj$!V|2m@E`!#h-((J>s(xGe=)7uXL1tWxIT4}Xtl$#*wFxdc z+af?!4Uy7wTdEEXsU^y3Gf-`=s)SQ9r#BJ>C@rZhQ0ma$tsL8m4{Z%^*)?$GNMFxz z4=CTQ9-ExJq}I{3wxeTRXIIB^?WZmIw6<+s^1r={#%@0fKD_ysF?@mw-vo+(R*#ME zo4;Y@&g3J$&ja|XkN#7K#l5R1umftWY?t3G#sB;tBz*cx{2Yb<)}ieaNxF{Y&-kJc zz)_f=Ohw zB#T}L5U_8Qe-VX@^GedJp)|;Z4;v+aS)2Za{=Sm_Nq$H=;8RcO&jPp>Ka@Vn=QNx} zM$vOEr+w`j#c~!1%lSCMi(v!UEN3h&i};^nIhV?>$Z|d+KP11&a$05)Me6u01j3$> z^w!)uRdaEh`x0j0(ww8st(D56HcM?z{i#D;wz)O(@09NU$`8qJO4kw%7t!uH2*PQc zz8db7PHp+#MF7-r$8IOjc9|&c(LV1@8CipOJE_&Auhp?oQ;yI9<({mi5d-zSa-$S` zP}YQMe9mprT@t9FwaXFd0t4ypoFlkK-roIEtyXJ#7qtf8hFFd&gr&6Fylc4Y(gdoZ zw{FCGw1U+&&Q{JXnyT~0Q>&%^Mb+K)i07E1cuK3!fS+%54(%;8&~kGJVYMeiCB41w zMeQA16i+ejiLF?MzPwwCtJNN-;Faz}*&9hS_Sy;Us#rR^>@8tE>hAagSkklCRgu(` zxK?cg*C3Kb1&|c0K#ayspx&+3)mObvL3(6tzuoF}uS2b!Py|acwYA*tUvFS-eQzb5 znC>&)j(R(>5S9vx^S3xz$wq%g0pdw9T6R0Nyc)nXd*gGi*LPX{;v5XZZSk(cUmu-z zueA>KadLu1iN8z-8WIT;fzhyfNj?%>u{G+!{G3}aT{3hqY@?0{PRSs!93aZ690OlI z9vKE2cxYI>v@o7zWzxvpKbG%upm{@rCU*&dwkp%j0oBnky=@=rW?4}*N3gz5)iLpN zU`IqlrxisLSVNr-?|Ztyl-|5y+pc0W9mAAzTUDp*u8dYiQwe7n80>v#2>b1nfwqC7 z3sJmLLE#)XS%7$J!-3;W0|y(0g}}jh7n&M7OTocK@)ijGeWAlT&sH$BR1Xg8e3OBp zh1TiN#PS#g8zs>iW{`I3hzHI|FxVrLUlQ;bLi+TF(S4HrJ%b7cFjZT=jJh^ zlKgwz4kl8&1QA>+5!j8pqqlB4WdHm-84pdnAl78_w-~bxhM|^RzwBCpSSwNF8gHwS zbQnl@V-10%iy6smz?$hKBwn}288u=WPHqj=+GMw&&z0{&G+oq&jmzZx_g{rrm2sh5 zXFlao3zV6Q@oeG0yiLNaTK{O)F(Y}I9gj5>5rA+>gwEfYpp4JC z_U0NlUY^Co1#Ae(0>)oMj>!70b~K!Z0_kU+Y>q~6PrK(fB#26$H#4frzfY;Hl~ZE6 zuXrC~>n3bR{z}A_mZ{E{$=ktD^jz?^#p-3M$-r8#CtCmP5oHQ^kz-5I_A+R_)laRH zcGL$zE1jyY+kL3pjS{W!5yoa{?~ap$Y!o5aChS(LgY;7Vo?i#hlc66C%W&OEE5La+$tY&C~W5CPxFD~6&X+y)sbT%;Ft-+<6 zZ5*1`>4u5sXeD5KiU#Ka3S65KMn4Wj12H1MJ7x`Y@%O5=nhe5q|Fsu&w1W^?FPioD zUYs*93Xp5>F1&**UVq;e4lmz7TovQB-i_<6VJ=|tZo{trVaS2lTgL$r%Lzx_hDXtc zcS^+4?it>u82yQC=_k>N(v^De?nw-h(#$A%hn;{`k_ z-I7pQkL%=M%fPf1FJpmmn&6wRUA~xv;&R z!^S(*=4I6({FG}B{rUu(z5twi6L(|urt#)MIB^$ubqzABBU{j$j#yFZn3e6|P3>*B zn4JMM*K5_<+NJGURo|!J z^1FN8s6VqC&#ljOa#GCD)&Od2RH8~&CjD=9Zza019CW-pp|vl%FTN_eTAK_k^tLdF zx*Jc>$yeEXgF+`6L{Ve7&Sy!p20h!}53@Rhnf-vHtt4XtD1>+M*xH%eq> zFXnG4x(Oa#ex=g00hQ6EcY5fpg7#RxgV1H31;~3&&4grp&b2caqMNLU9N}A#Q-bRp zz58U0DDKXSU$8hb5Wu6kPVF8bT*kWxwwjYK7#Ou=8diR-G5t85v6^DAWF|0ixlugZ zV1n_Ui*cPmo3^0g_Um$h41oFCkzJ3`Z_}*^GZs8Hi#`%H^-cy$3v0?TcAO zP#B!ybXt>5N4L`vw9}gj>uk_>PO9601MguDZ#h$-8_ojYm0g;yU%EZ!77cHesqs+z zJ9w<`;;{Pbw&ihXqz|anWkWT&h5Qjdr@xX5tq;}`7xXEhD7}160!MS zjlYHwF6YidBEF47?62XVi1{}6ZVmB|wtsjJht*%ZVf;h8U9aQlcYngbTG>Bv=IcG; zs5wx-mq%Sf#|{(rNA1{U_dbbQTm@T6(+F8!1#9>PvzxBui+_?s?62jZi0$@Fal}t) zh<~*G#O)kbf9!DXC!Lho1INp;IB)^ z{f>7^RF$jV8juCW`m+|Sus;`z6+D&MJ%taNzto3(gWc4TIBhm*xjjoYgEf z;Alr4!qmsTbo1xWThW%$D|#oZu^LVxKOS)0(Rf#kHp~-l2Cy>oiuRprberTaSdjW_ zm2?_r=EIJZ_67c8j8s0iR`r>LaPfDI$NWJDW`8Zm8w11WSuW@6Esaj)d`QRqBjX!* z#J|KMF011ZGa;_it#`+WEwA-i4?zTJTdtL6VPox&G6opL?u$ zY->|29Pc>ErJrA6@w84qt{pcYPVodf-0E9F#Q`H68QS7p$d$U-$ zCD$W@=hy6bIMWWIA6H%7m&MakEVY{4(xCS|bVu{AYgqDMBV+C+pkPEiiD}q$i5VXr z>u*@GdiOWMu)4;{ze!ljJmYC9(A%fF_WIwSpz__oB3=k>DYD-xi;Ny0t&U7i+8H}G zXkY3B5*hA>Ex7+vzH3?;m+LIaZzs6sX9`Tk(AJibfgpRxYL1oN2L-0=!>QhjO##p2 zxbXfCgV)=qgv8q}w-4#wnqETsU5QtOKvhrg^PmmG&5bK-4$L2MVGgKhU(Bu^`lE!o z`R;1&E2&1-{<8(Hy?wuD$6^hFZJ~<+F1IdSk=;XCEdQgC-S6A+v^1J>+0DaQJT1lI zvYS7!V`-V)xL&P#M8i@k%CvO%z83C6`iEAe-foJSobyHMI{Ei#j8q@NHmutW%X51k z7ur8z(3WbMLC~&~Q_x0h*nu_uINg!RKGV%d!^$(=rZWAcq$EG$=l%?b0oB ze@3-EKU4OF^2)k%-R|(`gze_QkDs>`@e@wOd~GvxJ@^E=r4#nH&zfTm=i?^gYAYfE zcj3!MrH{>Mt?Vxxn9Jyx2_Z`8*?z)-?%w*#Cgy+-&9~H+KjB1NLeGKL{CT_hD-&@w zTRtLds82dDm(lT&u;ssQVoqMOuew^jHH??zTi;Vo#3l3`2r+NVe`6x9X3OFB**W@> zzja_PqvKGv?7DN{@0yqk% o+^#=f8TRTC1fAphl!CWf!(z9Gm53gAy#HXwTUNWa4IqpDAF*I};Q#;t literal 81332 zcmd^IeVATFbw4+J8u^F;5yMx22;sx9?~-hGL*(6EvLt~J;$}l))NEdM7g*WsuA5B= zh}EjKw4&lyt!SwqNRcAiib|>V@$nBIwb=TBT9Hyg+fqfPij-26o-_B(d*{xbGxyHN zraVvgc}_O(yK~O`=FFKhb7#&ybMore%*a*e&p&5z@u#t((b>_{xuUD1_`UqtxuUbX zTl{I~e1K#Zz*o)$`06OY*KPrL_!j{GazD}_z^}e2D1ku`^wQfPAv*b~l+HW_5+r!+ zd_l=ci+~7z{8d58yd!`J{{F_49yk$z=6?$^-;us`T}t1763ab_nC=n;kKKp3kbbs6P;$~8i0=-7pKKG9%)1%! z-3)Nwms5J+(})l0zOIyha}VM}dg{@XzWWH`L;CdwK?(c>^@6l)c}l0e1rnmORtbWi zZwI1eF@8pZpFAcgIbbOe!8e{x>4*IQMBkW9>B*e{ME`wbO5eK*04X`^D}vzXh==HB zw+l)Ze;wt29pGQD6Oob=8^D53xUq{^7Qi{_9`>qNkUo^gYBy^f2oBM-SlN z?n>z)Y&+5YD4Xb+TT=SLO#nns>`mz*>{FueAReM;Af+G7!*WQ!MwvuE8p8U%ozg$w z06_FDEKKxI`vfJYVH=U)ch{%%tEFgzsIO#iN-udYBt%P|PHEK+NQjQvDG2`a9U$oO zrvZ?XC8L7ie_jJb$!W_3!7mUy(Jv1blpNR(MDT6YIa1Pr?fH*8Q+jk008+B_-jq(? z4hhi-pG)cZjgSy^qwNu`e0NG+XF@`>9NR>6F5)C=ATFZSLn*C#0^5LebVduiAt5^I zLn$q|4-%py7Nm6KEF?sS-I>z!kdNs3Ln*!Z7D$MWK`cbaA~q!W<;{YUMOZfyJc2qV z`nTH!B?ny(f)2bNb%C_(%PF0T^%9+pet_r@EQbWYT`ed%^b0@)&mNP~cNU=?EJ7WA z5#XmgQhM}vsKehua>iszOXs65kxoRrCOTnWNJq6F z+fMYd15-NhR!E3mh`dA#f11+K>rk&qFL+Z*M_`+X7A#Kb@Ewp4%|~9M!yu(a8&F3` zFZyUo$C4hOM4P%uP;wlWMS>rnlG4AUK9G`wznRfe{Ec+ZbV{e*i#kL)`Lf8UlhgMC8-!@ZlPW@gv5CPyd6W_m}joowwI-#0eV+uOOWU-C4ES2BgV`g_$v zt&yw8OtPq0^UAT=HLclJ@7kHEJ=6VrCaxYFYmKTkzI>psZ~eg9wY}S=Oc$2s`0l>F zt?`N0kF*RGGqctkfOvsI?xvO<`RV(^%EGTMn;Al2G ztRt*<(?H*4>TqtP-xS7fqc>MzGOq_n(7Nwk)tqLsOcW(wX~ z+}O}stPBQwtj&NLVP$W@HWV~cS<;4dy(W!^C`*!lmF}*uT?ZyY%ojImwpQ^9x%mjQ z*N^3>hs;%$`^R3+Ftcu*8J``~S2%@5LE7i}Y{_yM=T>8BW!5lFt}IV;mHND7 zEG}k0bZyEk>&I-K(T#O(Qz|n~={%QVPB#`dG^;$ZS8|$W_Yza}^v<%N?YF&bsSr8F zkO@9epgO}FMe$DC-lh^?wHER@JA3k})LYJBndObm@}1^ggt7BHFGO)zbtd}yg4CJb z$W@rw>|IMmscreQ;pS^6M;xCGD_F|Uh8%;ourECuR`Hdd4LOFwG*En;w6SQEe z3ajBR>+w}!=^~8vnY<83r&(W+>NSmAX17^c6wh;Jre>!`rY1Vs zT_^2mCo9kIXUQ|3qQK%OWs_-hA9ZGsVVN1w%f@DQk55hZRtuqhtV{A8G19TO4B9QL)Kq!ntTqd^aQ)=&+1BL9SdFH& zZK%*ZPXUS*@kUKTXhl3*O)GK| zP&_f;IzBl%bE7dCA+&wnCXPQK-aS{f-(Q0#embwW1&aA*uCmiqF{Vr z6MOR-I)AERyQJTB^pvTXuNN;qXSPN?EA(L{%k95*c1(%_a0&Qs1jX>iG#VPX2%rplB`Wz!zNuP~;brM~!f;4OpWmrv6 zV+l@|I?HJ-FoeOm{$pui?RwH{j#aFKq6#ix4OPH;GtwAhQ=FYKbSi9BLmE|Z0c&XE z6^Ac+KSLTrY>KlHL#NuYkU$z$Z~<#*yL)!Dw>SH@{Zi`wuedoK)I>5^ZPJb>FakEkGQx3@Fg2XK zdJB}XS1~~=GxTi!`f|9;JRm(tmNLxc3(BGL@*vSrN!gs&j&=`~*PNaipPZFJ{{u5K zIAH6^RNsOM6GF#4J_u-^UNQ4PDXAuCA%Sz*o{74X#Wv-jQmDaC0_nh+lN6v-A0nbw z;12~BsDUu;h%A1+(_u=0xJ;jP>JzHZy!E)mG#sWlqpW$D5+YYYTG#{hm8r~^ zZ56~4oNiW@H|spGYMX#!Q#GpK0@hFk)HzJ?Q35UGMAOS#VIJbN1#o=91+1YuRUE#G zG=|s|XL+y5L#Nu4us|ABZ~<#*lb@%qiQ?u_ zk(zf%W68~t#_VcyYw(hbiv3a!lG`ikB$nFvVF`tizPKthjh!;apSIVM>s|2-p;BEgYtJ z;UZzC!xU#>Vj@+1_iXtv#b0LmFvUw&KBU^of8_Ckue|bMimxQ@FvV9MdPd3$yLooc z6<4T-i@ZGA9>EzX01Y7O#Ce z9H@DWRYM4WjAdu8dyG|23VV!YXRmXNRYL-EjAiGnb&OR{gmR38NMI57HEfLp$Xw*owj8P@*=U=Znxzrx>m$-`|gP2j1M6FB9}1kQg9 zV9`kleD%iwN6bs$M!e4A#0O9a{$BVSfD4}j*zsL}D=>rm=r;jozK=H_{3G5VfuA48 z&)0nmZ+F1&?m}7jp{xZz1God_ZTktp%_#57_W^tw<#pljdr;n^DDM%Jx8c`#djw)x zzAS;aoRYw*vl7_;bAVNg6L<`HmmZM7)87E-{~^F6{@#h%>TmpSfUCZTH+*2(N3rbf zSl8FF{B{2da5t9kL|pe{`P=>h;NbrPSoSpDn1SU-Q3ntF2r=S!_dJ9=_oHr}0l4W0 z0DGUn_TqQ9e+S!)-_67C9zbkESpM6{f5SiH*Vx8=|Ah6PmcaFx`F|$TC-Auw64-cr0#9})@a~lfoY|GYSC*sPb5VXHfuYq2Jb`sQadZOR3lsRzQK;($ z2`o4wf!QNb-eLH+=V7_$CveM)Q4V6+cx(bUW4%u=Ld=g~`~D5!`hyag(3y&=%4DuK#zu0p;KXmLg4`lfb=*@fpOp9c}e6#J>Y|aXjLD5bhvFald) z0^SE#!+YWRa3U;&9(Wtv4bOwK;g8_2;qx#He+IkZLofp$gxA8&FbyAoDfm-(HSC2y zhdpo$j@5b5w0tlegr4X^7=Q!+pKAOncvmg0AAlK~^Zd7ixN)Lp)u7}RN-BxUqPPew zyzt4U!dE42HDz^XYBiU2u9oty)od$Uv|gnmy`yX`$uhSfPx@6|)~#YT4u z?tgkET4w53vQN1c#P{2=nTjYw{tv4}t~@Qm=)p8!4OIvA)GBO1Q<;QGF1M5l_~l%w zg6h=&GMQPwd^x)`a)q8#L97{TWz6Q87Gh0_9ziIis+crJg<~#Z=ti|*`E)caSZas!#@;+BY?d8#;>Rs_eBYPQDAxoZ2=g zKjO&(C@o82it6kYTUnYA9)neg(_J@OdQWy3ixk=jJH=V3f*aLo%4DqqcJ|5hhX(At zFdN0ry+MXsGwPnH(z)-Psw~GZIyaH}Qk;}T4TdCP!gpvP7h&*B5}g&?Zm{RA7A3Yi zrfj;b!{m%9NlYn2F*_KIrMY3q7B>2LrF6Z#GZ}+pVjJT@nzNA%$m6-DQJ%AjzT_9JiclLTTCZQ_ttik0M&oQ9fTAH$RY6?vU4i zsCF~Iy>5B#Lj2yzDk)aR>3t!2*db~yGgm{V7k5z3yjHxHY zHzC7iqsU}uDq9*MTwzlKY-M@D&Y9;5K>+sgVR~w!MIH4?xELAfSQKS9qS}bO#N>#A zUMvhe&}C0S?VTk~L0MkAK2qKp+y)lmeM*#?y-uz>D6m5Wsp;bEFzSg@0^i)xi3hND zLlsf($aGObT5AUj=4uNKWu%eX?g$Z}8-x(WwZ{i3P?zYgK%+#ZO9FZ~VmxvtDoA&v zxU%vhbZ|ka{&s-7{t%{oMMBu2F43!x%M#=Cu>hxtatGHQ!I`MwJ~lN~5$b_Z?-5!a z*T_vvo>Ziv7Tu^oaJLCzVr@U7i1KSq?vj+Q^FY<^J4K8KB1MeSG#@;q@wS>mhqkKp zLWHq9GQyQk#|1&|y2=H~mxT*&j=3XCW9U+BMv?9qO(Ns zs0`F~w#v4Z>-kfhds<5JNj&d;*MS!!UC!W{J)YPcFZM8HL~!n=JpR@s&bhBNal-0D z4^(Q%48hq>qfTQKYI7AS{T?o-0H3C>F2+qe-9#%922((H?qiKcT7^6_Gv&3wq3+-9q(9NlVg<2qu9Z zC`$sBMtkV7{b(ulSbkvjL0HhE^OL0j5;{pLi5^VyJX%#WxWa>&huZT8u?(Kli@xB< zsSgjYzhu*;gG0k>1~y+XxPH^nrGvwx`zD6>buAwrnV!bKZ``tBL%9(CVSLy0Fa{S| zrz|Cowk8AGLLoqkjo~fJ+gcIHTbIKV0yh)0I$#;<0bs6fchdr4Fmw2TV9%#zv~Rl$ z*pl>IXVMsRbn8w`KdD#Wmo}*cGKB>m4+R7OWpWs8f=c$v7Jcv$yaCbAGMea-CI#%Wnb6h=R4lYk9UF>qNJ2y zA-b$q_Bs~JJ)mmpY$1apw6c{AH<#xds+3%!syugNGpzeRk-4>E=Uygo1)DX z9VsiZwuVg4Afi!9VO`hCpW1Tx1}UYh1X;E0C?^yUvug+70hE;P^RpJ`!o+%(a zR9$&E3l}C2C`{<=W@vh_MW4>0^Ae_`3yOr7P2`2xF_sdXIS>9wxxuoA%tVclw+OYX zg|mb7U`cG4w2>;|k^DlC+ci<1K}`bPQJMuRXKEf8X#|*CuE_O(YLF|A*cGYnXi=y( z!bq{YTz9k#l`ob;9)q?N2JwJ7g>loqRb|+d@rl&7D)UsAZOr-}fGgsIt zQ!$*MQws$n%l64oeDSQ!HO|B!!)2ZAL>qh(fRyKKA4PdSZv^*MCQ}u1h&o$Hafr4NNO{hR*5%19So@n^g(ekQYU!=bB5`}^ zLA)uD4V2mZEeR>pOBbq4_9|T-t#Xxa28m6S0ywIY3t9TW`K4=Ysvt5GVwQ4?-3A`q;9*C9sRTZnK!9%~=x|$K} zgVvzm?CCpHzjJu;t7^Yd_6oG8d74g*p>I%Lut;C87+SYwD;k|0J)JAMIu;jx z!@b@v8fuDYk z)Ead<9JSyO{2njZ5I;xYzwh6%@RIS7nW^1VSIjP6I(Ww74eK{voc+D<>oEL8V2A({ z?9=}U#6jYJT20V9GPP?OF~5IDl01tSD&$;P98>-i$)@)L2-sK2Z$u;0y0S9MsSGkf zyUdFG8~T0;{geHWbij)i@}GII9Y1)#b7M7}`C8K}EvIuudaKIf#bi12gysAl!b@S} z{T>F(8O_@w{-;>Zx$;kBIiHXpvfpGmb7m2B`uGF{!oJJothpXlbLp6S7%Q-8&NAj! zNM+HOr7@@e^g^#3bIaxTR1Pn4Dg02mIni((?VgNKtj6i8;g!;GdV3Y>?VvhX z>ZwhpV>#J*bcQ85SizQ;9{5j)d`{v@m{tH4;262WfQUK|9j%~XS3U+1F*Wf*4a5J9CXPu_uro4kPMh3`vnDKa&xF4(gnngu4yibjXW`%jy=|kUfoIsPm%y05v z=-i7r05n7On3cQCi24!H@fsrI7_Nk*L9Fzz-4-34pdjKrTO}ZOi?-HR8GN9ypkd|epH<@Cf?6%Bj zXA6|2gf6B9n|u#5SZm$P=%f9Lmzwbymm&fXZkSSJxDHDDTxoB%mHx6aCT_uokPKj) z?W)_dN;}7lhSN|a{q)G;sLl3tI^K~X@{EMmy2^b{!{~%;;a~I>Z$@kl!nXfY`OImX zI{7v^I~ZC$*USUQ?>4->EM8|v9}RCevrBRT>bH;Zx+h)JROa62 zJ#z7+%|7c9Q@_OIlg}+2nPq?Sf()5^syH2%_PNsLY(92PhN^ZFI<0c|-m{?@D52rp zeU{%Y7>(^|?!pXBDf1ogKHBNRV$9SwY->4eysL)c9h0hy(UcOb%#xx7x6f`!BG=tOl@9lN4a0M*~6^j z)?u%2Fybs)suIrD9y63$QPY?HxrQ}LU`1;jL|m6hT*`?<^@vdli(HH02<6mTL`biz zY_uWd`?m_B$5`RDcqxa`I#Q}2YFe$)&%72l*%0nWE!v*oUv9uyGd-rJD)-fa?Syww z!R3~DQ-`H}uI$ksxk00?I5*$q2? zh|-0dV**@FGkRxMYf3sa&F<;Fu2&N-L!w-LI~PxzL~7k&ESA0H9SoMzGJ^x->=A5l zybT-Bm@J3`qiL$Tmn@pu$zYj7%~*C$TZG0niLs^*_m!6I+4yoo6rR#JN(6xI&Bc*8 zIAzX)Io0WC39EgoF~z{piDQh}$EMSWv@LtW~wd;{{L6kKm0$w>m7xhbTq)!y^h9vll6;r}v z-Nj*b*X^9gzf5Xal?*y|S81{Y;o(iDpqWOc7qG>@O!0_4^h@*STqB;Ah(#K)APpm2 zZW@iLUSn z73=RAu=;g)B&?RGls8DMVa_U!2e9CLqXDOfPUGNg$X6+gPm()u2KfCPXPBjml}wyx z2OjO4jA(uIir&d+teR7(UJoewOx3(`uRz_tIYk@iLK6*`$Nq-}>01m)-L*Rja4y|hU`OSvqon5;aNDeceXK`ZolOH6l)ogPWE`jpR^+O&~qfjye;3Q zBM!6W{c^VRDGO#F9q$iY{&X92#0yL#csbsd|H_KkL(g>OY6Qf*E&sKSILwyg#s66R z@@FiVeRLelmTm96-`&O>8vdi1Lya}Kd^w}I^4WV*U)PCbn^|u`#BD; sN4IlsSHoWeuUz&P^-J%Ud|tsDHn7;R6^|7UkM|xkUSI8+4yNb-FMFYzh5!Hn From 4ba1b18bce1b01f0ab1dc4577757cab5d9ff6316 Mon Sep 17 00:00:00 2001 From: Honghyun Date: Tue, 25 Jul 2023 08:55:00 +0900 Subject: [PATCH 7/7] add delay after transmit --- c++/src/dynamixel_sdk/port_handler_mac.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/c++/src/dynamixel_sdk/port_handler_mac.cpp b/c++/src/dynamixel_sdk/port_handler_mac.cpp index f602d57a..bb4eef22 100644 --- a/c++/src/dynamixel_sdk/port_handler_mac.cpp +++ b/c++/src/dynamixel_sdk/port_handler_mac.cpp @@ -122,7 +122,18 @@ int PortHandlerMac::readPort(uint8_t *packet, int length) int PortHandlerMac::writePort(uint8_t *packet, int length) { - return write(socket_fd_, packet, length); + int result = write(socket_fd_, packet, length); + + // Wait Tx Done + int unsent = 1; + while (unsent > 0) { + ioctl(socket_fd_, TIOCOUTQ, &unsent); + } + unsigned int tx_time = ((float)(length * 10) / baudrate_) * 1000000000; + struct timespec delay = {0, tx_time}; + nanosleep(&delay, NULL); + + return result; } void PortHandlerMac::setPacketTimeout(uint16_t packet_length)