From 21b772ea831c8088fa922c5bc8006144b94c8d65 Mon Sep 17 00:00:00 2001 From: fgarciacardenas <47540719+fgarciacardenas@users.noreply.github.com> Date: Mon, 7 Oct 2024 15:48:35 +0200 Subject: [PATCH] Feature/release update (#71) * Corrected ODOMSH frame id * Update repository to be compatible with the new VRTK2 software * Updated README * Removed test * Corrected resolution of ROS messages --------- Co-authored-by: Facundo Garcia --- fixposition_driver_lib/CMakeLists.txt | 4 + fixposition_driver_lib/README.md | 2 +- .../messages/fpa_type.hpp | 209 +- .../include/fixposition_driver_lib/params.hpp | 1 + .../src/fixposition_driver.cpp | 8 + .../src/messages/fpa/eoe.cpp | 57 + .../src/messages/fpa/gnssant.cpp | 2 +- .../src/messages/fpa/gnsscorr.cpp | 2 +- .../src/messages/fpa/imubias.cpp | 80 + .../src/messages/fpa/llh.cpp | 2 +- .../src/messages/fpa/odomenu.cpp | 2 +- .../src/messages/fpa/odomsh.cpp | 2 +- .../src/messages/fpa/odomstatus.cpp | 111 + .../src/messages/fpa/tp.cpp | 62 + fixposition_driver_ros1/CMakeLists.txt | 5 + .../fixposition_driver_ros1/data_to_ros1.hpp | 32 +- .../fixposition_driver_node.hpp | 11 + .../fixposition_driver_ros1/ros_msgs.hpp | 10 + fixposition_driver_ros1/launch/serial.yaml | 4 +- fixposition_driver_ros1/launch/tcp.yaml | 4 +- .../msg/extras/CovWarn.msg | 18 + fixposition_driver_ros1/msg/fpa/eoe.msg | 17 + fixposition_driver_ros1/msg/fpa/gnssant.msg | 4 +- fixposition_driver_ros1/msg/fpa/gnsscorr.msg | 2 +- fixposition_driver_ros1/msg/fpa/imubias.msg | 71 + fixposition_driver_ros1/msg/fpa/llh.msg | 2 +- .../msg/fpa/odomstatus.msg | 190 + fixposition_driver_ros1/msg/fpa/tp.msg | 56 + fixposition_driver_ros1/msg/nmea/gxgsv.msg | 2 +- fixposition_driver_ros1/src/data_to_ros1.cpp | 127 + .../src/fixposition_driver_node.cpp | 36 + fixposition_driver_ros1/src/params.cpp | 6 + fixposition_driver_ros2/CMakeLists.txt | 5 + .../fixposition_driver_ros2/data_to_ros2.hpp | 33 +- .../fixposition_driver_node.hpp | 43 +- .../fixposition_driver_ros2/ros2_msgs.hpp | 10 + fixposition_driver_ros2/launch/serial.yaml | 5 +- fixposition_driver_ros2/launch/tcp.yaml | 5 +- .../msg/extras/COVWARN.msg | 15 + fixposition_driver_ros2/msg/fpa/EOE.msg | 14 + fixposition_driver_ros2/msg/fpa/GNSSANT.msg | 4 +- fixposition_driver_ros2/msg/fpa/GNSSCORR.msg | 2 +- fixposition_driver_ros2/msg/fpa/IMUBIAS.msg | 68 + fixposition_driver_ros2/msg/fpa/LLH.msg | 2 +- .../msg/fpa/ODOMSTATUS.msg | 187 + fixposition_driver_ros2/msg/fpa/TP.msg | 53 + fixposition_driver_ros2/msg/nmea/GXGSV.msg | 2 +- fixposition_driver_ros2/src/data_to_ros2.cpp | 129 + .../src/fixposition_driver_node.cpp | 36 + fixposition_driver_ros2/src/params.cpp | 7 + test/HowToTest.md | 177 - test/TestData_example.png | Bin 34455 -> 0 bytes test/data/vrtk2_output_1.txt | 101076 --------------- test/data/vrtk2_output_1.txt.tag | Bin 240680 -> 0 bytes 54 files changed, 1703 insertions(+), 101311 deletions(-) create mode 100644 fixposition_driver_lib/src/messages/fpa/eoe.cpp create mode 100644 fixposition_driver_lib/src/messages/fpa/imubias.cpp create mode 100644 fixposition_driver_lib/src/messages/fpa/odomstatus.cpp create mode 100644 fixposition_driver_lib/src/messages/fpa/tp.cpp create mode 100644 fixposition_driver_ros1/msg/extras/CovWarn.msg create mode 100644 fixposition_driver_ros1/msg/fpa/eoe.msg create mode 100644 fixposition_driver_ros1/msg/fpa/imubias.msg create mode 100644 fixposition_driver_ros1/msg/fpa/odomstatus.msg create mode 100644 fixposition_driver_ros1/msg/fpa/tp.msg create mode 100644 fixposition_driver_ros2/msg/extras/COVWARN.msg create mode 100644 fixposition_driver_ros2/msg/fpa/EOE.msg create mode 100644 fixposition_driver_ros2/msg/fpa/IMUBIAS.msg create mode 100644 fixposition_driver_ros2/msg/fpa/ODOMSTATUS.msg create mode 100644 fixposition_driver_ros2/msg/fpa/TP.msg delete mode 100644 test/HowToTest.md delete mode 100644 test/TestData_example.png delete mode 100644 test/data/vrtk2_output_1.txt delete mode 100644 test/data/vrtk2_output_1.txt.tag diff --git a/fixposition_driver_lib/CMakeLists.txt b/fixposition_driver_lib/CMakeLists.txt index 9fe0c2d..88fb4c6 100644 --- a/fixposition_driver_lib/CMakeLists.txt +++ b/fixposition_driver_lib/CMakeLists.txt @@ -21,15 +21,19 @@ include_directories(include add_library( ${PROJECT_NAME} SHARED src/messages/fpa/corrimu.cpp + src/messages/fpa/eoe.cpp src/messages/fpa/gnssant.cpp src/messages/fpa/gnsscorr.cpp + src/messages/fpa/imubias.cpp src/messages/fpa/llh.cpp src/messages/fpa/odomenu.cpp src/messages/fpa/odometry.cpp src/messages/fpa/odomsh.cpp + src/messages/fpa/odomstatus.cpp src/messages/fpa/rawimu.cpp src/messages/fpa/text.cpp src/messages/fpa/tf.cpp + src/messages/fpa/tp.cpp src/messages/nmea/gpgga.cpp src/messages/nmea/gpgll.cpp src/messages/nmea/gngsa.cpp diff --git a/fixposition_driver_lib/README.md b/fixposition_driver_lib/README.md index 077068b..354b9bc 100644 --- a/fixposition_driver_lib/README.md +++ b/fixposition_driver_lib/README.md @@ -1,6 +1,6 @@ # Fixposition Driver Lib -This is a CMake library used to parse [Fixposition ASCII messages](../README.md#fixposition-ascii-messages). The message content will be converted into a generic struct and can be processed further from there. +This is a CMake library used to parse [Fixposition ASCII messages](https://docs.fixposition.com/fd/i-o-messages). The message content will be converted into a generic struct and can be processed further from there. It can be built using plain CMake, or using catkin or colcon depending on which ROS version is used. diff --git a/fixposition_driver_lib/include/fixposition_driver_lib/messages/fpa_type.hpp b/fixposition_driver_lib/include/fixposition_driver_lib/messages/fpa_type.hpp index bbaaeb2..59609f3 100644 --- a/fixposition_driver_lib/include/fixposition_driver_lib/messages/fpa_type.hpp +++ b/fixposition_driver_lib/include/fixposition_driver_lib/messages/fpa_type.hpp @@ -180,6 +180,90 @@ struct FP_ODOMSH { } }; +// ------------ FP_A-ODOMSTATUS ------------ + +struct FP_ODOMSTATUS { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + // Message fields + times::GpsTime stamp; + int init_status; + int fusion_imu; + int fusion_gnss1; + int fusion_gnss2; + int fusion_corr; + int fusion_cam1; + int fusion_ws; + int fusion_markers; + int imu_status; + int imu_noise; + int imu_conv; + int gnss1_status; + int gnss2_status; + int baseline_status; + int corr_status; + int cam1_status; + int ws_status; + int ws_conv; + int markers_status; + int markers_conv; + + // Message structure + const std::string header_ = "ODOMSTATUS"; + static constexpr unsigned int kVersion_ = 1; + static constexpr unsigned int kSize_ = 41; + + FP_ODOMSTATUS() { + stamp = fixposition::times::GpsTime(); + init_status = -1; + fusion_imu = -1; + fusion_gnss1 = -1; + fusion_gnss2 = -1; + fusion_corr = -1; + fusion_cam1 = -1; + fusion_ws = -1; + fusion_markers = -1; + imu_status = -1; + imu_noise = -1; + imu_conv = -1; + gnss1_status = -1; + gnss2_status = -1; + baseline_status = -1; + corr_status = -1; + cam1_status = -1; + ws_status = -1; + ws_conv = -1; + markers_status = -1; + markers_conv = -1; + } + + void ConvertFromTokens(const std::vector& tokens); + + void ResetData() { + stamp = fixposition::times::GpsTime(); + init_status = -1; + fusion_imu = -1; + fusion_gnss1 = -1; + fusion_gnss2 = -1; + fusion_corr = -1; + fusion_cam1 = -1; + fusion_ws = -1; + fusion_markers = -1; + imu_status = -1; + imu_noise = -1; + imu_conv = -1; + gnss1_status = -1; + gnss2_status = -1; + baseline_status = -1; + corr_status = -1; + cam1_status = -1; + ws_status = -1; + ws_conv = -1; + markers_status = -1; + markers_conv = -1; + } +}; + // ------------ FP_A-LLH ------------ struct FP_LLH { @@ -277,6 +361,57 @@ struct FP_RAWIMU { } }; +// ------------ FP_A-IMUBIAS ------------ + +struct FP_IMUBIAS { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + // Message fields + times::GpsTime stamp; + std::string frame_id; + int fusion_imu; + int imu_status; + int imu_noise; + int imu_conv; + Eigen::Vector3d bias_acc; + Eigen::Vector3d bias_gyr; + Eigen::Vector3d bias_cov_acc; + Eigen::Vector3d bias_cov_gyr; + + // Message structure + const std::string header_ = "IMUBIAS"; + static constexpr unsigned int kVersion_ = 1; + static constexpr unsigned int kSize_ = 21; + + FP_IMUBIAS() { + stamp = fixposition::times::GpsTime(); + frame_id = ""; + fusion_imu = -1; + imu_status = -1; + imu_noise = -1; + imu_conv = -1; + bias_acc.setZero(); + bias_gyr.setZero(); + bias_cov_acc.setZero(); + bias_cov_gyr.setZero(); + } + + void ConvertFromTokens(const std::vector& tokens); + + void ResetData() { + stamp = fixposition::times::GpsTime(); + frame_id = ""; + fusion_imu = -1; + imu_status = -1; + imu_noise = -1; + imu_conv = -1; + bias_acc.setZero(); + bias_gyr.setZero(); + bias_cov_acc.setZero(); + bias_cov_gyr.setZero(); + } +}; + // ------------ FP_A-CORRIMU ------------ struct FP_CORRIMU { @@ -362,10 +497,10 @@ struct FP_GNSSCORR { int gnss2_fix; int gnss2_nsig_l1; int gnss2_nsig_l2; - float corr_latency; - float corr_update_rate; - float corr_data_rate; - float corr_msg_rate; + double corr_latency; + double corr_update_rate; + double corr_data_rate; + double corr_msg_rate; int sta_id; Eigen::Vector3d sta_llh; int sta_dist; @@ -439,5 +574,71 @@ struct FP_TEXT { } }; +// ------------ FP_A-EOE ------------ + +struct FP_EOE { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + // Message fields + times::GpsTime stamp; + std::string epoch; + + // Message structure + const std::string header_ = "EOE"; + static constexpr unsigned int kVersion_ = 1; + static constexpr unsigned int kSize_ = 6; + + FP_EOE() { + stamp = fixposition::times::GpsTime(); + epoch = ""; + } + + void ConvertFromTokens(const std::vector& tokens); + + void ResetData() { + stamp = fixposition::times::GpsTime(); + epoch = ""; + } +}; + +// ------------ FP_A-TP ------------ + +struct FP_TP { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + // Message fields + std::string tp_name; + std::string timebase; + std::string timeref; + int tp_tow_sec; + double tp_tow_psec; + int gps_leaps; + + // Message structure + const std::string header_ = "TP"; + static constexpr unsigned int kVersion_ = 1; + static constexpr unsigned int kSize_ = 9; + + FP_TP() { + tp_name = ""; + timebase = ""; + timeref = ""; + tp_tow_sec = 0; + tp_tow_psec = 0.0; + gps_leaps = 0; + } + + void ConvertFromTokens(const std::vector& tokens); + + void ResetData() { + tp_name = ""; + timebase = ""; + timeref = ""; + tp_tow_sec = 0; + tp_tow_psec = 0.0; + gps_leaps = 0; + } +}; + } // namespace fixposition #endif // __FIXPOSITION_DRIVER_LIB_CONVERTER_FPA_TYPE__ diff --git a/fixposition_driver_lib/include/fixposition_driver_lib/params.hpp b/fixposition_driver_lib/include/fixposition_driver_lib/params.hpp index 7cc1c72..2fd0b55 100644 --- a/fixposition_driver_lib/include/fixposition_driver_lib/params.hpp +++ b/fixposition_driver_lib/include/fixposition_driver_lib/params.hpp @@ -29,6 +29,7 @@ struct FpOutputParams { INPUT_TYPE type; //!< TCP or SERIAL std::vector formats; //!< data formats to convert, supports "FP" for now std::string qos_type; //!< ROS QoS type, supports "sensor_" and "default_" + bool cov_warning; //!< enable/disable covariance warning std::string ip; //!< IP address for TCP connection std::string port; //!< Port for TCP connection diff --git a/fixposition_driver_lib/src/fixposition_driver.cpp b/fixposition_driver_lib/src/fixposition_driver.cpp index e11aace..92da33d 100644 --- a/fixposition_driver_lib/src/fixposition_driver.cpp +++ b/fixposition_driver_lib/src/fixposition_driver.cpp @@ -198,20 +198,28 @@ bool FixpositionDriver::InitializeConverters() { a_converters_["ODOMENU"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "ODOMSH") { a_converters_["ODOMSH"] = std::unique_ptr>(new NmeaConverter()); + } else if (format == "ODOMSTATUS") { + a_converters_["ODOMSTATUS"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "LLH") { a_converters_["LLH"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "TF") { a_converters_["TF"] = std::unique_ptr>(new NmeaConverter()); + } else if (format == "TP") { + a_converters_["TP"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "RAWIMU") { a_converters_["RAWIMU"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "CORRIMU") { a_converters_["CORRIMU"] = std::unique_ptr>(new NmeaConverter()); + } else if (format == "IMUBIAS") { + a_converters_["IMUBIAS"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "GNSSANT") { a_converters_["GNSSANT"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "GNSSCORR") { a_converters_["GNSSCORR"] = std::unique_ptr>(new NmeaConverter()); } else if (format == "TEXT") { a_converters_["TEXT"] = std::unique_ptr>(new NmeaConverter()); + } else if (format == "EOE") { + a_converters_["EOE"] = std::unique_ptr>(new NmeaConverter()); // NMEA messages } else if (format == "GPGGA") { diff --git a/fixposition_driver_lib/src/messages/fpa/eoe.cpp b/fixposition_driver_lib/src/messages/fpa/eoe.cpp new file mode 100644 index 0000000..e1bda7f --- /dev/null +++ b/fixposition_driver_lib/src/messages/fpa/eoe.cpp @@ -0,0 +1,57 @@ +/** + * @file + * @brief Implementation of FP_A-EOE parser + * + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Fixposition AG + * / /\ \ All right reserved. + * /__/ \__\ + * \endverbatim + * + */ + +/* PACKAGE */ +#include +#include + +namespace fixposition { + +/// msg field indices +static constexpr int msg_type_idx = 1; +static constexpr int msg_version_idx = 2; +static constexpr int gps_week_idx = 3; +static constexpr int gps_tow_idx = 4; +static constexpr int epoch_idx = 5; + +void FP_EOE::ConvertFromTokens(const std::vector& tokens) { + bool ok = tokens.size() == kSize_; + if (!ok) { + // Size is wrong + std::cout << "Error in parsing FP_A-EOE string with " << tokens.size() << " fields!\n"; + } else { + // If size is ok, check version + const int _version = std::stoi(tokens.at(msg_version_idx)); + + ok = _version == kVersion_; + if (!ok) { + // Version is wrong + std::cout << "Error in parsing FP_A-EOE string with version " << _version << "!\n"; + } + } + + if (!ok) { + // Reset message and return + ResetData(); + return; + } + + // Parse time + stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); + + // Populate fields + epoch = tokens.at(epoch_idx); +} + +} // namespace fixposition diff --git a/fixposition_driver_lib/src/messages/fpa/gnssant.cpp b/fixposition_driver_lib/src/messages/fpa/gnssant.cpp index ca83ff1..cb07c17 100644 --- a/fixposition_driver_lib/src/messages/fpa/gnssant.cpp +++ b/fixposition_driver_lib/src/messages/fpa/gnssant.cpp @@ -53,7 +53,7 @@ void FP_GNSSANT::ConvertFromTokens(const std::vector& tokens) { } // Populate VRTK message header - stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx));; + stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); // GNSS status data gnss1_state = tokens.at(gnss1_state_idx); diff --git a/fixposition_driver_lib/src/messages/fpa/gnsscorr.cpp b/fixposition_driver_lib/src/messages/fpa/gnsscorr.cpp index 94ad77d..1d8a06d 100644 --- a/fixposition_driver_lib/src/messages/fpa/gnsscorr.cpp +++ b/fixposition_driver_lib/src/messages/fpa/gnsscorr.cpp @@ -62,7 +62,7 @@ void FP_GNSSCORR::ConvertFromTokens(const std::vector& tokens) { } // Populate VRTK message header - stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx));; + stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); // GNSS status data gnss1_fix = ParseStatusFlag(tokens, gnss1_fix_idx); diff --git a/fixposition_driver_lib/src/messages/fpa/imubias.cpp b/fixposition_driver_lib/src/messages/fpa/imubias.cpp new file mode 100644 index 0000000..66c4ad0 --- /dev/null +++ b/fixposition_driver_lib/src/messages/fpa/imubias.cpp @@ -0,0 +1,80 @@ +/** + * @file + * @brief Implementation of FP_A-IMUBIAS parser + * + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Fixposition AG + * / /\ \ All right reserved. + * /__/ \__\ + * \endverbatim + * + */ + +/* PACKAGE */ +#include +#include + +namespace fixposition { + +/// msg field indices +static constexpr int msg_type_idx = 1; +static constexpr int msg_version_idx = 2; +static constexpr int gps_week_idx = 3; +static constexpr int gps_tow_idx = 4; +static constexpr int fusion_imu_idx = 5; +static constexpr int imu_status_idx = 6; +static constexpr int imu_noise_idx = 7; +static constexpr int imu_conv_idx = 8; +static constexpr int bias_acc_x_idx = 9; +static constexpr int bias_acc_y_idx = 10; +static constexpr int bias_acc_z_idx = 11; +static constexpr int bias_gyr_x_idx = 12; +static constexpr int bias_gyr_y_idx = 13; +static constexpr int bias_gyr_z_idx = 14; +static constexpr int bias_cov_acc_x_idx = 15; +static constexpr int bias_cov_acc_y_idx = 16; +static constexpr int bias_cov_acc_z_idx = 17; +static constexpr int bias_cov_gyr_x_idx = 18; +static constexpr int bias_cov_gyr_y_idx = 19; +static constexpr int bias_cov_gyr_z_idx = 20; + +void FP_IMUBIAS::ConvertFromTokens(const std::vector& tokens) { + bool ok = tokens.size() == kSize_; + if (!ok) { + // Size is wrong + std::cout << "Error in parsing FP_A-IMUBIAS string with " << tokens.size() << " fields!\n"; + } else { + // If size is ok, check version + const int _version = std::stoi(tokens.at(msg_version_idx)); + + ok = _version == kVersion_; + if (!ok) { + // Version is wrong + std::cout << "Error in parsing FP_A-IMUBIAS string with version " << _version << "!\n"; + } + } + + if (!ok) { + // Reset message and return + ResetData(); + return; + } + + // Parse time + stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); + + // Populate fields + frame_id = "FP_VRTK"; + fusion_imu = ParseStatusFlag(tokens, fusion_imu_idx); + imu_status = ParseStatusFlag(tokens, imu_status_idx); + imu_noise = ParseStatusFlag(tokens, imu_noise_idx); + imu_conv = ParseStatusFlag(tokens, imu_conv_idx); + bias_acc = Vector3ToEigen(tokens.at(bias_acc_x_idx), tokens.at(bias_acc_y_idx), tokens.at(bias_acc_z_idx)); + bias_gyr = Vector3ToEigen(tokens.at(bias_gyr_x_idx), tokens.at(bias_gyr_y_idx), tokens.at(bias_gyr_z_idx)); + bias_cov_acc = Vector3ToEigen(tokens.at(bias_cov_acc_x_idx), tokens.at(bias_cov_acc_y_idx), tokens.at(bias_cov_acc_z_idx)); + bias_cov_gyr = Vector3ToEigen(tokens.at(bias_cov_gyr_x_idx), tokens.at(bias_cov_gyr_y_idx), tokens.at(bias_cov_gyr_z_idx)); +} + +} // namespace fixposition diff --git a/fixposition_driver_lib/src/messages/fpa/llh.cpp b/fixposition_driver_lib/src/messages/fpa/llh.cpp index 220b77a..6766799 100644 --- a/fixposition_driver_lib/src/messages/fpa/llh.cpp +++ b/fixposition_driver_lib/src/messages/fpa/llh.cpp @@ -56,7 +56,7 @@ void FP_LLH::ConvertFromTokens(const std::vector& tokens) { } // Populate VRTK message header - stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx));; + stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); // LLH position llh = Vector3ToEigen(tokens.at(latitude_idx), tokens.at(longitude_idx), tokens.at(height_idx)); diff --git a/fixposition_driver_lib/src/messages/fpa/odomenu.cpp b/fixposition_driver_lib/src/messages/fpa/odomenu.cpp index 99d5e44..8aa45c8 100644 --- a/fixposition_driver_lib/src/messages/fpa/odomenu.cpp +++ b/fixposition_driver_lib/src/messages/fpa/odomenu.cpp @@ -94,7 +94,7 @@ void FP_ODOMENU::ConvertFromTokens(const std::vector& tokens) { if (fusion_status >= static_cast(FusionStatus::INERTIAL_GNSS_FUSION)) { // Message header - odom.stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx));; + odom.stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); // Pose & Cov odom.pose.position = Vector3ToEigen(tokens.at(pos_x_idx), tokens.at(pos_y_idx), tokens.at(pos_z_idx)); diff --git a/fixposition_driver_lib/src/messages/fpa/odomsh.cpp b/fixposition_driver_lib/src/messages/fpa/odomsh.cpp index ae2eb04..d3a151e 100644 --- a/fixposition_driver_lib/src/messages/fpa/odomsh.cpp +++ b/fixposition_driver_lib/src/messages/fpa/odomsh.cpp @@ -94,7 +94,7 @@ void FP_ODOMSH::ConvertFromTokens(const std::vector& tokens) { if (fusion_status >= static_cast(FusionStatus::INERTIAL_GNSS_FUSION)) { // Message header - odom.stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx));; + odom.stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); // Pose & Cov odom.pose.position = Vector3ToEigen(tokens.at(pos_x_idx), tokens.at(pos_y_idx), tokens.at(pos_z_idx)); diff --git a/fixposition_driver_lib/src/messages/fpa/odomstatus.cpp b/fixposition_driver_lib/src/messages/fpa/odomstatus.cpp new file mode 100644 index 0000000..0baa931 --- /dev/null +++ b/fixposition_driver_lib/src/messages/fpa/odomstatus.cpp @@ -0,0 +1,111 @@ +/** + * @file + * @brief Implementation of FP_A-ODOMSTATUS parser + * + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Fixposition AG + * / /\ \ All right reserved. + * /__/ \__\ + * \endverbatim + * + */ + +/* PACKAGE */ +#include +#include + +namespace fixposition { + +/// msg field indices +static constexpr int msg_type_idx = 1; +static constexpr int msg_version_idx = 2; +static constexpr int gps_week_idx = 3; +static constexpr int gps_tow_idx = 4; +static constexpr int init_status_idx = 5; +static constexpr int fusion_imu_idx = 6; +static constexpr int fusion_gnss1_idx = 7; +static constexpr int fusion_gnss2_idx = 8; +static constexpr int fusion_corr_idx = 9; +static constexpr int fusion_cam1_idx = 10; +static constexpr int reserved0_idx = 11; +static constexpr int fusion_ws_idx = 12; +static constexpr int fusion_markers_idx = 13; +static constexpr int reserved1_idx = 14; +static constexpr int reserved2_idx = 15; +static constexpr int reserved3_idx = 16; +static constexpr int reserved4_idx = 17; +static constexpr int imu_status_idx = 18; +static constexpr int imu_noise_idx = 19; +static constexpr int imu_conv_idx = 20; +static constexpr int gnss1_status_idx = 21; +static constexpr int gnss2_status_idx = 22; +static constexpr int baseline_status_idx = 23; +static constexpr int corr_status_idx = 24; +static constexpr int cam1_status_idx = 25; +static constexpr int reserved5_idx = 26; +static constexpr int ws_status_idx = 27; +static constexpr int ws_conv_idx = 28; +static constexpr int markers_status_idx = 29; +static constexpr int markers_conv_idx = 30; +static constexpr int reserved6_idx = 31; +static constexpr int reserved7_idx = 32; +static constexpr int reserved8_idx = 33; +static constexpr int reserved9_idx = 34; +static constexpr int reserved10_idx = 35; +static constexpr int reserved11_idx = 36; +static constexpr int reserved12_idx = 37; +static constexpr int reserved13_idx = 38; +static constexpr int reserved14_idx = 39; +static constexpr int reserved15_idx = 40; + +void FP_ODOMSTATUS::ConvertFromTokens(const std::vector& tokens) { + bool ok = tokens.size() == kSize_; + if (!ok) { + // Size is wrong + std::cout << "Error in parsing FP_A-ODOMSTATUS string with " << tokens.size() << " fields!\n"; + } else { + // If size is ok, check version + const int _version = std::stoi(tokens.at(msg_version_idx)); + + ok = _version == kVersion_; + if (!ok) { + // Version is wrong + std::cout << "Error in parsing FP_A-ODOMSTATUS string with version " << _version << "!\n"; + } + } + + if (!ok) { + // Reset message and return + ResetData(); + return; + } + + // Parse time + stamp = ConvertGpsTime(tokens.at(gps_week_idx), tokens.at(gps_tow_idx)); + + // Populate fields + init_status = ParseStatusFlag(tokens, init_status_idx); + fusion_imu = ParseStatusFlag(tokens, fusion_imu_idx); + fusion_gnss1 = ParseStatusFlag(tokens, fusion_gnss1_idx); + fusion_gnss2 = ParseStatusFlag(tokens, fusion_gnss2_idx); + fusion_corr = ParseStatusFlag(tokens, fusion_corr_idx); + fusion_cam1 = ParseStatusFlag(tokens, fusion_cam1_idx); + fusion_ws = ParseStatusFlag(tokens, fusion_ws_idx); + fusion_markers = ParseStatusFlag(tokens, fusion_markers_idx); + imu_status = ParseStatusFlag(tokens, imu_status_idx); + imu_noise = ParseStatusFlag(tokens, imu_noise_idx); + imu_conv = ParseStatusFlag(tokens, imu_conv_idx); + gnss1_status = ParseStatusFlag(tokens, gnss1_status_idx); + gnss2_status = ParseStatusFlag(tokens, gnss2_status_idx); + baseline_status = ParseStatusFlag(tokens, baseline_status_idx); + corr_status = ParseStatusFlag(tokens, corr_status_idx); + cam1_status = ParseStatusFlag(tokens, cam1_status_idx); + ws_status = ParseStatusFlag(tokens, ws_status_idx); + ws_conv = ParseStatusFlag(tokens, ws_conv_idx); + markers_status = ParseStatusFlag(tokens, markers_status_idx); + markers_conv = ParseStatusFlag(tokens, markers_conv_idx); +} + +} // namespace fixposition diff --git a/fixposition_driver_lib/src/messages/fpa/tp.cpp b/fixposition_driver_lib/src/messages/fpa/tp.cpp new file mode 100644 index 0000000..af29cfd --- /dev/null +++ b/fixposition_driver_lib/src/messages/fpa/tp.cpp @@ -0,0 +1,62 @@ +/** + * @file + * @brief Implementation of FP_A-TP parser + * + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Fixposition AG + * / /\ \ All right reserved. + * /__/ \__\ + * \endverbatim + * + */ + +/* PACKAGE */ +#include +#include + +namespace fixposition { + +/// msg field indices +static constexpr int msg_type_idx = 1; +static constexpr int msg_version_idx = 2; +static constexpr int tp_name_idx = 3; +static constexpr int timebase_idx = 4; +static constexpr int timeref_idx = 5; +static constexpr int tp_tow_sec_idx = 6; +static constexpr int tp_tow_psec_idx = 7; +static constexpr int gps_leaps_idx = 8; + +void FP_TP::ConvertFromTokens(const std::vector& tokens) { + bool ok = tokens.size() == kSize_; + if (!ok) { + // Size is wrong + std::cout << "Error in parsing FP_A-TP string with " << tokens.size() << " fields!\n"; + } else { + // If size is ok, check version + const int _version = std::stoi(tokens.at(msg_version_idx)); + + ok = _version == kVersion_; + if (!ok) { + // Version is wrong + std::cout << "Error in parsing FP_A-TP string with version " << _version << "!\n"; + } + } + + if (!ok) { + // Reset message and return + ResetData(); + return; + } + + // Populate fields + tp_name = tokens.at(tp_name_idx); + timebase = tokens.at(timebase_idx); + timeref = tokens.at(timeref_idx); + tp_tow_sec = StringToInt(tokens.at(tp_tow_sec_idx)); + tp_tow_psec = StringToDouble(tokens.at(tp_tow_psec_idx)); + gps_leaps = StringToInt(tokens.at(gps_leaps_idx)); +} + +} // namespace fixposition diff --git a/fixposition_driver_ros1/CMakeLists.txt b/fixposition_driver_ros1/CMakeLists.txt index 09f643f..339805b 100644 --- a/fixposition_driver_ros1/CMakeLists.txt +++ b/fixposition_driver_ros1/CMakeLists.txt @@ -28,13 +28,17 @@ add_message_files( WheelSensor.msg GnssSats.msg NMEA.msg + fpa/eoe.msg fpa/gnssant.msg fpa/gnsscorr.msg + fpa/imubias.msg fpa/llh.msg fpa/odomenu.msg fpa/odometry.msg fpa/odomsh.msg + fpa/odomstatus.msg fpa/text.msg + fpa/tp.msg nmea/gpgga.msg nmea/gpgll.msg nmea/gngsa.msg @@ -44,6 +48,7 @@ add_message_files( nmea/gprmc.msg nmea/gpvtg.msg nmea/gpzda.msg + extras/CovWarn.msg ) generate_messages( diff --git a/fixposition_driver_ros1/include/fixposition_driver_ros1/data_to_ros1.hpp b/fixposition_driver_ros1/include/fixposition_driver_ros1/data_to_ros1.hpp index 847644f..1ad082b 100644 --- a/fixposition_driver_ros1/include/fixposition_driver_ros1/data_to_ros1.hpp +++ b/fixposition_driver_ros1/include/fixposition_driver_ros1/data_to_ros1.hpp @@ -30,15 +30,19 @@ namespace fixposition { * @param[in] data * @param[out] msg */ -void FpToRosMsg(const OdometryData& data, ros::Publisher& pub); -void FpToRosMsg( const ImuData& data, ros::Publisher& pub); -void FpToRosMsg( const FP_GNSSANT& data, ros::Publisher& pub); -void FpToRosMsg( const FP_GNSSCORR& data, ros::Publisher& pub); -void FpToRosMsg( const FP_LLH& data, ros::Publisher& pub); -void FpToRosMsg( const FP_ODOMENU& data, ros::Publisher& pub); -void FpToRosMsg( const FP_ODOMETRY& data, ros::Publisher& pub); -void FpToRosMsg( const FP_ODOMSH& data, ros::Publisher& pub); -void FpToRosMsg( const FP_TEXT& data, ros::Publisher& pub); +void FpToRosMsg( const OdometryData& data, ros::Publisher& pub); +void FpToRosMsg( const ImuData& data, ros::Publisher& pub); +void FpToRosMsg( const FP_EOE& data, ros::Publisher& pub); +void FpToRosMsg( const FP_GNSSANT& data, ros::Publisher& pub); +void FpToRosMsg( const FP_GNSSCORR& data, ros::Publisher& pub); +void FpToRosMsg( const FP_IMUBIAS& data, ros::Publisher& pub); +void FpToRosMsg( const FP_LLH& data, ros::Publisher& pub); +void FpToRosMsg( const FP_ODOMENU& data, ros::Publisher& pub); +void FpToRosMsg( const FP_ODOMETRY& data, ros::Publisher& pub); +void FpToRosMsg( const FP_ODOMSH& data, ros::Publisher& pub); +void FpToRosMsg(const FP_ODOMSTATUS& data, ros::Publisher& pub); +void FpToRosMsg( const FP_TP& data, ros::Publisher& pub); +void FpToRosMsg( const FP_TEXT& data, ros::Publisher& pub); void FpToRosMsg(const GP_GGA& data, ros::Publisher& pub); void FpToRosMsg(const GP_GLL& data, ros::Publisher& pub); @@ -114,6 +118,16 @@ void OdomToImuMsg(const FP_ODOMETRY& data, ros::Publisher& pub); */ void OdomToYprMsg(const OdometryData& data, ros::Publisher& pub); +/** + * @brief + * + * @param[in] stamp + * @param[in] pos_diff + * @param[in] prev_cov + * @param[out] msg + */ +void JumpWarningMsg(const times::GpsTime& stamp, const Eigen::Vector3d& pos_diff, const Eigen::MatrixXd& prev_cov, ros::Publisher& pub); + } // namespace fixposition #endif diff --git a/fixposition_driver_ros1/include/fixposition_driver_ros1/fixposition_driver_node.hpp b/fixposition_driver_ros1/include/fixposition_driver_ros1/fixposition_driver_node.hpp index 1264956..87dd17f 100644 --- a/fixposition_driver_ros1/include/fixposition_driver_ros1/fixposition_driver_node.hpp +++ b/fixposition_driver_ros1/include/fixposition_driver_ros1/fixposition_driver_node.hpp @@ -73,12 +73,16 @@ class FixpositionDriverNode : public FixpositionDriver { // ROS publishers // FP_A messages ros::Publisher fpa_odometry_pub_; //!< FP_A-ODOMETRY message + ros::Publisher fpa_imubias_pub_; //!< FP_A-IMUBIAS message + ros::Publisher fpa_eoe_pub_; //!< FP_A-EOE message ros::Publisher fpa_llh_pub_; //!< FP_A-LLH message ros::Publisher fpa_odomenu_pub_; //!< FP_A-ODOMENU message ros::Publisher fpa_odomsh_pub_; //!< FP_A-ODOMSH message + ros::Publisher fpa_odomstatus_pub_; //!< FP_A-ODOMSTATUS message ros::Publisher fpa_gnssant_pub_; //!< FP_A-GNSSANT message ros::Publisher fpa_gnsscorr_pub_; //!< FP_A-GNSSCORR message ros::Publisher fpa_text_pub_; //!< FP_A-TEXT message + ros::Publisher fpa_tp_pub_; //!< FP_A-TP message // NMEA messages ros::Publisher nmea_gpgga_pub_; //!< NMEA-GP-GGA message @@ -115,6 +119,13 @@ class FixpositionDriverNode : public FixpositionDriver { // TF tf2_ros::TransformBroadcaster br_; tf2_ros::StaticTransformBroadcaster static_br_; + + // Jump warning topic + ros::Publisher extras_jump_pub_; //!< Jump warning topic + + // Previous state + Eigen::Vector3d prev_pos; + Eigen::MatrixXd prev_cov; }; } // namespace fixposition diff --git a/fixposition_driver_ros1/include/fixposition_driver_ros1/ros_msgs.hpp b/fixposition_driver_ros1/include/fixposition_driver_ros1/ros_msgs.hpp index cb01418..89a7356 100644 --- a/fixposition_driver_ros1/include/fixposition_driver_ros1/ros_msgs.hpp +++ b/fixposition_driver_ros1/include/fixposition_driver_ros1/ros_msgs.hpp @@ -23,18 +23,28 @@ #include #include +// Include generic #include #include #include +// Include extras +#include + +// Include FP-A #include #include +#include +#include #include #include #include #include +#include #include +#include +// Include NMEA #include #include #include diff --git a/fixposition_driver_ros1/launch/serial.yaml b/fixposition_driver_ros1/launch/serial.yaml index 07e135a..d077a1d 100644 --- a/fixposition_driver_ros1/launch/serial.yaml +++ b/fixposition_driver_ros1/launch/serial.yaml @@ -1,6 +1,7 @@ fp_output: formats: [ - "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "RAWIMU", "CORRIMU", "GNSSANT", "GNSSCORR", "TEXT", "TF", # FP_A + "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "ODOMSTATUS", "RAWIMU", "CORRIMU", + "IMUBIAS", "GNSSANT", "GNSSCORR", "EOE", "TEXT", "TF", "TP", # FP_A "GPGGA", "GPGLL", "GNGSA", "GPGST", "GPHDT", "GPRMC", "GPVTG", "GPZDA", "GXGSV" # NMEA ] type: serial @@ -8,6 +9,7 @@ fp_output: serial_baudrate: 115200 rate: 200 reconnect_delay: 5.0 # wait time in [s] until retry connection + cov_warning: false customer_input: speed_topic: "/fixposition/speed" diff --git a/fixposition_driver_ros1/launch/tcp.yaml b/fixposition_driver_ros1/launch/tcp.yaml index f828200..7073945 100644 --- a/fixposition_driver_ros1/launch/tcp.yaml +++ b/fixposition_driver_ros1/launch/tcp.yaml @@ -1,6 +1,7 @@ fp_output: formats: [ - "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "RAWIMU", "CORRIMU", "GNSSANT", "GNSSCORR", "TEXT", "TF", # FP_A + "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "ODOMSTATUS", "RAWIMU", "CORRIMU", + "IMUBIAS", "GNSSANT", "GNSSCORR", "EOE", "TEXT", "TF", "TP", # FP_A "GPGGA", "GPGLL", "GNGSA", "GPGST", "GPHDT", "GPRMC", "GPVTG", "GPZDA", "GXGSV" # NMEA ] type: tcp @@ -8,6 +9,7 @@ fp_output: ip: "10.0.2.1" # change to VRTK2's IP address in the network rate: 200 reconnect_delay: 5.0 # wait time in [s] until retry connection + cov_warning: false customer_input: speed_topic: "/fixposition/speed" diff --git a/fixposition_driver_ros1/msg/extras/CovWarn.msg b/fixposition_driver_ros1/msg/extras/CovWarn.msg new file mode 100644 index 0000000..3517ad8 --- /dev/null +++ b/fixposition_driver_ros1/msg/extras/CovWarn.msg @@ -0,0 +1,18 @@ +#################################################################################################### +# +# Copyright (c) 2023 ___ ___ +# \\ \\ / / +# \\ \\/ / +# / /\\ \\ +# /__/ \\__\\ Fixposition AG +# +#################################################################################################### +# +# Fixposition Covariance Warning Message +# +# +#################################################################################################### + +Header header +geometry_msgs/Vector3 jump # Position change +geometry_msgs/Vector3 covariance # Covariance diff --git a/fixposition_driver_ros1/msg/fpa/eoe.msg b/fixposition_driver_ros1/msg/fpa/eoe.msg new file mode 100644 index 0000000..f2a1f78 --- /dev/null +++ b/fixposition_driver_ros1/msg/fpa/eoe.msg @@ -0,0 +1,17 @@ +#################################################################################################### +# +# Copyright (c) 2023 ___ ___ +# \\ \\ / / +# \\ \\/ / +# / /\\ \\ +# /__/ \\__\\ Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-EOE Message +# +# +#################################################################################################### + +Header header +string epoch # Indicates which epoch ended (FUSION, GNSS, GNSS1 or GNSS2) diff --git a/fixposition_driver_ros1/msg/fpa/gnssant.msg b/fixposition_driver_ros1/msg/fpa/gnssant.msg index 2ca1a15..37809f7 100644 --- a/fixposition_driver_ros1/msg/fpa/gnssant.msg +++ b/fixposition_driver_ros1/msg/fpa/gnssant.msg @@ -16,7 +16,7 @@ Header header string gnss1_state # GNSS1 antenna state string gnss1_power # GNSS1 antenna power -int16 gnss1_age # Time since gnss1_state or gnss1_power information last changed +int32 gnss1_age # Time since gnss1_state or gnss1_power information last changed string gnss2_state # GNSS2 antenna state string gnss2_power # GNSS2 antenna power -int16 gnss2_age # Time since gnss2_state or gnss2_power information last changed +int32 gnss2_age # Time since gnss2_state or gnss2_power information last changed diff --git a/fixposition_driver_ros1/msg/fpa/gnsscorr.msg b/fixposition_driver_ros1/msg/fpa/gnsscorr.msg index 4e92f3e..d465731 100644 --- a/fixposition_driver_ros1/msg/fpa/gnsscorr.msg +++ b/fixposition_driver_ros1/msg/fpa/gnsscorr.msg @@ -28,4 +28,4 @@ float64 corr_msg_rate # Average correction message rate (10s window) int16 sta_id # Correction station ID, range 0–4095 geometry_msgs/Vector3 sta_llh # Correction station LLH position (latitude, longitude, height) -int16 sta_dist # Correction station baseline length +int32 sta_dist # Correction station baseline length diff --git a/fixposition_driver_ros1/msg/fpa/imubias.msg b/fixposition_driver_ros1/msg/fpa/imubias.msg new file mode 100644 index 0000000..6eb123f --- /dev/null +++ b/fixposition_driver_ros1/msg/fpa/imubias.msg @@ -0,0 +1,71 @@ +#################################################################################################### +# +# Copyright (c) 2023 ___ ___ +# \\ \\ / / +# \\ \\/ / +# / /\\ \\ +# /__/ \\__\\ Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-IMUBIAS Message +# +# +#################################################################################################### + +Header header +int16 fusion_imu # Fusion measurement status: IMU (see below) +int16 imu_status # IMU bias status (see below) +int16 imu_noise # IMU variance status (see below) +int16 imu_conv # IMU convergence status (see below) +geometry_msgs/Vector3 bias_acc # Accelerometer bias +geometry_msgs/Vector3 bias_gyr # Gyroscope bias +geometry_msgs/Vector3 bias_cov_acc # Accelerometer bias covariance +geometry_msgs/Vector3 bias_cov_gyr # Gyroscope bias covariance + + +# Fusion measurement status (fusion_imu) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not used | +# | 1 | Used | +# | 2 | Degraded | + + +# IMU bias status (imu_status) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not converged | +# | 1 | Warmstarted | +# | 2 | Rough convergence | +# | 3 | Fine convergence | + + +# IMU variance (imu_noise) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Reserved | +# | 1 | Low noise | +# | 2 | Medium noise | +# | 3 | High noise | +# | 4...7 | Reserved | + + +# IMU accelerometer and gyroscope convergence (imu_conv) +# +# | Value | Description | +# |-------|----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Awaiting IMU measurements | +# | 2 | Insufficient global measurements | +# | 3 | Insufficient motion | +# | 4 | Converging | +# | 5...6 | Reserved | +# | 7 | Idle | \ No newline at end of file diff --git a/fixposition_driver_ros1/msg/fpa/llh.msg b/fixposition_driver_ros1/msg/fpa/llh.msg index 1522d2a..ff9e44c 100644 --- a/fixposition_driver_ros1/msg/fpa/llh.msg +++ b/fixposition_driver_ros1/msg/fpa/llh.msg @@ -16,4 +16,4 @@ Header header string pose_frame # frame of the pose values [pose, quaternion] geometry_msgs/Vector3 position # LLH position (latitude, longitude, height) -float64[36] covariance # Position covariance in ENU +float64[9] covariance # Position covariance in ENU diff --git a/fixposition_driver_ros1/msg/fpa/odomstatus.msg b/fixposition_driver_ros1/msg/fpa/odomstatus.msg new file mode 100644 index 0000000..3654ce6 --- /dev/null +++ b/fixposition_driver_ros1/msg/fpa/odomstatus.msg @@ -0,0 +1,190 @@ +#################################################################################################### +# +# Copyright (c) 2023 ___ ___ +# \\ \\ / / +# \\ \\/ / +# / /\\ \\ +# /__/ \\__\\ Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-ODOMSTATUS Message +# +# +#################################################################################################### + +Header header +int16 init_status # Fusion init status (see below) +int16 fusion_imu # Fusion measurement status: IMU (see below) +int16 fusion_gnss1 # Fusion measurement status: GNSS 1 (see below) +int16 fusion_gnss2 # Fusion measurement status: GNSS 2 (see below) +int16 fusion_corr # Fusion measurement status: GNSS corrections (see below) +int16 fusion_cam1 # Fusion measurement status: camera (see below) +int16 fusion_ws # Fusion measurement status: wheelspeed (see below) +int16 fusion_markers # Fusion measurement status: markers (see below) +int16 imu_status # IMU bias status (see below) +int16 imu_noise # IMU variance status (see below) +int16 imu_conv # IMU convergence status (see below) +int16 gnss1_status # GNSS 1 status (see below) +int16 gnss2_status # GNSS 2 status (see below) +int16 baseline_status # Baseline status (see below) +int16 corr_status # GNSS correction status (see below) +int16 cam1_status # Camera 1 status (see below) +int16 ws_status # Wheelspeed status (see below) +int16 ws_conv # Wheelspeed convergence status (see below) +int16 markers_status # Markers status (see below) +int16 markers_conv # Markers convergence status (see below) + + +# Fusion initialisation status (init_status) +# +# | Value | Description | +# |-------|----------------------| +# | null | Unknown | +# | 0 | Not initialized | +# | 1 | Locally initialised | +# | 2 | Globally initialised | + + +# Fusion measurement status (fusion_imu, fusion_cam1, fusion_cam2, fusion_gnss1, fusion_gnss2, fusion_corr, fusion_ws, fusion_markers) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not used | +# | 1 | Used | +# | 2 | Degraded | + + +# IMU bias status (imu_status) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not converged | +# | 1 | Warmstarted | +# | 2 | Rough convergence | +# | 3 | Fine convergence | + + +# IMU variance (imu_noise) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Reserved | +# | 1 | Low noise | +# | 2 | Medium noise | +# | 3 | High noise | +# | 4...7 | Reserved | + + +# IMU accelerometer and gyroscope convergence (imu_conv) +# +# | Value | Description | +# |-------|----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Awaiting IMU measurements | +# | 2 | Insufficient global measurements | +# | 3 | Insufficient motion | +# | 4 | Converging | +# | 5...6 | Reserved | +# | 7 | Idle | + + +# GNSS fix status (gnss1_status, gnss2_status) +# +# | Value | Description | +# |-------|--------------------------------| +# | null | Info not available | +# | 0 | No fix | +# | 1 | Single-point positioning (SPP) | +# | 2 | RTK moving baseline | +# | 3...4 | Reserved | +# | 5 | RTK float | +# | 6...7 | Reserved | +# | 8 | RTK fixed | + + +# GNSS correction status (corr_status) +# +# | Value | Description | +# |-------|----------------------------------------------------------------------------------------------------------------| +# | null | Info not available | +# | 0 | Waiting fusion | +# | 1 | No GNSS available | +# | 2 | No corrections used | +# | 3 | Limited corrections used: station data & at least one of the constellations among the valid rover measurements | +# | 4 | Corrections are too old | +# | 5 | Sufficient corrections used: station data and corrections for ALL bands among the valid rover measurements | + + +# Baseline status (baseline_status) +# +# | Value | Description | +# |-------|------------------------| +# | null | Info not available | +# | 0 | Waiting fusion | +# | 1 | Not available / No fix | +# | 2 | Failing | +# | 3 | Passing | + + +# Camera status (cam1_status) +# +# | Value | Description | +# |-------|--------------------------------------------------| +# | null | Info not available | +# | 0 | Camera not available | +# | 1 | Camera available, but not usable (e.g. too dark) | +# | 2...4 | Reserved | +# | 5 | Camera working and available | + + +# Wheelspeed status (ws_status) +# +# | Value | Description | +# |-------|------------------------------------------------------------| +# | null | Info not available | +# | 0 | No wheelspeed enabled | +# | 1 | Missing wheelspeed measurements | +# | 2 | At least one wheelspeed enabled, no wheelspeed converged | +# | 3 | At least one wheelspeed enabled and at least one converged | +# | 4 | At least one wheelspeed enabled and all converged | + + +# Wheelspeed convergence status (ws_conv) +# +# | Value | Description | +# |-------|-----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Missing wheelspeed measurements | +# | 2 | Insufficient global measurements | +# | 3 | Insufficient motion | +# | 4 | Insufficient imu bias convergence | +# | 5 | Converging | +# | 6 | Idle | + + +# Markers status (markers_status) +# +# | Value | Description | +# |-------|-----------------------------| +# | null | Info not available | +# | 0 | No markers available | +# | 1 | Markers available | +# | 2 | Markers available, and used | + + +# Markers convergence status (markers_conv) +# +# | Value | Description | +# |-------|----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Waiting marker measurements | +# | 2 | Insufficient global measurements | +# | 3 | Converging | +# | 4 | Idle | diff --git a/fixposition_driver_ros1/msg/fpa/tp.msg b/fixposition_driver_ros1/msg/fpa/tp.msg new file mode 100644 index 0000000..6e12173 --- /dev/null +++ b/fixposition_driver_ros1/msg/fpa/tp.msg @@ -0,0 +1,56 @@ +#################################################################################################### +# +# Copyright (c) 2023 ___ ___ +# \\ \\ / / +# \\ \\/ / +# / /\\ \\ +# /__/ \\__\\ Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-TP Message +# +# +#################################################################################################### + +string tp_name # Timepulse name (source) +string timebase # Time base (see below), or null if not available +string timeref # Time reference (see below), or null if not available +int64 tp_tow_sec # Timepulse time seconds of week, integer second part (0–604799), or null +float64 tp_tow_psec # Timepulse time seconds of week, sub-second part (0.000000000000–0.999999999999), or null +int64 gps_leaps # GPS leapseconds, or null if unknown + + +# Values for timebase +# +# | Value | Description | +# |-------|---------------------------| +# | null | No timepulse alignment | +# | GNSS | Timepulse aligned to GNSS | +# | UTC | Timepulse aligned to UTC | + + +# Values for timeref if timebase is GNSS +# +# | Value | Description | +# |-------|---------------------------------| +# | GPS | Timepulse aligned to GPS | +# | GAL | Timepulse aligned to Galileo | +# | BDS | Timepulse aligned to BeiDou | +# | GLO | Timepulse aligned to GLONASS | +# | OTHER | Timepulse aligned to other GNSS | + + +# Values for timeref if timebase is UTC +# +# | Value | Description | +# |-------|----------------------------------------------------------------------------| +# | NONE | Timepulse aligned to no UTC (no precise UTC parameters known yet) | +# | CRL | Timepulse aligned to Communications Research Laboratory (CRL), Japan | +# | NIST | Timepulse aligned to National Institute of Standards and Technology (NIST) | +# | USNO | Timepulse aligned to U.S. Naval Observatory (USNO) | +# | BIPM | Timepulse aligned to International Bureau of Weights and Measures (BIPM) | +# | EU | Timepulse aligned to European laboratories | +# | SU | Timepulse aligned to Former Soviet Union (SU) | +# | NTSC | Timepulse aligned to National Time Service Center (NTSC), China | +# | OTHER | Timepulse aligned to other/unknown UTC | diff --git a/fixposition_driver_ros1/msg/nmea/gxgsv.msg b/fixposition_driver_ros1/msg/nmea/gxgsv.msg index 5619331..a7ba73a 100644 --- a/fixposition_driver_ros1/msg/nmea/gxgsv.msg +++ b/fixposition_driver_ros1/msg/nmea/gxgsv.msg @@ -17,7 +17,7 @@ # -------|-----------|---------|-------------------------------------| int16 sentences # [-] | Total number of sentences (1 to 9). int16 sent_num # [-] | Sentence number (1 to 9). -int16 num_sats # [-] | Total number of satellites in view. +int32 num_sats # [-] | Total number of satellites in view. int16[] sat_id # [-] | Satellite ID number. int16[] elev # [deg] | Satellite elevation. int16[] azim # [deg] | Satellite azimuth from true North. diff --git a/fixposition_driver_ros1/src/data_to_ros1.cpp b/fixposition_driver_ros1/src/data_to_ros1.cpp index 48118e6..31b7fa1 100644 --- a/fixposition_driver_ros1/src/data_to_ros1.cpp +++ b/fixposition_driver_ros1/src/data_to_ros1.cpp @@ -61,6 +61,33 @@ void FpToRosMsg(const ImuData& data, ros::Publisher& pub) { } } +void FpToRosMsg(const FP_IMUBIAS& data, ros::Publisher& pub) { + if (pub.getNumSubscribers() > 0) { + // Create message + fixposition_driver_ros1::imubias msg; + + // Populate message + if (data.stamp.tow == 0.0 && data.stamp.wno == 0) { + msg.header.stamp = ros::Time::now(); + } else { + msg.header.stamp = ros::Time::fromBoost(GpsTimeToPtime(data.stamp)); + } + + msg.header.frame_id = data.frame_id; + msg.fusion_imu = data.fusion_imu; + msg.imu_status = data.imu_status; + msg.imu_noise = data.imu_noise; + msg.imu_conv = data.imu_conv; + tf::vectorEigenToMsg(data.bias_acc, msg.bias_acc); + tf::vectorEigenToMsg(data.bias_gyr, msg.bias_gyr); + tf::vectorEigenToMsg(data.bias_cov_acc, msg.bias_cov_acc); + tf::vectorEigenToMsg(data.bias_cov_gyr, msg.bias_cov_gyr); + + // Publish message + pub.publish(msg); + } +} + void FpToRosMsg(const FP_GNSSANT& data, ros::Publisher& pub) { if (pub.getNumSubscribers() > 0) { // Create message @@ -230,6 +257,44 @@ void FpToRosMsg(const FP_ODOMSH& data, ros::Publisher& pub) { } } +void FpToRosMsg(const FP_ODOMSTATUS& data, ros::Publisher& pub) { + if (pub.getNumSubscribers() > 0) { + // Create message + fixposition_driver_ros1::odomstatus msg; + + // Populate message + if (data.stamp.tow == 0.0 && data.stamp.wno == 0) { + msg.header.stamp = ros::Time::now(); + } else { + msg.header.stamp = ros::Time::fromBoost(GpsTimeToPtime(data.stamp)); + } + + msg.init_status = data.init_status; + msg.fusion_imu = data.fusion_imu; + msg.fusion_gnss1 = data.fusion_gnss1; + msg.fusion_gnss2 = data.fusion_gnss2; + msg.fusion_corr = data.fusion_corr; + msg.fusion_cam1 = data.fusion_cam1; + msg.fusion_ws = data.fusion_ws; + msg.fusion_markers = data.fusion_markers; + msg.imu_status = data.imu_status; + msg.imu_noise = data.imu_noise; + msg.imu_conv = data.imu_conv; + msg.gnss1_status = data.gnss1_status; + msg.gnss2_status = data.gnss2_status; + msg.baseline_status = data.baseline_status; + msg.corr_status = data.corr_status; + msg.cam1_status = data.cam1_status; + msg.ws_status = data.ws_status; + msg.ws_conv = data.ws_conv; + msg.markers_status = data.markers_status; + msg.markers_conv = data.markers_conv; + + // Publish message + pub.publish(msg); + } +} + void FpToRosMsg(const FP_TEXT& data, ros::Publisher& pub) { if (pub.getNumSubscribers() > 0) { // Create message @@ -244,6 +309,42 @@ void FpToRosMsg(const FP_TEXT& data, ros::Publisher& pub) { } } +void FpToRosMsg(const FP_TP& data, ros::Publisher& pub) { + if (pub.getNumSubscribers() > 0) { + // Create message + fixposition_driver_ros1::tp msg; + + // Populate message + msg.tp_name = data.tp_name; + msg.timebase = data.timebase; + msg.timeref = data.timeref; + msg.tp_tow_sec = data.tp_tow_sec; + msg.tp_tow_psec = data.tp_tow_psec; + msg.gps_leaps = data.gps_leaps; + + // Publish message + pub.publish(msg); + } +} + +void FpToRosMsg(const FP_EOE& data, ros::Publisher& pub) { + if (pub.getNumSubscribers() > 0) { + // Create message + fixposition_driver_ros1::eoe msg; + + // Populate message + if (data.stamp.tow == 0.0 && data.stamp.wno == 0) { + msg.header.stamp = ros::Time::now(); + } else { + msg.header.stamp = ros::Time::fromBoost(GpsTimeToPtime(data.stamp)); + } + msg.epoch = data.epoch; + + // Publish message + pub.publish(msg); + } +} + void FpToRosMsg(const GP_GGA& data, ros::Publisher& pub) { if (pub.getNumSubscribers() > 0) { // Create message @@ -621,4 +722,30 @@ void OdomToYprMsg(const OdometryData& data, ros::Publisher& pub) { } } +void JumpWarningMsg(const times::GpsTime& stamp, const Eigen::Vector3d& pos_diff, const Eigen::MatrixXd& prev_cov, ros::Publisher& pub) { + if (pub.getNumSubscribers() > 0) { + // Create message + fixposition_driver_ros1::CovWarn msg; + + // Populate message + if (stamp.tow == 0.0 && stamp.wno == 0) { + msg.header.stamp = ros::Time::now(); + } else { + msg.header.stamp = ros::Time::fromBoost(times::GpsTimeToPtime(stamp)); + } + + std::stringstream warn_msg; + warn_msg << "Position jump detected! The change in position is greater than the estimated covariances. " + << "Position difference: [" << pos_diff[0] << ", " << pos_diff[1] << ", " << pos_diff[2] << "], " + << "Covariances: [" << prev_cov(0,0) << ", " << prev_cov(1,1) << ", " << prev_cov(2,2) << "]"; + + ROS_WARN("%s", warn_msg.str().c_str()); + tf::vectorEigenToMsg(pos_diff, msg.jump); + tf::vectorEigenToMsg(Eigen::Vector3d(prev_cov(0,0),prev_cov(1,1),prev_cov(2,2)), msg.covariance); + + // Publish message + pub.publish(msg); + } +} + } // namespace fixposition diff --git a/fixposition_driver_ros1/src/fixposition_driver_node.cpp b/fixposition_driver_ros1/src/fixposition_driver_node.cpp index b2bd06a..f6ab947 100644 --- a/fixposition_driver_ros1/src/fixposition_driver_node.cpp +++ b/fixposition_driver_ros1/src/fixposition_driver_node.cpp @@ -22,12 +22,16 @@ FixpositionDriverNode::FixpositionDriverNode(const FixpositionDriverParams& para nh_("~"), // FP_A messages fpa_odometry_pub_(nh_.advertise("/fixposition/fpa/odometry", 5)), + fpa_imubias_pub_(nh_.advertise("/fixposition/fpa/imubias", 5)), + fpa_eoe_pub_(nh_.advertise("/fixposition/fpa/eoe", 5)), fpa_llh_pub_(nh_.advertise("/fixposition/fpa/llh", 5)), fpa_odomenu_pub_(nh_.advertise("/fixposition/fpa/odomenu", 5)), fpa_odomsh_pub_(nh_.advertise("/fixposition/fpa/odomsh", 5)), + fpa_odomstatus_pub_(nh_.advertise("/fixposition/fpa/odomstatus", 5)), fpa_gnssant_pub_(nh_.advertise("/fixposition/fpa/gnssant", 5)), fpa_gnsscorr_pub_(nh_.advertise("/fixposition/fpa/gnsscorr", 5)), fpa_text_pub_(nh_.advertise("/fixposition/fpa/text", 5)), + fpa_tp_pub_(nh_.advertise("/fixposition/fpa/tp", 5)), // NMEA messages nmea_gpgga_pub_(nh_.advertise("/fixposition/nmea/gpgga", 5)), @@ -67,6 +71,13 @@ FixpositionDriverNode::FixpositionDriverNode(const FixpositionDriverParams& para rtcm_sub_ = nh_.subscribe(params_.customer_input.rtcm_topic, 10, &FixpositionDriverNode::RtcmCallback, this, ros::TransportHints().tcpNoDelay()); + + // Configure jump warning message + if (params_.fp_output.cov_warning) { + extras_jump_pub_ = nh_.advertise("/fixposition/extras/jump", 5); + prev_pos.setZero(); + prev_cov.setZero(); + } RegisterObservers(); } @@ -104,6 +115,19 @@ void FixpositionDriverNode::RegisterObservers() { OdomToImuMsg(data, poiimu_pub_); OdomToNavSatFix(data, odometry_llh_pub_); OdometryDataToTf(data, br_); + + // Output jump warning + if (params_.fp_output.cov_warning) { + if (!prev_pos.isZero() && !prev_cov.isZero()) { + Eigen::Vector3d pos_diff = (prev_pos - data.odom.pose.position).cwiseAbs(); + + if ((pos_diff[0] > 0) || (pos_diff[1] > prev_cov(1,1)) || (pos_diff[2] > prev_cov(2,2))) { + JumpWarningMsg(data.odom.stamp, pos_diff, prev_cov, extras_jump_pub_); + } + } + prev_pos = data.odom.pose.position; + prev_cov = data.odom.pose.cov; + } }); } else if (format == "ODOMENU") { dynamic_cast*>(a_converters_["ODOMENU"].get()) @@ -118,6 +142,15 @@ void FixpositionDriverNode::RegisterObservers() { FpToRosMsg(data, fpa_odomsh_pub_); FpToRosMsg(data.odom, odometry_smooth_pub_); }); + } else if (format == "ODOMSTATUS") { + dynamic_cast*>(a_converters_["ODOMSTATUS"].get()) + ->AddObserver([this](const FP_ODOMSTATUS& data) { FpToRosMsg(data, fpa_odomstatus_pub_); }); + } else if (format == "IMUBIAS") { + dynamic_cast*>(a_converters_["IMUBIAS"].get()) + ->AddObserver([this](const FP_IMUBIAS& data) { FpToRosMsg(data, fpa_imubias_pub_); }); + } else if (format == "EOE") { + dynamic_cast*>(a_converters_["EOE"].get()) + ->AddObserver([this](const FP_EOE& data) { FpToRosMsg(data, fpa_eoe_pub_); }); } else if (format == "LLH") { dynamic_cast*>(a_converters_["LLH"].get()) ->AddObserver([this](const FP_LLH& data) { FpToRosMsg(data, fpa_llh_pub_); }); @@ -161,6 +194,9 @@ void FixpositionDriverNode::RegisterObservers() { } } }); + } else if (format == "TP") { + dynamic_cast*>(a_converters_["TP"].get()) + ->AddObserver([this](const FP_TP& data) { FpToRosMsg(data, fpa_tp_pub_); }); } else if (format == "GPGGA") { dynamic_cast*>(a_converters_["GPGGA"].get())->AddObserver([this](const GP_GGA& data) { FpToRosMsg(data, nmea_gpgga_pub_); diff --git a/fixposition_driver_ros1/src/params.cpp b/fixposition_driver_ros1/src/params.cpp index 99988e9..c611ab9 100644 --- a/fixposition_driver_ros1/src/params.cpp +++ b/fixposition_driver_ros1/src/params.cpp @@ -25,6 +25,8 @@ bool LoadParamsFromRos1(const std::string& ns, FpOutputParams& params) { const std::string IP = ns + "/ip"; const std::string PORT = ns + "/port"; const std::string BAUDRATE = ns + "/baudrate"; + const std::string COV_WARNING = ns + "/cov_warning"; + // read parameters if (!ros::param::get(RATE, params.rate)) { params.rate = 100; @@ -34,6 +36,10 @@ bool LoadParamsFromRos1(const std::string& ns, FpOutputParams& params) { params.reconnect_delay = 5.0; ROS_WARN("Using Default Reconnect Delay : %f", params.reconnect_delay); } + if (!ros::param::get(COV_WARNING, params.cov_warning)) { + params.cov_warning = false; + ROS_WARN("Using Default Covariance Warning option : %i", params.cov_warning); + } std::string type_str; if (!ros::param::get(TYPE, type_str)) { diff --git a/fixposition_driver_ros2/CMakeLists.txt b/fixposition_driver_ros2/CMakeLists.txt index 021b01f..b8bbc8e 100644 --- a/fixposition_driver_ros2/CMakeLists.txt +++ b/fixposition_driver_ros2/CMakeLists.txt @@ -30,11 +30,15 @@ rosidl_generate_interfaces(${PROJECT_NAME} msg/WheelSensor.msg msg/fpa/GNSSANT.msg msg/fpa/GNSSCORR.msg + msg/fpa/IMUBIAS.msg + msg/fpa/EOE.msg msg/fpa/LLH.msg msg/fpa/ODOMENU.msg msg/fpa/ODOMETRY.msg msg/fpa/ODOMSH.msg + msg/fpa/ODOMSTATUS.msg msg/fpa/TEXT.msg + msg/fpa/TP.msg msg/nmea/GPGGA.msg msg/nmea/GPGLL.msg msg/nmea/GNGSA.msg @@ -44,6 +48,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} msg/nmea/GPRMC.msg msg/nmea/GPVTG.msg msg/nmea/GPZDA.msg + msg/extras/COVWARN.msg DEPENDENCIES std_msgs nav_msgs diff --git a/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp b/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp index 35c4225..21c7943 100644 --- a/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp +++ b/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp @@ -51,15 +51,19 @@ inline builtin_interfaces::msg::Time GpsTimeToMsgTime(times::GpsTime input) { * @param[in] data * @param[out] msg */ -void FpToRosMsg(const OdometryData& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const ImuData& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_GNSSANT& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_GNSSCORR& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_LLH& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_ODOMENU& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_ODOMETRY& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_ODOMSH& data, rclcpp::Publisher::SharedPtr pub); -void FpToRosMsg( const FP_TEXT& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const OdometryData& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const ImuData& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_EOE& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_GNSSANT& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_GNSSCORR& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_IMUBIAS& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_LLH& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_ODOMENU& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_ODOMETRY& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_ODOMSH& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg(const FP_ODOMSTATUS& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_TP& data, rclcpp::Publisher::SharedPtr pub); +void FpToRosMsg( const FP_TEXT& data, rclcpp::Publisher::SharedPtr pub); void FpToRosMsg(const GP_GGA& data, rclcpp::Publisher::SharedPtr pub); void FpToRosMsg(const GP_GLL& data, rclcpp::Publisher::SharedPtr pub); @@ -135,6 +139,17 @@ void OdomToImuMsg(const fixposition::FP_ODOMETRY& data, rclcpp::Publisher::SharedPtr pub); +/** + * @brief + * + * @param[in] stamp + * @param[in] pos_diff + * @param[in] prev_cov + * @param[out] msg + */ +void JumpWarningMsg(std::shared_ptr node, const times::GpsTime& stamp, const Eigen::Vector3d& pos_diff, + const Eigen::MatrixXd& prev_cov, rclcpp::Publisher::SharedPtr pub); + } // namespace fixposition #endif diff --git a/fixposition_driver_ros2/include/fixposition_driver_ros2/fixposition_driver_node.hpp b/fixposition_driver_ros2/include/fixposition_driver_ros2/fixposition_driver_node.hpp index cf47bee..453dbdb 100644 --- a/fixposition_driver_ros2/include/fixposition_driver_ros2/fixposition_driver_node.hpp +++ b/fixposition_driver_ros2/include/fixposition_driver_ros2/fixposition_driver_node.hpp @@ -72,24 +72,28 @@ class FixpositionDriverNode : public FixpositionDriver { // ROS publishers // FP_A messages - rclcpp::Publisher::SharedPtr fpa_odometry_pub_; //!< FP_A-ODOMETRY message - rclcpp::Publisher::SharedPtr fpa_llh_pub_; //!< FP_A-LLH message - rclcpp::Publisher::SharedPtr fpa_odomenu_pub_; //!< FP_A-ODOMENU message - rclcpp::Publisher::SharedPtr fpa_odomsh_pub_; //!< FP_A-ODOMSH message - rclcpp::Publisher::SharedPtr fpa_gnssant_pub_; //!< FP_A-GNSSANT message - rclcpp::Publisher::SharedPtr fpa_gnsscorr_pub_; //!< FP_A-GNSSCORR message - rclcpp::Publisher::SharedPtr fpa_text_pub_; //!< FP_A-TEXT message + rclcpp::Publisher::SharedPtr fpa_odometry_pub_; //!< FP_A-ODOMETRY message + rclcpp::Publisher::SharedPtr fpa_imubias_pub_; //!< FP_A-IMUBIAS message + rclcpp::Publisher::SharedPtr fpa_eoe_pub_; //!< FP_A-EOE message + rclcpp::Publisher::SharedPtr fpa_llh_pub_; //!< FP_A-LLH message + rclcpp::Publisher::SharedPtr fpa_odomenu_pub_; //!< FP_A-ODOMENU message + rclcpp::Publisher::SharedPtr fpa_odomsh_pub_; //!< FP_A-ODOMSH message + rclcpp::Publisher::SharedPtr fpa_odomstatus_pub_; //!< FP_A-ODOMSTATUS message + rclcpp::Publisher::SharedPtr fpa_gnssant_pub_; //!< FP_A-GNSSANT message + rclcpp::Publisher::SharedPtr fpa_gnsscorr_pub_; //!< FP_A-GNSSCORR message + rclcpp::Publisher::SharedPtr fpa_text_pub_; //!< FP_A-TEXT message + rclcpp::Publisher::SharedPtr fpa_tp_pub_; //!< FP_A-TP message // NMEA messages - rclcpp::Publisher::SharedPtr nmea_gpgga_pub_; //!< NMEA-GP-GGA message - rclcpp::Publisher::SharedPtr nmea_gpgll_pub_; //!< NMEA-GP-GLL message - rclcpp::Publisher::SharedPtr nmea_gngsa_pub_; //!< NMEA-GP-GSA message - rclcpp::Publisher::SharedPtr nmea_gpgst_pub_; //!< NMEA-GP-GST message - rclcpp::Publisher::SharedPtr nmea_gxgsv_pub_; //!< NMEA-GP-GSV message - rclcpp::Publisher::SharedPtr nmea_gphdt_pub_; //!< NMEA-GP-HDT message - rclcpp::Publisher::SharedPtr nmea_gprmc_pub_; //!< NMEA-GP-RMC message - rclcpp::Publisher::SharedPtr nmea_gpvtg_pub_; //!< NMEA-GP-VTG message - rclcpp::Publisher::SharedPtr nmea_gpzda_pub_; //!< NMEA-GP-ZDA message + rclcpp::Publisher::SharedPtr nmea_gpgga_pub_; //!< NMEA-GP-GGA message + rclcpp::Publisher::SharedPtr nmea_gpgll_pub_; //!< NMEA-GP-GLL message + rclcpp::Publisher::SharedPtr nmea_gngsa_pub_; //!< NMEA-GP-GSA message + rclcpp::Publisher::SharedPtr nmea_gpgst_pub_; //!< NMEA-GP-GST message + rclcpp::Publisher::SharedPtr nmea_gxgsv_pub_; //!< NMEA-GP-GSV message + rclcpp::Publisher::SharedPtr nmea_gphdt_pub_; //!< NMEA-GP-HDT message + rclcpp::Publisher::SharedPtr nmea_gprmc_pub_; //!< NMEA-GP-RMC message + rclcpp::Publisher::SharedPtr nmea_gpvtg_pub_; //!< NMEA-GP-VTG message + rclcpp::Publisher::SharedPtr nmea_gpzda_pub_; //!< NMEA-GP-ZDA message // ODOMETRY rclcpp::Publisher::SharedPtr odometry_ecef_pub_; //!< ECEF Odometry @@ -115,6 +119,13 @@ class FixpositionDriverNode : public FixpositionDriver { // TF std::shared_ptr br_; std::shared_ptr static_br_; + + // Jump warning topic + rclcpp::Publisher::SharedPtr extras_jump_pub_; //!< Jump warning topic + + // Previous state + Eigen::Vector3d prev_pos; + Eigen::MatrixXd prev_cov; }; } // namespace fixposition diff --git a/fixposition_driver_ros2/include/fixposition_driver_ros2/ros2_msgs.hpp b/fixposition_driver_ros2/include/fixposition_driver_ros2/ros2_msgs.hpp index 9ade4f6..2ae8657 100644 --- a/fixposition_driver_ros2/include/fixposition_driver_ros2/ros2_msgs.hpp +++ b/fixposition_driver_ros2/include/fixposition_driver_ros2/ros2_msgs.hpp @@ -24,18 +24,28 @@ #include #include +// Include generic #include #include #include +// Include extras +#include + +// Include FP-A #include #include +#include +#include #include #include #include #include +#include #include +#include +// Include NMEA #include #include #include diff --git a/fixposition_driver_ros2/launch/serial.yaml b/fixposition_driver_ros2/launch/serial.yaml index acafba7..63a7a81 100644 --- a/fixposition_driver_ros2/launch/serial.yaml +++ b/fixposition_driver_ros2/launch/serial.yaml @@ -2,7 +2,8 @@ fixposition_driver_ros2: ros__parameters: fp_output: formats: [ - "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "RAWIMU", "CORRIMU", "GNSSANT", "GNSSCORR", "TEXT", "TF", # FP_A + "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "ODOMSTATUS", "RAWIMU", "CORRIMU", + "IMUBIAS", "GNSSANT", "GNSSCORR", "EOE", "TEXT", "TF", "TP", # FP_A "GPGGA", "GPGLL", "GNGSA", "GPGST", "GPHDT", "GPRMC", "GPVTG", "GPZDA", "GXGSV" # NMEA ] type: "serial" @@ -10,6 +11,8 @@ fixposition_driver_ros2: baudrate: 115200 rate: 200 reconnect_delay: 5.0 # wait time in [s] until retry connection + cov_warning: false + customer_input: speed_topic: "/fixposition/speed" rtcm_topic: "/fixposition/rtcm" diff --git a/fixposition_driver_ros2/launch/tcp.yaml b/fixposition_driver_ros2/launch/tcp.yaml index ee8281d..b284d5b 100644 --- a/fixposition_driver_ros2/launch/tcp.yaml +++ b/fixposition_driver_ros2/launch/tcp.yaml @@ -2,7 +2,8 @@ fixposition_driver_ros2: ros__parameters: fp_output: formats: [ - "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "RAWIMU", "CORRIMU", "GNSSANT", "GNSSCORR", "TEXT", "TF", # FP_A + "ODOMETRY", "LLH", "ODOMENU", "ODOMSH", "ODOMSTATUS", "RAWIMU", "CORRIMU", + "IMUBIAS", "GNSSANT", "GNSSCORR", "EOE", "TEXT", "TF", "TP", # FP_A "GPGGA", "GPGLL", "GNGSA", "GPGST", "GPHDT", "GPRMC", "GPVTG", "GPZDA", "GXGSV" # NMEA ] type: "tcp" @@ -11,6 +12,8 @@ fixposition_driver_ros2: rate: 200 reconnect_delay: 5.0 # wait time in [s] until retry connection qos_type: "sensor_short" # Supported types: "sensor_short", "sensor_long", "default_short", "default_long" + cov_warning: false + customer_input: speed_topic: "/fixposition/speed" rtcm_topic: "/fixposition/rtcm" diff --git a/fixposition_driver_ros2/msg/extras/COVWARN.msg b/fixposition_driver_ros2/msg/extras/COVWARN.msg new file mode 100644 index 0000000..cfe6e43 --- /dev/null +++ b/fixposition_driver_ros2/msg/extras/COVWARN.msg @@ -0,0 +1,15 @@ +#################################################################################################### +# +# Copyright (c) 2023 +# Fixposition AG +# +#################################################################################################### +# +# Fixposition Covariance Warning Message +# +# +#################################################################################################### + +std_msgs/Header header +geometry_msgs/Vector3 jump # Position change +geometry_msgs/Vector3 covariance # Covariance diff --git a/fixposition_driver_ros2/msg/fpa/EOE.msg b/fixposition_driver_ros2/msg/fpa/EOE.msg new file mode 100644 index 0000000..d1c541b --- /dev/null +++ b/fixposition_driver_ros2/msg/fpa/EOE.msg @@ -0,0 +1,14 @@ +#################################################################################################### +# +# Copyright (c) 2023 +# Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-EOE Message +# +# +#################################################################################################### + +std_msgs/Header header +string epoch # Indicates which epoch ended (FUSION, GNSS, GNSS1 or GNSS2) diff --git a/fixposition_driver_ros2/msg/fpa/GNSSANT.msg b/fixposition_driver_ros2/msg/fpa/GNSSANT.msg index 42f3eae..ef468f0 100644 --- a/fixposition_driver_ros2/msg/fpa/GNSSANT.msg +++ b/fixposition_driver_ros2/msg/fpa/GNSSANT.msg @@ -13,7 +13,7 @@ std_msgs/Header header string gnss1_state # GNSS1 antenna state string gnss1_power # GNSS1 antenna power -int16 gnss1_age # Time since gnss1_state or gnss1_power information last changed +int32 gnss1_age # Time since gnss1_state or gnss1_power information last changed string gnss2_state # GNSS2 antenna state string gnss2_power # GNSS2 antenna power -int16 gnss2_age # Time since gnss2_state or gnss2_power information last changed +int32 gnss2_age # Time since gnss2_state or gnss2_power information last changed diff --git a/fixposition_driver_ros2/msg/fpa/GNSSCORR.msg b/fixposition_driver_ros2/msg/fpa/GNSSCORR.msg index 2095b4d..b9fc453 100644 --- a/fixposition_driver_ros2/msg/fpa/GNSSCORR.msg +++ b/fixposition_driver_ros2/msg/fpa/GNSSCORR.msg @@ -25,4 +25,4 @@ float64 corr_msg_rate # Average correction message rate (10s window) int16 sta_id # Correction station ID, range 0–4095 geometry_msgs/Vector3 sta_llh # Correction station LLH position (latitude, longitude, height) -int16 sta_dist # Correction station baseline length +int32 sta_dist # Correction station baseline length diff --git a/fixposition_driver_ros2/msg/fpa/IMUBIAS.msg b/fixposition_driver_ros2/msg/fpa/IMUBIAS.msg new file mode 100644 index 0000000..10ae6fd --- /dev/null +++ b/fixposition_driver_ros2/msg/fpa/IMUBIAS.msg @@ -0,0 +1,68 @@ +#################################################################################################### +# +# Copyright (c) 2023 +# Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-IMUBIAS Message +# +# +#################################################################################################### + +std_msgs/Header header +int16 fusion_imu # Fusion measurement status: IMU (see below) +int16 imu_status # IMU bias status (see below) +int16 imu_noise # IMU variance status (see below) +int16 imu_conv # IMU convergence status (see below) +geometry_msgs/Vector3 bias_acc # Accelerometer bias +geometry_msgs/Vector3 bias_gyr # Gyroscope bias +geometry_msgs/Vector3 bias_cov_acc # Accelerometer bias covariance +geometry_msgs/Vector3 bias_cov_gyr # Gyroscope bias covariance + + +# Fusion measurement status (fusion_imu) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not used | +# | 1 | Used | +# | 2 | Degraded | + + +# IMU bias status (imu_status) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not converged | +# | 1 | Warmstarted | +# | 2 | Rough convergence | +# | 3 | Fine convergence | + + +# IMU variance (imu_noise) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Reserved | +# | 1 | Low noise | +# | 2 | Medium noise | +# | 3 | High noise | +# | 4...7 | Reserved | + + +# IMU accelerometer and gyroscope convergence (imu_conv) +# +# | Value | Description | +# |-------|----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Awaiting IMU measurements | +# | 2 | Insufficient global measurements | +# | 3 | Insufficient motion | +# | 4 | Converging | +# | 5...6 | Reserved | +# | 7 | Idle | \ No newline at end of file diff --git a/fixposition_driver_ros2/msg/fpa/LLH.msg b/fixposition_driver_ros2/msg/fpa/LLH.msg index 31b4ac7..e5dd5e1 100644 --- a/fixposition_driver_ros2/msg/fpa/LLH.msg +++ b/fixposition_driver_ros2/msg/fpa/LLH.msg @@ -13,4 +13,4 @@ std_msgs/Header header string pose_frame # frame of the pose values [pose, quaternion] geometry_msgs/Vector3 position # LLH position (latitude, longitude, height) -float64[36] covariance # Position covariance in ENU +float64[9] covariance # Position covariance in ENU diff --git a/fixposition_driver_ros2/msg/fpa/ODOMSTATUS.msg b/fixposition_driver_ros2/msg/fpa/ODOMSTATUS.msg new file mode 100644 index 0000000..7868a7b --- /dev/null +++ b/fixposition_driver_ros2/msg/fpa/ODOMSTATUS.msg @@ -0,0 +1,187 @@ +#################################################################################################### +# +# Copyright (c) 2023 +# Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-ODOMSTATUS Message +# +# +#################################################################################################### + +std_msgs/Header header +int16 init_status # Fusion init status (see below) +int16 fusion_imu # Fusion measurement status: IMU (see below) +int16 fusion_gnss1 # Fusion measurement status: GNSS 1 (see below) +int16 fusion_gnss2 # Fusion measurement status: GNSS 2 (see below) +int16 fusion_corr # Fusion measurement status: GNSS corrections (see below) +int16 fusion_cam1 # Fusion measurement status: camera (see below) +int16 fusion_ws # Fusion measurement status: wheelspeed (see below) +int16 fusion_markers # Fusion measurement status: markers (see below) +int16 imu_status # IMU bias status (see below) +int16 imu_noise # IMU variance status (see below) +int16 imu_conv # IMU convergence status (see below) +int16 gnss1_status # GNSS 1 status (see below) +int16 gnss2_status # GNSS 2 status (see below) +int16 baseline_status # Baseline status (see below) +int16 corr_status # GNSS correction status (see below) +int16 cam1_status # Camera 1 status (see below) +int16 ws_status # Wheelspeed status (see below) +int16 ws_conv # Wheelspeed convergence status (see below) +int16 markers_status # Markers status (see below) +int16 markers_conv # Markers convergence status (see below) + + +# Fusion initialisation status (init_status) +# +# | Value | Description | +# |-------|----------------------| +# | null | Unknown | +# | 0 | Not initialized | +# | 1 | Locally initialised | +# | 2 | Globally initialised | + + +# Fusion measurement status (fusion_imu, fusion_cam1, fusion_cam2, fusion_gnss1, fusion_gnss2, fusion_corr, fusion_ws, fusion_markers) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not used | +# | 1 | Used | +# | 2 | Degraded | + + +# IMU bias status (imu_status) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Not converged | +# | 1 | Warmstarted | +# | 2 | Rough convergence | +# | 3 | Fine convergence | + + +# IMU variance (imu_noise) +# +# | Value | Description | +# |-------|--------------------| +# | null | Info not available | +# | 0 | Reserved | +# | 1 | Low noise | +# | 2 | Medium noise | +# | 3 | High noise | +# | 4...7 | Reserved | + + +# IMU accelerometer and gyroscope convergence (imu_conv) +# +# | Value | Description | +# |-------|----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Awaiting IMU measurements | +# | 2 | Insufficient global measurements | +# | 3 | Insufficient motion | +# | 4 | Converging | +# | 5...6 | Reserved | +# | 7 | Idle | + + +# GNSS fix status (gnss1_status, gnss2_status) +# +# | Value | Description | +# |-------|--------------------------------| +# | null | Info not available | +# | 0 | No fix | +# | 1 | Single-point positioning (SPP) | +# | 2 | RTK moving baseline | +# | 3...4 | Reserved | +# | 5 | RTK float | +# | 6...7 | Reserved | +# | 8 | RTK fixed | + + +# GNSS correction status (corr_status) +# +# | Value | Description | +# |-------|----------------------------------------------------------------------------------------------------------------| +# | null | Info not available | +# | 0 | Waiting fusion | +# | 1 | No GNSS available | +# | 2 | No corrections used | +# | 3 | Limited corrections used: station data & at least one of the constellations among the valid rover measurements | +# | 4 | Corrections are too old | +# | 5 | Sufficient corrections used: station data and corrections for ALL bands among the valid rover measurements | + + +# Baseline status (baseline_status) +# +# | Value | Description | +# |-------|------------------------| +# | null | Info not available | +# | 0 | Waiting fusion | +# | 1 | Not available / No fix | +# | 2 | Failing | +# | 3 | Passing | + + +# Camera status (cam1_status) +# +# | Value | Description | +# |-------|--------------------------------------------------| +# | null | Info not available | +# | 0 | Camera not available | +# | 1 | Camera available, but not usable (e.g. too dark) | +# | 2...4 | Reserved | +# | 5 | Camera working and available | + + +# Wheelspeed status (ws_status) +# +# | Value | Description | +# |-------|------------------------------------------------------------| +# | null | Info not available | +# | 0 | No wheelspeed enabled | +# | 1 | Missing wheelspeed measurements | +# | 2 | At least one wheelspeed enabled, no wheelspeed converged | +# | 3 | At least one wheelspeed enabled and at least one converged | +# | 4 | At least one wheelspeed enabled and all converged | + + +# Wheelspeed convergence status (ws_conv) +# +# | Value | Description | +# |-------|-----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Missing wheelspeed measurements | +# | 2 | Insufficient global measurements | +# | 3 | Insufficient motion | +# | 4 | Insufficient imu bias convergence | +# | 5 | Converging | +# | 6 | Idle | + + +# Markers status (markers_status) +# +# | Value | Description | +# |-------|-----------------------------| +# | null | Info not available | +# | 0 | No markers available | +# | 1 | Markers available | +# | 2 | Markers available, and used | + + +# Markers convergence status (markers_conv) +# +# | Value | Description | +# |-------|----------------------------------| +# | null | Info not available | +# | 0 | Awaiting Fusion | +# | 1 | Waiting marker measurements | +# | 2 | Insufficient global measurements | +# | 3 | Converging | +# | 4 | Idle | diff --git a/fixposition_driver_ros2/msg/fpa/TP.msg b/fixposition_driver_ros2/msg/fpa/TP.msg new file mode 100644 index 0000000..47dde39 --- /dev/null +++ b/fixposition_driver_ros2/msg/fpa/TP.msg @@ -0,0 +1,53 @@ +#################################################################################################### +# +# Copyright (c) 2023 +# Fixposition AG +# +#################################################################################################### +# +# Fixposition FP_A-TP Message +# +# +#################################################################################################### + +string tp_name # Timepulse name (source) +string timebase # Time base (see below), or null if not available +string timeref # Time reference (see below), or null if not available +int64 tp_tow_sec # Timepulse time seconds of week, integer second part (0–604799), or null +float64 tp_tow_psec # Timepulse time seconds of week, sub-second part (0.000000000000–0.999999999999), or null +int64 gps_leaps # GPS leapseconds, or null if unknown + + +# Values for timebase +# +# | Value | Description | +# |-------|---------------------------| +# | null | No timepulse alignment | +# | GNSS | Timepulse aligned to GNSS | +# | UTC | Timepulse aligned to UTC | + + +# Values for timeref if timebase is GNSS +# +# | Value | Description | +# |-------|---------------------------------| +# | GPS | Timepulse aligned to GPS | +# | GAL | Timepulse aligned to Galileo | +# | BDS | Timepulse aligned to BeiDou | +# | GLO | Timepulse aligned to GLONASS | +# | OTHER | Timepulse aligned to other GNSS | + + +# Values for timeref if timebase is UTC +# +# | Value | Description | +# |-------|----------------------------------------------------------------------------| +# | NONE | Timepulse aligned to no UTC (no precise UTC parameters known yet) | +# | CRL | Timepulse aligned to Communications Research Laboratory (CRL), Japan | +# | NIST | Timepulse aligned to National Institute of Standards and Technology (NIST) | +# | USNO | Timepulse aligned to U.S. Naval Observatory (USNO) | +# | BIPM | Timepulse aligned to International Bureau of Weights and Measures (BIPM) | +# | EU | Timepulse aligned to European laboratories | +# | SU | Timepulse aligned to Former Soviet Union (SU) | +# | NTSC | Timepulse aligned to National Time Service Center (NTSC), China | +# | OTHER | Timepulse aligned to other/unknown UTC | diff --git a/fixposition_driver_ros2/msg/nmea/GXGSV.msg b/fixposition_driver_ros2/msg/nmea/GXGSV.msg index 9c5eefe..be4fc4c 100644 --- a/fixposition_driver_ros2/msg/nmea/GXGSV.msg +++ b/fixposition_driver_ros2/msg/nmea/GXGSV.msg @@ -14,7 +14,7 @@ # -------|-----------|---------|-------------------------------------| int16 sentences # [-] | Total number of sentences (1 to 9). int16 sent_num # [-] | Sentence number (1 to 9). -int16 num_sats # [-] | Total number of satellites in view. +int32 num_sats # [-] | Total number of satellites in view. int16[] sat_id # [-] | Satellite ID number. int16[] elev # [deg] | Satellite elevation. int16[] azim # [deg] | Satellite azimuth from true North. diff --git a/fixposition_driver_ros2/src/data_to_ros2.cpp b/fixposition_driver_ros2/src/data_to_ros2.cpp index a6cf6bc..8411375 100644 --- a/fixposition_driver_ros2/src/data_to_ros2.cpp +++ b/fixposition_driver_ros2/src/data_to_ros2.cpp @@ -60,6 +60,34 @@ void FpToRosMsg(const ImuData& data, rclcpp::Publisher::S } } + +void FpToRosMsg(const FP_IMUBIAS& data, rclcpp::Publisher::SharedPtr pub) { + if (pub->get_subscription_count() > 0) { + // Create message + fixposition_driver_ros2::msg::IMUBIAS msg; + + // Populate message + if (data.stamp.tow == 0.0 && data.stamp.wno == 0) { + msg.header.stamp = rclcpp::Clock().now(); + } else { + msg.header.stamp = GpsTimeToMsgTime(data.stamp); + } + + msg.header.frame_id = data.frame_id; + msg.fusion_imu = data.fusion_imu; + msg.imu_status = data.imu_status; + msg.imu_noise = data.imu_noise; + msg.imu_conv = data.imu_conv; + tf2::toMsg(data.bias_acc, msg.bias_acc); + tf2::toMsg(data.bias_gyr, msg.bias_gyr); + tf2::toMsg(data.bias_cov_acc, msg.bias_cov_acc); + tf2::toMsg(data.bias_cov_gyr, msg.bias_cov_gyr); + + // Publish message + pub->publish(msg); + } +} + void FpToRosMsg(const FP_GNSSANT& data, rclcpp::Publisher::SharedPtr pub) { if (pub->get_subscription_count() > 0) { // Create message @@ -229,6 +257,44 @@ void FpToRosMsg(const FP_ODOMSH& data, rclcpp::Publisher::SharedPtr pub) { + if (pub->get_subscription_count() > 0) { + // Create message + fixposition_driver_ros2::msg::ODOMSTATUS msg; + + // Populate message + if (data.stamp.tow == 0.0 && data.stamp.wno == 0) { + msg.header.stamp = rclcpp::Clock().now(); + } else { + msg.header.stamp = GpsTimeToMsgTime(data.stamp); + } + + msg.init_status = data.init_status; + msg.fusion_imu = data.fusion_imu; + msg.fusion_gnss1 = data.fusion_gnss1; + msg.fusion_gnss2 = data.fusion_gnss2; + msg.fusion_corr = data.fusion_corr; + msg.fusion_cam1 = data.fusion_cam1; + msg.fusion_ws = data.fusion_ws; + msg.fusion_markers = data.fusion_markers; + msg.imu_status = data.imu_status; + msg.imu_noise = data.imu_noise; + msg.imu_conv = data.imu_conv; + msg.gnss1_status = data.gnss1_status; + msg.gnss2_status = data.gnss2_status; + msg.baseline_status = data.baseline_status; + msg.corr_status = data.corr_status; + msg.cam1_status = data.cam1_status; + msg.ws_status = data.ws_status; + msg.ws_conv = data.ws_conv; + msg.markers_status = data.markers_status; + msg.markers_conv = data.markers_conv; + + // Publish message + pub->publish(msg); + } +} + void FpToRosMsg(const FP_TEXT& data, rclcpp::Publisher::SharedPtr pub) { if (pub->get_subscription_count() > 0) { // Create message @@ -243,6 +309,42 @@ void FpToRosMsg(const FP_TEXT& data, rclcpp::Publisher::SharedPtr pub) { + if (pub->get_subscription_count() > 0) { + // Create message + fixposition_driver_ros2::msg::TP msg; + + // Populate message + msg.tp_name = data.tp_name; + msg.timebase = data.timebase; + msg.timeref = data.timeref; + msg.tp_tow_sec = data.tp_tow_sec; + msg.tp_tow_psec = data.tp_tow_psec; + msg.gps_leaps = data.gps_leaps; + + // Publish message + pub->publish(msg); + } +} + +void FpToRosMsg(const FP_EOE& data, rclcpp::Publisher::SharedPtr pub) { + if (pub->get_subscription_count() > 0) { + // Create message + fixposition_driver_ros2::msg::EOE msg; + + // Populate message + if (data.stamp.tow == 0.0 && data.stamp.wno == 0) { + msg.header.stamp = rclcpp::Clock().now(); + } else { + msg.header.stamp = GpsTimeToMsgTime(data.stamp); + } + msg.epoch = data.epoch; + + // Publish message + pub->publish(msg); + } +} + void FpToRosMsg(const GP_GGA& data, rclcpp::Publisher::SharedPtr pub) { if (pub->get_subscription_count() > 0) { // Create message @@ -621,4 +723,31 @@ void OdomToYprMsg(const OdometryData& data, rclcpp::Publisher node, const times::GpsTime& stamp, const Eigen::Vector3d& pos_diff, + const Eigen::MatrixXd& prev_cov, rclcpp::Publisher::SharedPtr pub) { + if (pub->get_subscription_count() > 0) { + // Create message + fixposition_driver_ros2::msg::COVWARN msg; + + // Populate message + if (stamp.tow == 0.0 && stamp.wno == 0) { + msg.header.stamp = rclcpp::Clock().now(); + } else { + msg.header.stamp = GpsTimeToMsgTime(stamp); + } + + std::stringstream warn_msg; + warn_msg << "Position jump detected! The change in position is greater than the estimated covariances. " + << "Position difference: [" << pos_diff[0] << ", " << pos_diff[1] << ", " << pos_diff[2] << "], " + << "Covariances: [" << prev_cov(0,0) << ", " << prev_cov(1,1) << ", " << prev_cov(2,2) << "]"; + + RCLCPP_WARN(node->get_logger(), "%s", warn_msg.str().c_str()); + tf2::toMsg(pos_diff, msg.jump); + tf2::toMsg(Eigen::Vector3d(prev_cov(0,0),prev_cov(1,1),prev_cov(2,2)), msg.covariance); + + // Publish message + pub->publish(msg); + } +} + } // namespace fixposition diff --git a/fixposition_driver_ros2/src/fixposition_driver_node.cpp b/fixposition_driver_ros2/src/fixposition_driver_node.cpp index e20612e..4300d05 100644 --- a/fixposition_driver_ros2/src/fixposition_driver_node.cpp +++ b/fixposition_driver_ros2/src/fixposition_driver_node.cpp @@ -23,12 +23,16 @@ FixpositionDriverNode::FixpositionDriverNode(std::shared_ptr node, // FP_A messages fpa_odometry_pub_(node_->create_publisher("/fixposition/fpa/odometry", qos_settings)), + fpa_imubias_pub_(node_->create_publisher("/fixposition/fpa/imubias", qos_settings)), + fpa_eoe_pub_(node_->create_publisher("/fixposition/fpa/eoe", qos_settings)), fpa_llh_pub_(node_->create_publisher("/fixposition/fpa/llh", qos_settings)), fpa_odomenu_pub_(node_->create_publisher("/fixposition/fpa/odomenu", qos_settings)), fpa_odomsh_pub_(node_->create_publisher("/fixposition/fpa/odomsh", qos_settings)), + fpa_odomstatus_pub_(node_->create_publisher("/fixposition/fpa/odomstatus", qos_settings)), fpa_gnssant_pub_(node_->create_publisher("/fixposition/fpa/gnssant", qos_settings)), fpa_gnsscorr_pub_(node_->create_publisher("/fixposition/fpa/gnsscorr", qos_settings)), fpa_text_pub_(node_->create_publisher("/fixposition/fpa/text", qos_settings)), + fpa_tp_pub_(node_->create_publisher("/fixposition/fpa/tp", qos_settings)), // NMEA messages nmea_gpgga_pub_(node_->create_publisher("/fixposition/nmea/gpgga", qos_settings)), @@ -72,6 +76,13 @@ FixpositionDriverNode::FixpositionDriverNode(std::shared_ptr node, rtcm_sub_ = node_->create_subscription( params_.customer_input.rtcm_topic, 10, std::bind(&FixpositionDriverNode::RtcmCallback, this, std::placeholders::_1)); + + // Configure jump warning message + if (params_.fp_output.cov_warning) { + extras_jump_pub_ = node_->create_publisher("/fixposition/extras/jump", qos_settings); + prev_pos.setZero(); + prev_cov.setZero(); + } RegisterObservers(); } @@ -110,6 +121,19 @@ void FixpositionDriverNode::RegisterObservers() { OdomToImuMsg(data, poiimu_pub_); OdomToNavSatFix(data, odometry_llh_pub_); OdometryDataToTf(data, br_); + + // Output jump warning + if (params_.fp_output.cov_warning) { + if (!prev_pos.isZero() && !prev_cov.isZero()) { + Eigen::Vector3d pos_diff = (prev_pos - data.odom.pose.position).cwiseAbs(); + + if ((pos_diff[0] > 0) || (pos_diff[1] > prev_cov(1,1)) || (pos_diff[2] > prev_cov(2,2))) { + JumpWarningMsg(node_, data.odom.stamp, pos_diff, prev_cov, extras_jump_pub_); + } + } + prev_pos = data.odom.pose.position; + prev_cov = data.odom.pose.cov; + } }); } else if (format == "ODOMENU") { dynamic_cast*>(a_converters_["ODOMENU"].get()) @@ -124,6 +148,15 @@ void FixpositionDriverNode::RegisterObservers() { FpToRosMsg(data, fpa_odomsh_pub_); FpToRosMsg(data.odom, odometry_smooth_pub_); }); + } else if (format == "ODOMSTATUS") { + dynamic_cast*>(a_converters_["ODOMSTATUS"].get()) + ->AddObserver([this](const FP_ODOMSTATUS& data) { FpToRosMsg(data, fpa_odomstatus_pub_); }); + } else if (format == "IMUBIAS") { + dynamic_cast*>(a_converters_["IMUBIAS"].get()) + ->AddObserver([this](const FP_IMUBIAS& data) { FpToRosMsg(data, fpa_imubias_pub_); }); + } else if (format == "EOE") { + dynamic_cast*>(a_converters_["EOE"].get()) + ->AddObserver([this](const FP_EOE& data) { FpToRosMsg(data, fpa_eoe_pub_); }); } else if (format == "LLH") { dynamic_cast*>(a_converters_["LLH"].get()) ->AddObserver([this](const FP_LLH& data) { FpToRosMsg(data, fpa_llh_pub_); }); @@ -169,6 +202,9 @@ void FixpositionDriverNode::RegisterObservers() { } } }); + } else if (format == "TP") { + dynamic_cast*>(a_converters_["TP"].get()) + ->AddObserver([this](const FP_TP& data) { FpToRosMsg(data, fpa_tp_pub_); }); } else if (format == "GPGGA") { dynamic_cast*>(a_converters_["GPGGA"].get())->AddObserver([this](const GP_GGA& data) { FpToRosMsg(data, nmea_gpgga_pub_); diff --git a/fixposition_driver_ros2/src/params.cpp b/fixposition_driver_ros2/src/params.cpp index a297804..3702ab5 100644 --- a/fixposition_driver_ros2/src/params.cpp +++ b/fixposition_driver_ros2/src/params.cpp @@ -26,6 +26,7 @@ bool LoadParamsFromRos2(std::shared_ptr node, const std::string& n const std::string IP = ns + ".ip"; const std::string PORT = ns + ".port"; const std::string BAUDRATE = ns + ".baudrate"; + const std::string COV_WARNING = ns + "/cov_warning"; node->declare_parameter(RATE, 100); node->declare_parameter(RECONNECT_DELAY, 5.0); @@ -35,6 +36,7 @@ bool LoadParamsFromRos2(std::shared_ptr node, const std::string& n node->declare_parameter(PORT, "21000"); node->declare_parameter(IP, "127.0.0.1"); node->declare_parameter(BAUDRATE, 115200); + node->declare_parameter(COV_WARNING, false); // read parameters if (node->get_parameter(RATE, params.rate)) { RCLCPP_INFO(node->get_logger(), "%s : %d", RATE.c_str(), params.rate); @@ -51,6 +53,11 @@ bool LoadParamsFromRos2(std::shared_ptr node, const std::string& n } else { RCLCPP_WARN(node->get_logger(), "%s : %s", QOS_TYPE.c_str(), params.qos_type.c_str()); } + if (node->get_parameter(COV_WARNING, params.cov_warning)) { + RCLCPP_INFO(node->get_logger(), "%s : %d", COV_WARNING.c_str(), params.cov_warning); + } else { + RCLCPP_WARN(node->get_logger(), "%s : %d", COV_WARNING.c_str(), params.cov_warning); + } std::string type_str; node->get_parameter(TYPE, type_str); diff --git a/test/HowToTest.md b/test/HowToTest.md deleted file mode 100644 index 288dcf0..0000000 --- a/test/HowToTest.md +++ /dev/null @@ -1,177 +0,0 @@ -# How to test using example data for Fixposition ROS / ROS2 Driver - -There is a sample TCP dump which is generated from the Fixposition Vision-RTK 2 sensor which can be used to test if the driver is working. - -## we use `str2str` from `RTKLIB` to replay datastream on TCP port - - Install RTKLIB: `sudo apt install rtklib` - - The files are in `test/data` - - `vrtk_output_1.txt` the tcp data stream - - `vrtk_output_1.txt.tag` the timestamp file for the corresponding data stream - - Replay the TCP stream: - - `str2str -in file://vrtk2_output_1.txt::T -out tcpsvr://localhost:21000` - - Adapt the IP and Port if needed - - You can check with netcat `nc localhost 21000` to see if the data is properly replayed - - For more details, see `str2str -h` - -## How to test -- Compile the ROS driver -- configure the ROS driver's `tcp.yaml` to the corresponding IP and port from above. -- Start the ROS driver with - - ROS1: `roslaunch fixposition_driver_ros1 tcp.launch` - - ROS2: `ros2 launch fixposition_driver_ros2 tcp.launch` -- For Visualization, start RVIZ with the provided RVIZ configuration in `fixposition_driver_ros1/rviz/fixposition_driver.rviz` or `fixposition_driver_ros2/rviz/fixposition_driver_ros2.rviz` -- You shall see something similar to this: - ![image](TestData_example.png) -- Or capture the messages published by fixposition driver using `rostopic echo ` / `ros2 topic echo `command - -List of ros / ros2 topics - -- ROS1: `rostopic list` -- ROS2: `ros2 topic list` -- then you should see - - ``` - /fixposition/corrimu - /fixposition/imu_ypr - /fixposition/navsatfix - /fixposition/odometry - /fixposition/odometry_enu - /fixposition/poiimu - /fixposition/rawimu - /fixposition/speed - /fixposition/vrtk - /fixposition/ypr - /tf - /tf_static - ``` - -and also echo the topics - -- ROS1: `rostopic echo /fixposition/odometry` -- ROS2: `ros2 topic echo /fixposition/odometry` - - -``` -header: - seq: 3173 - stamp: - secs: 1671488303 - nsecs: 752147983 - frame_id: "FP_ECEF" -child_frame_id: "FP_POI" -pose: - pose: - position: - x: 4278393.6861 - y: 636074.0115 - z: 4672249.8601 - orientation: - x: 0.249904 - y: -0.255811 - z: 0.543161 - w: -0.759661 - covariance: [0.01508, -0.00352, -0.00264, 0.0, 0.0, 0.0, -0.00352, 0.01174, 0.00159, 0.0, 0.0, 0.0, -0.00264, 0.00159, 0.01604, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045, 3e-05, 0.00023, 0.0, 0.0, 0.0, 3e-05, 0.00024, 6e-05, 0.0, 0.0, 0.0, 0.00023, 6e-05, 0.00036] -twist: - twist: - linear: - x: 3.277 - y: 0.0535 - z: -0.0513 - angular: - x: 0.00393 - y: -0.00585 - z: 0.03451 - covariance: [0.05008, 0.00475, 0.00146, 0.0, 0.0, 0.0, 0.00475, 0.06413, -0.00292, 0.0, 0.0, 0.0, 0.00146, -0.00292, 0.05633, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] -``` -Other topics: - -`/fixposition/ypr` -``` -x: -3.08980037375 -y: -0.0306836361218 -z: 0.0242531245715 -``` -`/fixposition/navsatfix` -``` -header: - seq: 2496 - stamp: - secs: 1671544327 - nsecs: 933986893 - frame_id: "FP_POI" -status: - status: 0 - service: 0 -latitude: 47.398651066 -longitude: 8.460000567 -altitude: 443.448 -position_covariance: [1.3144, 0.26529, 0.0026386, 0.26529, 0.20829, 0.0003131, 0.0026386, 0.0003131, 0.072502] -position_covariance_type: 3 -``` - -`/fixposition/poiimu` -``` -header: - seq: 129 - stamp: - secs: 1671544394 - nsecs: 97284521 - frame_id: "FP_POI" -orientation: - x: 0.0 - y: 0.0 - z: 0.0 - w: 0.0 -orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] -angular_velocity: - x: 0.00949 - y: 0.0017 - z: -0.09222 -angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] -linear_acceleration: - x: 0.0643 - y: -0.524 - z: 9.8803 -linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] -``` - -`/fixposition/imu_ypr` -``` -x: 0.0 -y: -0.0 -z: 0.0 -``` - -`/fixposition/odometry_enu` -``` -header: - seq: 172 - stamp: - secs: 1671547910 - nsecs: 126985755 - frame_id: "FP_ENU0" -child_frame_id: "FP_POI" -pose: - pose: - position: - x: -21.0624576159 - y: 86.8736442636 - z: -2.17882773687 - orientation: - x: -0.00429835026653 - y: 0.0135503346719 - z: 0.980623523325 - w: 0.195386113884 - covariance: [0.01680222578893909, 0.00300224066714241, -0.00018696977599586342, 0.0, 0.0, 0.0, 0.00300224066714241, 0.02108652020855367, -0.0017258279185579117, 0.0, 0.0, 0.0, -0.00018696977599586342, -0.0017258279185579104, 0.03373125400250724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001549265219747773, 4.2393809056184216e-05, -1.712745803748877e-06, 0.0, 0.0, 0.0, 4.2393809056184216e-05, 0.0002442723978313275, 7.356418678410831e-05, 0.0, 0.0, 0.0, -1.7127458037488635e-06, 7.356418678410831e-05, 0.00019080108019389524] -twist: - twist: - linear: - x: 4.5631 - y: -0.0224 - z: -0.0579 - angular: - x: 0.00157 - y: 0.00936 - z: 0.01756 - covariance: [0.03885, 0.00642, -0.0015, 0.0, 0.0, 0.0, 0.00642, 0.05358, -0.00514, 0.0, 0.0, 0.0, -0.0015, -0.00514, 0.05575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] -``` diff --git a/test/TestData_example.png b/test/TestData_example.png deleted file mode 100644 index bcdbe376037b1e0fd85ae0af082a2d82605324cf..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 34455 zcmeFZi9ghB)IZ)vA~#xwC`$_^TlTC)5whHti5a`XU~OzF!f_e#-Nvsi%>vy{C`O{d@ZyaIV;Uq8@hl z@7=?BIJ$Z+9jsS@H(l6!lluL8Hl7$)9KSIJdvBk{ef}%5{5S6T^GixdO2T6WNl67M ziGACov3>ja_i5d@ZtVMJffn#0d&6RUz1yS9qj>vGUFYoLaFUsK7>?-%9X(h)y=jz2hy?y_I$MHilSS)sSjjqTXI^tJY+%dM(Qnd;|EjcNbSd9ie3a+|#lI@OFt>vBi z@r3hO7nfVH3aM*;b?5g@e+ZaLa`>lv>*l`7(>t}^>bv%W+pU?!mML*NX87XzIW1Mb z<7xFlO2%4-_xcC*ORy?CoGeO$*A0v^3=GOljWZ0s_$ndc`@}>>a;M;ao=OcS%09zd zd+B~smMdp?DO0|0b>f>bA7RERbRs{pJ#GPzAgA$Nq;-o zDopJ!+)Erf0EIhZq1s{Y$ zqgg^kwd$6fC6gX+55{ZX+}heQE_rx4{JG2nhNV+%tF-mB0e!q`P)^3?RyFIkbpl6F z<(tsAIdCER(o&&ezN0j^R%|t`cyZLv5Dcuf6fd%0_g6L%K8Y_Wd6MCe#YX)K{BTme znfuzzk~g=1z@*=H52bI@AqErMYQ@L4dO7lY(}jwf8lmoGL_sg+**W zyy1szjb`o#=V!NSScC3N`)x0@OtK8bG7VIEf(=eYVXfBCidCZ;WlE3JnxnK~$za@h za7MTrM=VxXQBe`@MJL*t_1bEWfh$(2WC@&(FE6#bW7c&>dSy}>rSA3%+)c#%wx_yR z{rH`VVdMJoK|Gq=zqD>5(ltF(gvZZjCs-PnnI3(#(a@j{x20tW@2a)TRX$Yt5nO3S zzy42Au-7{4=J%^%PFkBpYa><5doPcQ$?}vqWK@kWIV%8&(C(H3N?+Zaz{0$ z&1q-9b0St7bb8aOmhWaBBM#)1tneVD9pf!MJ2F z#^Sb%YzhnKaV!7X=AY}F5jR)2w%z=1l?}wXf2j;!B3^NR@mH6D+zPpaS-c_$(YWo5-C zep7q-$a%!~h~{_IG%*(Y2Q1*?Zk>VCzIm)m_rvG-W@J~+tyoT8VF^v4Y=}e zuiEN}nBd6GW*nJkN2MmQvc8@Vna%bOZ#edX?3IrN!(nPRHoc#AcIwWDnRsBvB6L@| zD^2rE4-S4>_u?6eTZxNt*IPCF!;>0L0o>!`oN2sJTnq@4XK?YB;Sd|P;f?~$mdoet zCkSJ&d5Y*N#7&_I#MP4lXL2$&b7NtNv^qnw4xf{8+u8fvj|oxX1@ph3fS>)aHj1~g zQf(M@escvpEq=LfCf zPig25z^IF?5uQ}+U2|c4-9#(_pfT?-+Zya&j#|dsrY3b=!Q)t0*C(9ECy{UU1&>Fy z+WDpB`Uh#!y>$SD86K5>%f39pRH_PAk32`q^!^ zyGo&~UEW_?+}WvHF!TU%Chn{lbMn7*xn%VQCL&GU=cPPY5|Yf?k`XhX&D?SKHe0lIfnRbRHDR;{I+xy7QNrHhOrQ>fdH7o?$V z!+&A%?n)lfT-D7rf_+y0^-)yWx3mO>M<6Sf#%c@cbS&)sNoEEjm0o%lw@gY3VO6p` z8&O`0O=35Dc@Ml1-E)Cu zlDGPg`!|qo&SC@mYR^IjY_8tJt7LGR-OOQ#r-R~p=m;UaT zW?zvc7}r+jL{h97DHyD^)ZYkHaiKGX^8d1ZXHpR-Ca4_?w~2m+?(CXgwz>R#`zof6 zLz3x$*7ERBtz`@ZUN{8aoloS*C!20qqxyg-b>c>pn$~U`1zQ^s=srlA{8skMe|~-* zpcxy#;j5%qo9H;;QYcOBn1A%>3E&o0d?PiCm-b;}^#<|$a2 z6kV-lQlwB?<;n1=VV4~E@~$C%**y&as_g;kNhSRbkONPJ0T)@8*16&48}n6TLqqb& zPEy1(8qR0J_8oPX?l*SXZfz>zyl5ae3M=DsPcS6}yNd=ttqoWw)YgiQuXAoz?0>`C zz+HL3Qki@1QG(mejmh7?-j|5;v98{1lrbC%yO}a&lfXoO_m0|Xe(^-3Xe7h}#5fzD z%I(_3#O~=Ierb#2^&tzk-$q7~!<#Z%Cd_-SW{;4|-!z+dtTmvw689Uqz!* zBQ!PDLN~XszgdKG;J&Xf7cyJ9J5IWUxz(hCwlh8Kf*?IHl}MP{?(VcVBI9V5OjCOS z>m+mX&_i%H__7S%_#v?nke1uy$W`~+QHJ`u<+k8)KnY0w{a{{{M$^ynZU;NQJj;?o zQ<1ji`-fbR(rLD4)lW_g6 zoV4AsuS3lrElYSv0hJA-1;d^8%kZ2>ZVrf8SIZ6YHCx*%bBde1InxTFpB|gV;Nhcw zmym36@r1E(yyxytkV)Y{*oP%Xk14Bzxvf8Lem&+7Y=IoJxw%hyK{!!{u9+JlP%t1`E(N`W?JDcWT97IZ7k*=h+-= z;wUvBlqLGZ5rZ;Dv7~w$W+u(*OMSti>1{)??3n4GT5suob(GrA=c%c*Qqi-;wx{VK z-kcS;mJ#eVLo>*1eEejD)tft!nFB7)^il)b()s|7tnYcH%;4h1g!b95U#|hUO*G$d zmcq!U*ffvg?Yr%z2At-d$mrieRzL2WJ$dqkh3723Ic&$-+N&S;KisZ6S~zK~Mxbl~GZc9pJ=yT~?`g|2a@2XC4H z*Sr8&k?_&Sn|m{`>YbIKvBS5dVPn@Hl9NP-cI&y-)S+gPp6BkU-3q)?LbO_$XtMj| zme^>M3M@ml#ccv5&T)5H3mAv0dxYbt(;8eGSPkTZpG(BF`zbHJ`K3V#vpx9Xm~qiV zov(lh!2(15hmQ;-Z49Vs)h-8f$lpN*iJo9?-Au>6CQ^4#lM^o#@A^q5II5Qs-E%vUgin4e%8OSIk@g`xCNi$vzcXHWL25o4Hu>#gqFG%85uCA^f zb}6tdF{)*>-P_^Hl2fd!&bN2uk9SW61#!096$3@YJ*jP@>;|qcT0s6UG#BHW4^e5e zMHF&R-@odmkm_b`nQyF34|#pQd%1DPLCdCDeq?t6S%H^RWI6zDRQkkUI(a=jrghTo zl@$@CYhJimXO+TrEcJyU9x1~eWh{cow>-!J;eTLjQBS@8^Mz)qn|XCoM?3j$utW_gRh?UgAfd$Zvstk#pa1$vies3&CgG28DBzxdKHhyx2*^5 zRZTk;HSrR-or+a;9nIzRpm9~%T|WqKVy9X%`GIMOClO@=s9zf(?u^BX9?ij}gw@Kj zK%ipxyyFyBYIc2Vf~1k6_6_%xu#OewLt^TEmhNdWhv;V*FpZaBGYC>N**G9fwq>9G zI-6gHaAo;czu2k1s*mqEa6iqmYiop;bpVL*k3-i*M`O8CcNf4BvJCTI$?sMT&gYwp zIZJcTwnSA|({S>;S5a4@Ayj%#gX0+8dUtZtG38k;X={B6WQuUkN}L#wuv zdK?qEJ6OU(?JG`EdE9@1FM6!WwW@EQ%yljvAGj4O?1ndxed>e`2v zc(qc-uAUe#p3U@j;{x%5m>)s46|^r_uRcTC{K@2Us-t|zA%$c!Fdw(3iq5_YI1Z9V z(}a>s&A`Hhn{UzXMoW}GS4Sqqkbq?V?$t|)LaP<1bU0oOBwSOy#lajIZq(S}47L)5>LmSzPd($QVoxTxA?H8tj1T=g9i9-+VD~8W? zhPI5;@SEm)AO{gZd5ff{RP9}8cOTT#^)jB`6`X`T{h0_lPp>POfMk+AJC;E&6k z^}Zn)$wA3G4(r>f=CPgHr~&HO*lTIFsWs<9`*n!*F=9{@wn1-n&KoM~@f7bGJXCr> z9uB#fqdLkMyBgMk+1shDX8&rl)$-}uy7~2E=vxwdLAGB?*em+qX>eOmB7mKWAMK27 z+~^Kd6L_PJT~4P*Lb%q%h9q#SZ8<$|GaV0AMpRNn z%I;}Am&5R`i^*i)nkt!!-KeWKh_~EBQ!;jGu;BON+!}CP)HT64ts!1JBhz;drZNGt zDQ8k%*m5f7TTV&}m>!&dU=Vb5Ajhcok(NM0sD)`HkJR*kKH#?FVF7G^sa!_gwtEX1mH3TZ87C_E$aCpKXRrv*2yxp@@u{NEfiS zG9^|2J#RM^%Fm=ZRn;J^(5cp|#xT6T-EUo|4GAH7=I=C+42h>Y5zYe_E|AQIN@%Pv z-8ql<31*D~ttcFBnve)&FYAoSHoWBJIRS_zU;Tx3YE1@5rsg*&RX=U9IP6*yw>ne# zbk6|E&s&e@E`O8qvvTEQOFDLc|FC3YTy&B%nQ9{=$9-GB&;F&fy&kG|cbN9Vw|B=O zz|=H*_bSe-2J-NHh_@!EM)%WbF;7*27g-QHfhy?=)e_YLy=N>;p&;fu3iTYQQ=I=a zaQhzJslcg+++z6@-(rmr?u~PZ#l_8}i&IcWIP91;E8uu~r zga7c93@)wz*jj#)))$?`6VrM*Dk<*OaAFmxyC73J5evL)PKJLc5{YgdX$1MYZjF5i z<}l!Y6~p}$iZ@qq4Gs5ahc-CqL~I-s>})*$vlIWb*SbV5-QFhQP{nB}pIF(5xX7dm)taKt#?AEX@3IjMZ_|f%U1~p@ zt*e$uR)4Xe@yb>(Nr-55uy=lUrBvp4svUcE3Z^t@uoSxUdzCLQ^ zO0?jqFO=Qej_jr@p8wUY>dRn_xI;I1*L%) z;^pS{7Toh^@7o%Cs_dp2k4A4|)l4!S5@K{!g*7hTWOkvY!)$dVw94d#GZEz^5rgy) zO+-tGA|m#@vwEAb-CbCWBeT9NEW*X4T*8^GRi^m^!QusPJ+)Ct57$V`mBk*o!<(@g zIP6r$|YwVeb84~(UV zTj4Nh1$d+pFiQA>Xj#bj*4!8_PqDA4Vow$VWJ;-Z$*Bwqp(T9-D(IEt`(Jt74=Rzp z)B)Kp&?V&0RZUzIH-5Ane9HIem@@Aittnc?;A`KrR#6}kgY(ek5RTV=meC{piL!Ni z@bd)8>_%&cSxOjwSVb!(Oi_wTl1R(yY-|}d`xL#VT7yMk8vaUS5z}SW%9tEqNE!iH zs4lE)FVv-i%6uY3=ju$NM@!C zW(p%ygY&D99igN)qI+K^?p8rd$;0C^X?Np176EzWXj>t?b12I4BRE2-leb|?Sk&R$ zP8IT4iG*@AjrYzK{p3rylFqtZP%WSYwviyO_qfP{4AAH#yIkUq+}nviIb6RCH>x$+gje}zsK>P3K7kQn3QJ!G=Ie7LF8g(xc*|u zzGv3c@X6TRISr$JlYSY7=`(1sld8qV! zXp9jan7T!Tw`9q(6xySIzB<7uMc(xTXUUTARMAekiIPY-5&fYZWI~Aqy)pY9x_69; zhkkjraz6OESB=XN3CMj8(mLi@JLaM z?YFnd7`9CDthQdpFHi|9 z{UXwdzQ(H($hG5go_Kip(XAR<&Mxc1 zs3Pw&h8q*G2DhCnenM&d-nmeanoj)5GiYx!;3AiZcGd(-N5enO>?s|w;863co*>)* zRn)7gt_4-vQQFnx6nLkJ${t{O1%RpOP8AF=oC?KM((jG;_7!H89DO8omzABIdrl=W z_E5uLqZ?@cJ?8u23}*)#Z_m}CEH2d6=cy2+r24gTg^6;Fv85@)k~W`r{Xys?_}sQM zrjXTk?zJ`M$%L&AP=-wTj^0xO>0zI786Sb_b>||V0 zCK)R8;^F(H;|1=KqLCX_-Mjh0nC+>n^~vqxOitj*bL%l;TV@P0#hveZ{pu3G|MLjIzF5{KyWh ztl$1hN@t^WTL11FioH#r3U^evcD5l`2V|0=Id7JHs5DxGm~ED*luXUmb0`@qmaW_x z=YRx3z~P2?%|DDmp#0uBpiCDqg>bd1r zRTsLK|7&MSK{^^GexvM)bl!;rdNb#(`1!~E)`F_NA}#T-2T!372(F+~{Jc%(R1`}@ zXUm8sYEnhAn!mW9xt}ymlJI?~a3atwJodxAb@7q;-GPG`vLEp)%aF`-ymvBfl zkvb@p-`S{EQAf==t6eTK+cJ&5X)=mD^`GI*wmIfu9lC5+i{C2;-z^D@` zs1y3HBXknT(zvnrZK0>mL#-V1)FA5Kj?&Wnx#n`5e_Gm%Eb&UptWig`%1i#du!O0i zUg0yVov4)Sy-f1t3vVGp#T8pjJn+fjpm^oG&d!Qgq*0#;vd2;iY%>3T8`+DR*S(d? z#iDsR*r$=C;`1gRG$#^u*QH^Uq%O$dAtz0B-eaFs-QE)j07O?(kUrhn-eDxHx9`yM zjPH$r-8C;FOS&f82~Cgo$(C~?P5MMs{L&WpKTjg3)z1Q>X9_MK{Nid9^zpe$-1=(6 zT(ydc$UL=0-6Y2-=wX|{<>BGsf&b|>oFQQ%K?QWBq=uXxOfkDRR!+rKGScV$!Imq@R?f)|m1Lp8eBEABPGvCkcJ@4Z9LmR40*r*3XiwgZ8}2 zBn}Fq_Lh!j(RW$}QzKiygH!{bmg?IeQTR>6^s}?`LFwD;aCh+Aq|E#HNc~%(l8}#yk2aJ86aN|OH(B~(^$FuIq zt;vuON%tl>;&MvgwEEugVb;m*^ULN;U!55|1B5L*S6M&({L%dm1%^paW*ub)3kJP2 zI!AbsGy#MW#;fK(c*x#!S6b)uxVG;fCpqv84)MR9wokn#Q}J%Ubw+(}YPKhNL<@Oz+@@Z%Hs>#UVnAH3`C=cv4#B zLQBCgrCz!4RZL&xJh?ZerJg>NB34xJkUWNbtFyEV zPpD!VQT(IUxc%bX9oXI*z03=msnXz%nGH$`n6rzKCc^k$rSs^w9_pFYJ;Byf-Odmw zdAfAih5Tga`ZXo}x}{b<8!hIko``3;r(zuGlCrbk&o_+LCi=#TzFL!-Un`^1_E9pe z*kElQ@2w4h$J(#jte?kHOi*}X(~_n0dda2jj*Bi+l^kxEc;xI~LEZDBHSXeqz}BHr zeJh$J3gJle8>iS$!oqxUygoqJB}w2wb||P?bCyeN)wMArh4uPRPEwk3qcjN!)~&1Z zZHUjn{Oi`Tw8Y)f7ioy|Tc|40ThI$AvX|Q3bOP+yC-w@eU_12BtndF_7c+JM_$}{N z){&Zi`v$6@a}lfnW;hD^5TR8y$k789hLGngh~fk){-;;7iAQGU)@Z~t3OQ9eta;Dz zVU(z$;rfum@zj-Au*ZU}eh#6%B`tvK)saqY#b%h3cvY(5b??byO`k_smrF{-LS^=S zZ7kK|??F7R)GiED$CNRsC5MY5R$PVzSi9S&#am-$>QEQMvtxJk>(pIlC~AObg!F*RXwuDVTfn0JY@!WKkeyzf-KG*g zWStxnRHi69661yDe;1E*PI!jPc!dxTC@v2Jtxw#-+sei~?N&&>r4{QTXKRMXPG1-Bc!si!EA0p-%#M34^}tK-3{kN} zon?H)GE2Os-RkHyPP{$UR5^vKd@k!5fy1pG#V;}nK@kaynmvF_$_3vd8)ytZM}LJI za3dR_9z?Fa5=VP`jEKHk?0&B7Hk3V(Wt|2rL4!7&hCP)p?_3&ZFPn0SgN=AoOopvGnV;;l*of+^)d501=<=&2NC zcZY}{?hwK}EG<~kLi5LJe8|RTcqY(pKy)3j**{p9({azSF8bEYPSLHxC~Jb$Hw_6vSR1x)bC_BPGGoCWzOLAm+9Hv^>I5@AUgXSN-C+9sZ zmCw*fQ@eV)3w>8_c`}-i-B+7`3F@&in*|cV)fE_?EJN8$hWq2_<+s1A-%o>Hk@48qA|F8 zk-zA?h&59o;gtM7*whC>T6-7SgOqBodGDbSjx*hB@+kfy+bSoP8znx{43h*=_C-@==lzw; zqU?{ZTY)MWnCk9u1GfAr=>x{$JRqfYTKf+%8j}X}Xx-8Y2CWF@ssv9eU3PLq>PGUIAO%jpTP_Hl%34#`LMlSZDsVu{{a?-U*sq8!X zgpm`kOvnaMgwPikF%mQFdkSirY-o?lZ0S!vsL`w@HP19~$r&kP4rOjDB(z`9^M4j? z9qH^*K4>Z&FP++D8WX%9WS2ur+%PN}|Mk5Uquae!Q}{*lhV0)1e4-4`~x!HigLgv&T_PB zVlgXWMlIFRk#soDyGB$ie?k@8+y2+N?_aS5ozo4DYzDH`;`Cmp5$4TGeWQh-nu;$p z_lIjAUUpCKNil7*mGV&Ug(}uYTfSvIBrkF!2<&vz5gWxybAfb?;yfWOZ5H769pspVqg3 z_PwgK#x2Pe3%f=*uov@leAnb`%1hbe|gVkum?uqv3V z`|#okW~kTZJQaX=DV;-Mf?i!>$DQyHV-qRFRTB!{*Ua`>#4HB$(SwEu|26z0^&le5n)SxtI7@ZDH`*cBd6?V;UEYt~ zl?3-;IT+_j$msGnr)d`wxE>dcOXGW;GOp$`ClipP*oU8f+~V+(3GKU!>oHr-E^z_{C5e z_A+Iz8LL6ZgZsNagFFC44L6!sIN%gMU`Cd^idPoMXP#peV0noP2sOEmwS8(49_g(A z)Ol}TphomjCZC5?oGl8A-(T=s2yDV%ZYLR}-5u5)MQA&hor=% z!`9D*1b-0jPb@_Vx@BHOj5 zYWM~k)=&Q|&R(m(`QPduyJdb-y81U&EVL?~l68a?XEK5(RMU@OI2-f~8Hi)wE3a{~ z?p6#h7@HV4?>B?w1ytiTtMoGKF-?N!;%dZk9$Tm zgU6Po*)5op^Tv55-}daw)^*ZC=S}Lxxufqd1g-kl9(S!K$fjpqiP1_CqhTa_tSv8| z=y#Ons_=QpQMA8xd{%lze=rYu&>;f~uYdqFD1T-2BRJRc01lUdBdky_5%^EkG9fr; z-VH1`y8ixm+OlrNRndZILBQ3PxLr0t=8LJ(~OFjD`O&k~fnjN-_EX)R$ z7FH4!ga-yeRu&vdaZzqsyp2_C3ia!~jh+1?eTt=%a=;d=q1AV{w?%0rm(kshm-YpQ zE65jG$L{ndwjv9wzU1=C>9(9%9-3c;nb@v5)qnR6t;rYsUa=ih-Gc)bJK_F__G}U-X-AP!1%CHv|I* z(A;EG!qT;Gp(+y-2nIr^cvooUNfGG*&MaQX#L;BW`p8^2;-Gn`|A7W0e1*tJ6` z1{|D^MG`gDE2wGKSk6L%(0K*{3~}wTS_V7gs^i-TP&fYQ7lc;tDV#c*wQab!5zhLh zKgBO}_eY1@2kdU|1m^fa{u=e1Wn3owOot^d_*E#u!5a+pUNcu}Q?-4I#?V zdJk`~UbR7MFfY&+64TRP{s{-6P1wAye|QrM7A95v^6$|>xq}m*T#=?9k2md~kVhAZr5XCG$N3vlIP@_p|Qx?b2AX zQ$Q#+Oab@DM;u!WE0mg_N~nfv&JljM&Ok^kF;}#|%x~WPxbuRS zpl*?wtafiL!D;=7+b=)@t!{T44*BDdU8nt?oz#Zishi27JcMCt!~F9YzkpC4LygQH zwE#7h^cZ|7xcLJTSggp<^qO{yS#BObl2-b;oM(NBROSy$uLUJ+5WY9Ebv!IwEtOn2+KFw`(L_l0mxh4zKycLsa}Smlv%aZO6$e&T@+S1Py*#; z8^yDe(wQSGM?R*h_0JP^IK2VGofv6ujQnXseBBKu%7d)*8JQJD!oz(@Ab<^cDp)Xe z;%=4A9x?O}>pk#f6|H&s74D=oDr1yJL+2|C;MFh!ZDX3|^AB|MN?!!_t{w7;ZMBwQ z;*%H^&I{X}ff%M97dcHG>`BeX3P|CYbqLA=m_3;F$ypO-@md&6n{ESUAhR9=3*2Q& z+FMr5!O;@QvX)@`%!%=w{PR(BqUzu+^Wy3}UJq9G zf?&JwE8P4w^Ds#ig9TCT6f0Wmq&9jZD0%HM;htP9qM(Md_^nGfnxzv%Khl#lf|F2% zSseC5!U^px6XUcOl}-U_o;jo-Y#d_lV<%$_gwP)?R2~TBbO#4mXZh1DU5sR@Z-}`{ zV28F*LDevf8Q$~<`H#=5yXJqaWXoDur(j;(Y4w77X$x_^^~o~xkp~My;Wtw>Q~MR% zVwtlQl^fKa!w{Y3Z!pdIOzA8KXljl_3c6vvsKf8taUy@IpXV!?0p^>TfBaf|Tp6a| zozzo6L+oTq5oy-Esrhu0P!>4cQcO^_0UpWOSkKb|=7MgjX_lmaTxBNm(7gLp&8R$gW)$9gHyTi5wSC9i|6nt6=nWFqlQcnpEE zpR9(lagC?!XCc6l#%aF*HWloWb+ zh!2h&ppk88_J_L!tTM!+l9FqYXP1cp6DtQ6AdKkV0omB(C=I)b{pYZK*+EhC zxY)M4vDE}2ERNjCNdC#U?ME;W6}1|XV%v%wtcirvRS#}6To*lh3PiSN`_FPGPZm6Z z#q+@v!)ghXhcl+Nj~*QaeNdt!o54e?Y@!|pm5qh7i~s%;YCX|wj|%JELwag! z!Kd2|Qoqr|qStF3;|?i^7dp?aqnzpWb22OY_uz44c$oFz5{!`9QICI9^Dta>Gn>Cg z@aGy-uzpApG(L2l9jAYrW!D{lP!`!eA`vV6YH_A=hEfm9?UO??xqA4~^@UL!OK0!D z0gYOmbEa&5y=ti&gPVEDsgPvwa#yh#(TY5y7MF1j(6{}007Lk_`r+Bc|IPxWlMGrd zE{k0dr(Z%uOw7MHu_H2k(5m+oVyA|-cut&Nwv?`Xw6yx~@3W?pBb(1G)m4!{de6Sd z{+}X!|5=nWp@1el&=jZ=Qsl)iCaqcc#Ji=O@-S;IgXb|c2`n~5FCCrA#hkf?+Q3ez z;=TBBxOD($Qwe>*nluhjMw>!LAG4E__uhxtp*wTRk*UEUBeJ^PI+l4L(?DMQc^?BS zy5;8?FbPS<-J!$2qO_YP_~4BCCMy)A1Zl)3=eNf6fOLxk4lsr3Dr7S!~cr|9rn+^%2-H;h#6t;Cqki zmYxWF8L?aF3#-&k!2KZ~jwBGjX-*!VUTPb$9L-kl8U8B7y1UqI2Lr==jP&V?SWL{e z(mzj{j6~^Wha=$(6_A^3!)If2aDFh#c~+MmzIbPtz;yQ#w7(MC%LdfRxq~W{?jQHd z;+4sJHu85qGVm-9H({e`okA4rjVQc;?cUjOoPQ7&!t%1`%X_E!Ya^ds$zC7){rS8y zqIq^;Ux||<=sY8+BG=t_cecY0XA>am^ZUm%O9mC!R7S1EI?)&4{6xJcrd!y#nI^@1 zZ_mswdnvD)R5#f_1v&u>eGEPt3IlWPQF~@uKC5%$*MZZowU%s;tO(@}d@Pr+h03H6Er+4oSUcr!JwIKkEPaSM5tiLW zwbc7nfk1&$Sr=8TI|3@GLa^mx^fH|kZ)o1~9o>Za`;EY08&9jzQ)?Br>0(2V`pUDF zqgomoXX-S~M&ck{HrB6(q$`h!#)2 zo*HNpxg5~b#*Mr6EZlychjg_Kg$ZN;Au;p_=8v^PuS1qP21NNcFy6JC8r<)3ggaJ8Hcc zTy1St1DNg3qe$O>4ugqNwm!|v8_ua7w`XP`^bi{w_P1LXGr^jsmhiEyI2ac`+?yQ; zzkaqlnhIzcugvm}6s?%ho{d}^t@?x+P+zy(?r}Vk#zB7B-Q}iU5%$aR4~X~(SsLYG zWtl$==m~UghEI|>Ta>L~Krh0zu;{P%pga2BRSdq;Q<|)Z`>`&p69A2U7=HbBD#jV3 z-}Jt+77GemnZV)Gk`Ge@*v3%!v#(3=(qCMT>7of0w|Illg& z>@(_Dmef1Cq!t?&CgLG{A_AGv8iY5s2$td4vxy_#iGS}@&_7$opjF7PHXe8_DxtM0 zKe}ydg?i)9fnU&yn6J$C`??yW>VC#2-?$fMY`dSP?^pd5unhONZ@G92or62?t8p<| zgM&$s%I#RB-lZ^1QryuJKC1Us+Z1ptyO{Y(`cbWX>LNUhYU5pN18v`0ZAFcy^FcNtU^M$F^qOS2K!?K(s!Uc#}mp*Ga z@v;4>)^hyns=^}FtsNBinvCI~52eCY4CREMeB_tn3ZW9*$@mywY3_W3i;t&^e#2&c zb`AJYx-NX_XlXk#xP}eH?SoYgL!L<{h=Vs(8*Xva$e(TbXC3jrBkGZ_lz5c5JMgXJ zK~LSq^UJIM&Iv%0`$N%F?><)i@V1MK%jf0yL+xHYCc}%Q_a=AlL6808OCN8Id}BB( z9`s}Nv_(gSS%;Q`X_zebTzYERoWdd@ZH$mKg6N>qDQbIp<9|nyNeY~m@j zPt%s%1gUb;g9*YrBX_6uYUSGs7Ld*=Awz;Uipqtl!EiXMDfnxa$uQ256f=b_vK%=DsuhY5TMOL5qn;P`=8G7V+&{H#6p3yG(Hd}t5 z^AqJ#-*_b!1X`5s;)&n(b{eZ9WTtXgc?yo2!Q2=Ke2_6frYe44a+-CObMOD6IQmt) z6bjO3CwhkK-KoEk7V&h;zzB4FD&eIoFm*WR0w)}Qm<+qyt-_qjw^Im5yjNqFGF@SD zW^}Pqs))g6z-u(K=N24MJeq5HOIxYQV&lv@dz>_nk^)(AHnLBQ@jjpJLLUppeZyb` zSFto(Tzzs41`B6yX>krSAmxqZdIj^^sNVVzqVYxtH<~E6aU(JAhtep8l*JI zvWkkD(tC?ph2?Rw!)9TUIJBjwiFdDtiVu2B3wf^wV(kq7>`@j122xriEFDF`X1;Qg zw9}l*VbNL(2d;teb(M~}%>GeWG~u;f_>Jj31^U$J=R|Lf*O%)v+n>C~pCms?j3^Cs zRFVAsH9la!a>2kIt_JP|N=%)PksK*VCdG)p_-Avcz5-to5^&QsFi7C&@NORUi+%+= zvt z`DJ(2Rj_?ma-Yr~6Kv*G<*eBm)=138wpU!6*UNGnG!@dNz;|jTAqyX}2tXfCFaB$J zZ_iHhmcyN^>dALp5>h$V*(+Sm?9~>C*uJ7ky#Ryf;hoTLUO4Kr;|mNq@Q&F=kms{i z$GvBZf8Ez@L>2`EtC4^IMV!XpXN0jll|7UBwi?a^t?2uYP%q64>$9#@-$__05Wh4V zmJsg0W^}N&N@3uUzYHms_3K?YkA~Tp)2S}1D3#+Eh=BWbZ6vL@3%*Wqo<%QhOykrSHUZ_DZ&V4+Rz%&Ba`2+ zw`t6jZ@Z}u=d!gqS5n}Fy6j{}8$7JiPeG3na_W6;^3wlKSkU|$`=WGbtMrZ97?B)% zx|tWq(ETU-+|Mn!*n|iD<+HG(TLx3%RQ>;J?<>5T{=)yKD5B)YARUMzDiR_osi1^X z3Je?#!e}H%qf#nqAW94orN-!vA<{VzM~z0hV;eBycPHQP`TY;S^YeH($Kl@hzMuO% zucx2O?h`)^cHp?KF~kAn>wVXA18V{Y>mCq7Co5vxbRn<_7C1|HkA9B8Ss9qz6lqg1FUd zQ1c^)O+isFO}3|5L9$zGq+iS>#~$;(Kd-v>K_jQ(J(do(ngI<9`Wq{s?jW_cz{miK z-jBZ*dY!*|UW-sujbDD>W#}126hNq{I^=u+0h6Yo;~(`Ur(o6u@t7i+w0}LbLh@If zJj}!$n=n&avT67PMgQb2@OtPZi%XX<(TzY9&h?J^bj9E}144{B?sqa5HyxU3#jcD}Gg<++-JN7<8;Im*-c7P%S^v(8Ai(C-H6U6{3qY&{eWSg)_m z?GwWAt0$!q@$|HD!vmxc0%8|91ICXiTCQ3 zJ=zUJ%In>`Q?s^bm?)5$nWV74cej>&3R<)FTgQxCnh-c!A1QO3%KXc#JeqE?-vfiV ze+$IDC6QxP@L=YP{NWw~%o6~@%O34Z03#8A%dx)?dIar~}x~54_+!|1U%^RRj<4a zs9$5y7um0i1G%jU4$=@o>unKi5-3>c5m)|=)+;QK6(V+9c)H$!^uT9Z1(sTFZ-%uB+ z+4{yeKht@Q^Z+AME4S;1FPrz#W$|zTs&eqmpbzYXz zW8VcYb?p)1R^7*kBZq6>6bi@iy2yvVgnk$ibh#fa7g?1IiPfx4sv%dSwjR}L<Wtr2R!LCv*%y=gcf7^C8@(#EkuGuAE=#4A@XC|j@a)Q}iyQ>0$9%L#%ZPXx}( z1ptcrF3f)$J@lip%Hd8>5ZuL2_kjz>fcUNr>wLIN*{T|4(-+jz!~EU)^Wj0jf>`}# z;QY@}kYLb9>w^~ifqc7r^#bonuG=8xS6~>)$PIerld20!B+O3yUL?X~>a#1@rWxoD zONMr{fKFetMr={`gR!EqX~U0=4~o@jDzxFM z3$mI0Gcng(;5}Dg~T}C%(eau?W>z`g?7s!fVd4i@E zi2*@}5wrWOFX%zF?wMD2K@&4Rf&9%E#U}jxO>}ipxAa9O;CIz{=nel*>m$8Yd)IT3 zUqZ6=lFJWp`H$?MqIzt_g&R0l?w=t?2G$;`AqJ*pyFQD|o_=+S$UvslEo>}Cm`6RD zQXQ+xqNEo(GRn!)vqm zs}lDd-IHal>liyrkKtHj240s4;_~OO_J}#IH)kV2F;b|gbIcTjlz0k}116y@YZVl9 z2v4#QlC?t!QUdSeq@~R_{&+sfZ~EbCrMnyLGW0~KW$_%2SfVR3r>)r2Pns!PFgh4P z&U0b+@1And5161oxBMp{ib<|!6S@dsB~@YF*engVvm1N}6R54tsq>@tUE4jCP~(?g zhd3pm$oGuqw|^R#XmT^^twYI-z9M}mHAN;ZL(pMkeAVOX@%}I6!0OHw5N88a{ur~# zpdRB9hM6**j4`-*TdT;Z%3ITe0IT^T@8RorjY0Fs2Bn!*eOP)scb2zgkY4C%#^i0cw z&%R*+%iPTz7}(;wu7RN;81S~fi-G9qR;2Z6J^U^}{?t3mz`a!lf_T<veXGwkFcL@;(BKRotsc}TljJT!4a2-%{s>qXWpX%~sv-!51b zr6-fO*4OVed&N~{8}IL{_0%M5^xvqm|CSeoBl`!I?=?R9tJv}Q@QJSDx}9s_0mGR8 zCPi9NQHsbAW^X#<7JQ25gZuFo)#;!1_cW>k-j=zHB}7Dfl}~U~Z+Rw)35$qSBmOLU zf>|FJ1jI1$*#-?Q-s^=x5nL{JVKb` z04&poaP)%`y2kx*Vkm`W-gbqYOS2z`MvvR4JidNjauf|_#Mlw9MZYSMwh!F0ervXC zU}m}D=j2bOciJ00Oq}33NOt$96ftP0d|aPO;q%`89(hO%LTvZMyLOuH=yMRqvZuC? zTJH{8&(Ei*zdNvhTm0qQf#QY2#;J6?eVVaw;&|N|I?8vvJ#pWwn)hwvWtFu5WRjx? zRZjVPJ9dq3Sr**=)Y(_v;8i|29hsr+$5rQ_BDVcGh`<3{NgU`>G{Qj?91{fN9`=Z_ zpAZoi)}R}nWjH|6Du%TTa1ed>VF(D?c|#cSecmHOY&&Iz1D6tH^U9~dP#kKb6^Xo4 z-$xGZ8ebgez~ZM1#I`xNDL?Sj$93{qV_ulu=wD~9G})VL_i%b2Fj(7^vO6WDk$&fZ zlxMa=lvp(DdweKD)aRk()vQ__;xEn{+*nW!bzCpcggJO0?A@Uae)-fMG$M5f*oW2j z=a~TwnFd2U8Hy|saX=DCSzjPsv+hL)U+#4?%`k|$jA2b=>)B2yBL?`xtK_EUd%45v zkAYE73&dSh#IvWRWDW+mobOA1w2(-ZEAF&wyyD^DDx=42;H+ztRpHdo&m6MfqcRc~}e- z0+AVv+@;wWx|dO3Jcqmnwvy}e=IJ}7?$8+GCB5zhTYN+$B_(~n6y)mq5*)e_PVIfe zpV!WADjB^`DJ&eaS3F$%<xL0mW~$)OAo9W)8i-<6ct%UvX}mCTEN7~S zCn(GVWx4J^Z+tKh4k{6kD^7`M+?!flHVEEe$J2ZaY z*%|d}lH7lafr%lW(@!eAm4Mh3+L}GwOnzrwWRwi*bJ7s`ZNFL(wPRzM-)}iqBA!>m z(fAGy=Ye4|gKT&D{2$}$szziL%MK_+JRgNBKW=Zg;-7pEy72(6 z{`he0%;2QA_xhyYjHm)jU&^4cJ;dht96fh#f+Jpvd)b5bCY_YL6^i#lM8;CVy5WP)SDr1C0uZA8!NVS*TL-k z$TS1&ZlNF{Gol*_kg@81Efz=!5S1!Yxc&7*X8iqzdLaK+x4-0shJfZG zVfWCzHoHpryi@-J%ePX242Jt)rDqByM*`9b46rT!^z#BK-dln^{g6ljbHO4XG%$C+e*WcgILpFoCiUama zo0iJWT{D6N`r_(_!U7ya?Ohp?QWV8foh1{$KpNYPc|{7KCperPr<1vCIh>bbOWQe; zKHVP9XNJmJB??6A{x#`ZyU|x_H_UGP=*RohiMay8tdh%O14yRix`fj&81;u|Q)*wM z?&%xXn1V?Rgn5R*ug^schY)M?O5hWKfeBi!Zf>sz9f>tNN@8Q}0~}sor=JZfq`@%> z+L^b!;5c z?8=vL=7mCOFwhQiPtRap=$I~$>MBOaJ^hO`m{kUIBCk!nnBg&>{aw#B23k1f7r+7u z#K5W|E}v#ufyzgNS7uK>Nprg9Ac>HTJapGWD2?6gSEGYl*nkT?zZlr`~N} za_fsm$NWdwaQZI?g}X`a|IR9gh8p9Zy!FJ4Q8xF z%+D=}N$+okijyN_H@Y%hjRaX&DNSg4ThS;Z4OP&v9{KK9##^JBc(j=1y>107GkxPS zKbzf#s_e-nv2DIzOr7GTYp<@>);h_^1a5;Qv~3C8#=hg>TTlhIq7d{cRH@ES1vNXv zAUreSkY7ddvK=KeDAYk z>xW+$G{L7emgllO?b?EXsn* zXaJ3vt;E}(48DVYQ0mi!U zs`q@*A@?v|>7pzK#)Y@P0MRHP!RI+DN|JA^F2y!oYSF=JqGuHn5SicuZ>nY#OiYEL zAJjBxr;s$v3q|@vFLpVrS+U(o$1i%}`nu@shW*=QW$8wN4D_Egze3mK;UNb~T!9T? zQDK~*9yAvzhf9-@k?P)<|1~{*6-+(>y?;CMXHL2YW)?XKEE$G(<@*tH7f(Q(uGU0kW4(u(^&VIg^W#1e9&6{_U8Tmw86*Prf<^*qpK+Ku#3<$eUq8nC20JiGR5UgpVE?M(ct|o zy`cf`=1T+1sFU(NUMvhdaZa8*%0-I?q#LXLD^uNRKF;zd%uClQ78FwIeRwe3*V3oS z@oAfK%%q+XF=LD=*xV)Co2yC)P-X`)6f51%VdI^K%C3UIxvz>Em7}$aOs1iS3h{KI zefU`)=RidOUN8Gr@T-LnQTnVv>)FmMnh%V@JmED+d0>8Nq92?Gz@WFcBi^W}&v^ee z*E>F|UJla9y3Y~51%{xtE_dhK$hgJL)$*r3vj)*w6i0u!JmDPFohMwTqj&y1(Rajl z+_FtJkYzAE&Ar4oDeU;`-8k~&(SqZ@)|xNP!A1NL5ITX?B|FJ$`?=B4y+KmqtJ&3D zOa{kNUUCc=8}NXL-gf>&RIT5Nmv&VQn4;G4pq>Cr9$vx1;v-Ceb*tK#_x(noQLjC( zv&JXu)!=So0!-wOL`fWS>t^_`bZAGw0#@JCD$=rmed~U2(tqwe&A_2mxsq88P|KUN zRB_s_N`T4(0so19ueQS55IAzabpNi)=lIYCaqP9gswLB`Gg)x%+sp&;Y>Fjn?sFwBqq?Y`|8PYU5DQh= zCTljpa3|@h7^v&H&KkjWfyO{pDp_lNZwKMfRuvm9{Jok!Ym%M8>K_dBP6I4Z)TX?$ z&b$n!G)W1UA4gw1SHO8z33 zbnCX|Sggt?>+9#=@_VoJBCNM3Phw*ueAzH4Xablk6J~bjd$oH#KaTE3pL8e5jwmfp z1kytmJ-n7)oksEInTBRiO3m*4eO?-eOx=yfq;1|<-7aDRKafa#PeuAUg)jLxl}NbY z-c1vGHHgAP##Z^@atS^FJyqX;&V2RTF|78<^>Ha6z?0+8o&t-zyzktMxa{9=xiGZN zM!WE$Z~!a?hGXo+=C=yFsf{$x^97r$6#yh}yx7Gsvxl{kk%54t>s?@^4Q8A+X_=_b z+vqYea4`~5YLgA~LrtLRJY}GpAm1)KHlsO~Kn5G}dN7wR@x6OSvnuQ_VI>PcZOH?G z@bMb1$!ae`g@y)mi)}K^;?z=6k=VH$aAG=*KRq84;PPRe_%W!;ew$b0Pkr)Ev9A}4 zNBxXbu`h!YakZghJ7`fr9`rG`}^)Q$w}ct`t+fsUKpj z+>+ZStF=g2)&)k-<|Y$9mV}`jOeQ-eN-cA~ci;teO$)Gy8Y-{XF=Kbn9Gc$j2rWMc z`_Q0&N}~O?OXCYJ#zBN9KENwQV&*wh7KJ^beY)@q>!==@O?On(`aR?77QzJ2}L|1Do%o`#*$=u2qJV!a~>+j@52-nF6Az`6o&#qyG-B*S5}R zf>WY^Q{t8jnp`*&R7{8icp%$=G9~+>mqU%&C#z1(xJx(7^@JQ7V6^kHjkY5K&^MrN zVV%MGgg=Gkq~p`v-N8vy&!3;2+3*o*th$001qY$^@+Gr{yTLScZQ}jc09wkN=rokY z^s39vRmY+*ZR&S!Re@79_-_&lA#Y3xCrXv+hrH)ohlLbZ8V{d1>99V&V`TTX_8PK; zg{%ZHpsY6z#F{&;h$b>ckm`UwoMMm#cMXk2xVsvlKW_myv=H_t5 z<>Gdj2ITh3*Id99;g(aZu5O6Y)?TF$SSCO4x8D|we*_#qb8)y(Ykmgyr-0*7@?fGp z(a|ql8{K>+#9?*706iOKV}za^lC^}(YoRO7H)T{u*b#@j9TTp@Ft?2^&gY5ji(L<rT7f+n{fpuUVMSR0WMVN=hk-K>&$* z+eaRto9Ay-wGfJZ_Y{<}rL~HbnP#2f@_n>k_yyO(i&XA04Sbd-n~t~gCga(G7+1w$ zHGP`JNQ2e$a5ewbK?Ls`r^e!&O4DwG)lvijrP9!bvJ0F1L@40cvU_!KIoktA5FfCI z3pE7uwcqZTrSGso&o2^*mQD-p^LBa2Xz^qfkpwW7QP)bX_Yb7QUzo3%vVcQ4DJFo0nh3k0-4m6NX=f;vPDDuuh3cu;{HRKAl65^_QSE zLYD!u&o4E@M%NKY9wX5^KBj^&ZEZ^;)bC^!r8o^-h5#3Gj{3K9@PxC=vt-`lw=#d) zO$1qOvRl?>syav;)8u!2r$I0Dt?rd?fTC4)BJpjqrYlp{j{vO0Mhlvq9EcDq`dr0z zxvBXyV?Ha;x0*OMZsCz6{ZZEq=7vStB)Qefg5M^W8<^$5t1`VjTCjdOYT1jR5m4a~ zEJ-Vqsf^C78WH1DKMr}UT})`VzD`g@vu)fjvN`_K7`tglWKU4sN|%Cmt#EkpBH?h z=dyLejB1uz-WI31h37O-Ed$Vo@n8B@O|Z85VKP?H+0@qh>=hV_ZC4^q2W&$+UIl^S z(Q^2uUdgz(1Cy_)sSkiMtb&t-ChSOz+~xYc zFlZ$D;Tf=e=JZDkz9~(cWWvuq8D$JtE{0=DGES^~cx@sD8%n%jgy~Z$Y06z4wz0AX zUV39A61krj>izw?Aw6$M`MKfcsHt^t2a)*rLI0PM-|>rNN_y||kStRwz9=I@0fQo3 z7)!@boj}T%oE(aU;g~v|zd{*k=e%%{HT7i|ih67>sh@Q}y_t^ZOxcL$(UR_|U2b|v z>+YO0`~z+!@*kLv1ZJ0378L3UfSw^s(5VO)Vgi;uU|`u`0vFI_S>a3H@J0P5F1-tb z=t`@Xq;$AE5Vr_eo}R$O!a^HRX}A7149z|VN{4+Ic4eJi(b#iz2lSUzU_}l zuM(TY4d?i%IEI`K#pc{_U_XN~-QZEBbM2$) z_z2G+<{$X>&0$$$NygxkV0f`FNE@TiMl}8!kR9&UP^JrB5XN)%D@`g~&5uJ$4H~w> z+j*s6m3YoE-Q#8@U;tSwnE6H@F*$xjQK>?~dPhk=o*Z4PGp8|C*eqB~-Kq{;9;OMb zXY-K<0lFA&yeqI#v#Brwu=y}rqRrC;T3cqx&GY@Cn`F z0td#qxw(-KyG&-QC@QMso>Iq4@Sw{R>W29i@3N7sePTM#AyO9LEe#Z?o;)5+@`hk#)>w?sGSe;aWEL z0z$3aMVZhNqz!0g#Yo19WUW&m;#(16=Cb|<=t3YG_skb}5;|w@mG}ZrUQcdC2|b%j zJEn?m{@Ecw_aZ9at|~L4(ek;Kb&JyNWUa?}{ebDaHoJtH>v_Jp1M$oufmY{@QO&;?WR5xU;zS8=l4Q| z{+mQwA^=F*VXX`+?5Yk~s@=xMa)lP&KRQ7$Y|Zks-O)nLro*Su54W==s*C4ohd#q% zbZrwffq~>_HQiQ_d?MxSfcE8W6wTd)bRak1@Ciy2^^&b1&2Cq+ZTpXFyz>Wo7eO3p zb@B3*bC)=BeQP!`aCtu(3pF$X8RU|U-}DSxwkzebCHE{;kfMPKEhGJU(QfC3n)Ti- zE@QQ|!gJEXwSIF&H8trTKlq~icTmvSuK+Eve;{kc%Mlf3^Crs0>T1v@;}|Rkt}Dpe zsiLllZfw4P^yhnO$;aNiAZlJ!!WO0t%o*At z5a`e8W1yu0mk>}@{4peWIg~AG!ui9N{MB)X8Qg6crl3qc%y``#ptuu-`TVKis3@Q(g6X5cI5T}LHo4h1IxJ^FRL_fZ+(2xOM3Xj61!?x5=Q)7 zH@=V?WZih}2x-zR^_e+b99@d9C6<|FIU$3r0FZ~Cc=0qo@H&RO^NQDNW;^2cv0(i- zAnrm7?^9)scu-6_>q`~Ea_!UG*wx*Sm%iht_>y>hm9$R}sGfqEI8y1S@{fLxCxJd> zw`#odXMe={2PqdWZ$^%n_yDZXJse<$#0zG%fi?Q*X2ng3}0X{pZ${xC>YLku_gv4GV^Ap|8GOmJ%#q$Y51aLsMl8$lZD8BQ}*l%J`l%t z`eQmA6-N;svnWX)QIIHMGvB9SKCE`yVKVt+99jS1*5=M|wT<5^(C_SF@pzcypMHu) zEiO9fGEZ#Dls-wca2|^rsC7^6y*YyxUzcL=P!?`i{qYX^4L8Tov4^-*h`+nOP3BTwY*t zMI6b3c=O<@& zL;Y9r(svk{g)kO8@;LX^4Jh&zPHagrT#(OeIkYbRgEjUP=|oBi8&qlG;NjwK$GE`E~8HUnnEBve?&#|=?ziNl;UwIZ_Jg?%i#qpk^^&pC`D z>#;tWq)AlW(4*Qh)hxXYtu^u>e=B)pC9R6Uw|p9#M|zT_7kS}oDSJ5aKgf&&)o6D( zpA*WWBnK}PR8G~o|KrKJ>E|M$^QnOaEGm#X6fMvN)orqUs!MMw@;AQAc zrH}hZBwE)p(CJi@uP~{#woLxg>!mfST*5{ecyImX%SQ*e&nV$J3f?KD1>An9 z7By*{Ib30)Y)h0E<9_E#xHYX1@>^c$4(R#5ZZQ z9Ywp)26^3}o*%fETt`dX0Y{Rc)t}y93S%A^6`A=c{YQk9_lL=WxFqJN?NMP2;wC+T zqPR7aOpg*@U>TfnMaoy^k(4^kJ6I-3-XU0IpBbK-avk9Vn1lluD;Ao+vb;^J$NIeH5pK&WSh*~Z`P z>|cr1r*KKS5JXnIaIw}!nJ^dWiwUiTM$P76I%Q(|#?Qcl#Wy4lC0m7x>T2%sMVC0l$x7A?N$^C~rqmEim^CkG}xQmi5pe zi4bf3<@C^!UURW;xFNWtVtSJI=;?+4-qGlrV6u2I!KwGOR_}QXto@GKlVedzJ@ z-p-Xg7bmGjkj5+)nLaiVC|cs{JRK~*Vp&j*X8}S7F-OB^^>C76>)76H zTyk|k3)~_pVZGbkw>7jgddY0;NPrpL3>O1Mnb@iu__s-x7yVx4S>KvWJ$h@$I;vsX zSwfsE2o%lu34Tbi6zW2I7kVlu#6t2>b#`8#tn21w7)eTM*$E$_H*bLtGTj~`d2sx z#9~LfFB%c#leNakv8r73M*jPjgmX^ha%Ff8m6Dg;5>ufaE|u)F;PNj&p(fXB+X_IX z1(ts<$B=$8vj^AV_xH}yO#uHLoJ#qzr=NJ$n;d!_kY_qP{}Of^(|Wqum6mQi&omo$ zl+=tNNQP_|`xZMtKeL4XeoH(kvQe6JA}A4tlMLxLoJ<^d_oUvLPz?Xyts3Q@8E6Gp zy!bhhpWR*ufsle_4;hsx@-A@^<4{$RANs-SA1s+qrvf1W;ptkJKGEU3kCb26-{3D7q3lQ)0pw3n|M<=N@i$X{3mmI=YVJxN$fBTCU*^7OE zTyEmriD7zV$|p#)3a`fUrm^#FK{VEeZ)7MLu1*bb+E+()Od zSn9j@6)=K|O+5h%(8LWF;uicTfDNj^{7LMbq1ct0p$#ywPV4&abX5?U>k}>IP-0)Z z8FvN@HPu6($`O_`H8FA8E_1@5Tx7f%3{youX*<(vo3S$Y=GlK?)vCx8?ohAzz|G*gN z)4NRue(O%Y!_6#I63-n`07MW4J}^f!WK&bKbZa`JT^VEGCciONS8xbO6=;DoaUZsXBs+VVaz9 z5PW2JLiw%d>0D<|RBd5-KU*Oh0!gGdVz;%U1217?0VH^qQ^~Ly@^eezW8;}QH7Cr=`AxY4e$v-U{3YkI=1#0 zFc2nn5pvuU%m?E}eCpu7iZ?20FC!x8iwPN!7j@<@<~`oBiI{%AE1RsPX+Zh=w?V^8 zL>R_Pnr>gcqJ9?g)2-ruTF=jZv%~XIDm1_m1?|-sEpTT}Fe3lGn-{6UI9=m?LlUTn z0AZ)0WnHn6Ts;BlJ9p~J#saOBHi2>a^s-p8maA()VFX}zaZbi+U*Z|?sHdM&jfKGq z;6u&q#-6WlsF=Bax22F_bLV)`p#59_fSNN|IaVFB?%=Pxs3?dJLa9XzwFoXH+pFMW zKL`tcp@-!O8o#zOA`7b8zVe3j5}m?WywHP;h^vi67q&Aefs;ffMKC`#%+o+~x!s06 zMwOqz-M91PZ6I~PGXulcN?JGA%=VJL9H#+!dayP1_v})o@^&-lKYwsW7IrAQJ4|}W zG|tb@4?P=1<)(n-G6Hg|*W+LWRO$5C+NLkYJv=!UNMVGG7vU77^2SiP@$J^2@ zwM%arwa`W`1qVvG&Q&n;%w@2ri^rzc>DbuV(kCtY zm6v=~-t+Ni29gG6ZC*y2uz}fX5SAP(KJ~LX{%bhMElx(w>3Ym}jSTc@DTsT;yLjkR zbsy3au-L@#EaS>oL*vf!MxWNCTGp?xyzF(T;+}N2$N~8z%aPSui+U(0B~!4K5%B1>~Z21e72M6PQbwl!{y)`e1V~#uXJd_-fA7>u-u` zTB>MBd9UZeAdFb!zY_r1$k^Bz%;_4&aoubX>S>_rJ?SUFVzYF0%035%Szzkr*crh1 zn2yGV)@Ox%768=C?>3_nCD<-m zst!Zz156m7oUHQmmI^JGPoM_(SX4W_<$fhfa8n zSgYqbcf~*ppv1tq)6Z z+V@CbtEznJT$}044y?P|-tE}0Tqw8+Qz)+~c#`!w;Wbx+S+%!?l6zIa83LA(M%>F9#O0jQqhh5!oTQeC};US-;7er54RM zR5Mk2xIMZQmIq>@?YE1H!$3V<8E4^P2wmlj+ z{2F;22|Kvs)Zkg?kLK>*34w>ugwFJI{N&@*BV0UfnWw6#7!)Sh4oc|y`eF>w`XCCE zw!#&qGUp)!X399o&l}{KPPBfwmf62(D9EbToAt%CsH~G)iWmS9$FRmQ9m%Km=XLLp zI&&6@knWj+2;PwWf$# zWTp)+X=|o>nxHyK;`>-onb+WB5Y@C&(PyDSgx%ObZnYBvk5 zfcyY;x1~@U01^X72WN@MoSnMN0Zu*zry0;78S+oimAdTL%ilR`18TAOiE_u>;*J3& zVo_s5k|Bbu5fT~1#>SJNK)Dh>+4C=0n;QnWiH2);* z`B`ukV;}H<-L!k{*Kd4{rm93<=guPliINWqi*>7r1T&+?#!xKCSO0`FM4H`8{_o!2 z#o)TT;7hGX_Q~tu`WHeC86nx1s7DFl9`Y|#Kt&2rHcEYJ2+OG>cMO~X&C!>Df;`v@P6az&u5EVr+Q49=h#l%8vMKMuq#qKw@Vi$IIw_;-P zd#=~#JDxv(*Nn4|*;#H5-nD!7oY!gL(YRg&g*SAsf z;qHsO{5|}V-qDY)u5c`p7nNnVBvhRN&j^=a~UoM`Z5T`hzHmt%E&&iwcrVH{O9CKMdf{$O9&*Fx+aLbDFGd!}g`~g>Tk$>PAS2-DF^bIIXnKOBR{zVPTf)Nf%jT(P%;27>L!oG>wC(fxNRSKHoo6aUX0%k zlvm@QL**@abg;Y^Pa7>C!wbjB7jU-;@=fd>DnG`}r^@eehnezs+#_7JP0nZ3JUI=1 zzCg~3Pb`-6;?hxaaqO~6u7EeJmR<3oXt@EdyGd@2zigG;;kLWvZg|`txgVasPackU z9gxT4!$;)l`0R0cKK^`CUXGKTlQ-c1{^wnW4;wyX_^RRihF==~Wcat?lqvrGu8fAA zaMhb?Pa)jN`hX;*aqs(bRXq2hTn8_=J~&BZyz80lgD=09JK+cKULJ&lzRIKV zDC>ikOvYZnpkIfTf0aRKYg ziWJ9AQ*yoX42QPRcH#Y2JxRc>P!-EZvF&t(% z+;F7fwT8E0#}8`5emv->d;*V6lrQ4BHhk%k+t?w6{1m%bCkx~~u3#@G;FcNWWU2WM zwN4^PIy@<>oE^{0A?L>_tdk2;5}(N{SHevT$hC00B61_#tAyMVS1u)Yz(1{%5z+$} zs2~r(cdE!E@kJiw{9%Q;5*hy4LOEOc*_^?=9cnJ zoY_}?jB~Y@-{Po_@;AKRUru6Ad%DYM@ZFwrR$Q;IoEP^Fl8a-fL2?B=W|-`X*9OZC z@b=Mib9~!6nIeAp=>$0dHwu#n;tNydQMlqPITY8lPPoWy91tNd#se0~tMQ^G@)o={ zN{+!XtL0eyXsvu6f7&45zy~+UkMP-T@*7-fxBL~i|4+8zqA}1qp(Ckr_(9nLyC0Qv z<83G8V))i6xg36ePIkfR<79W7^NQRIPrM=f;^wzxf4uLW+y_5-AP>VIp2*{H;tP2i zF7jHAz%$>=QMiG1Qc0o>?=*bS@M*(W4c|BX((ot4zYV8M`|tN=!Y6;K4Nlnek6Z{R zOO#9F+tx`gsfM50$@Orm2dF3g1dI5PZ z{#-;}iiZ}L*W)qH@^!|TaE@GEyY z8T}2>jpTH=i>K^}?|R7vaNSmNDcr8*T!)Nkc{O*3p=tG-^m~! z!^tws7jU0!@=ZL%Nq&r%=91sy&H3eTI8Q-2Nk%@Ci^}$RVKF%i&RSZ|gT2ej#qkX5 z!jY86pQ^|;aO)a!eLSY7?1iV+k^QV=>d8HD&W7?Je7lJ}8aHYtPs8n6%MrM!uN;NT zw3j#F)*a=YI727-Abw@wkWl#As{?JFhi#u8uujDz-Gf4i3PY;!U;q}3C%1nIs zjg~Xw<74EUxX1*#F#a@AE`z&Gm8;>vnX)^sIY(}We@4iD*kh3#fQv=SLHL<WZS3?y_B7nia5uyK3=cOv z-tct8^9?UIyut7;yvXW2AcyejukvYJ?5BJMfB7Zf!wEKAG?N#2X)-w;7qB`T$S=$G zativ_8>N*q;B{6f1j&InWRVNvE7@dce9h{dAXV_6Tykw(A+PL-8(N(fq&0q2RPKyl zl#~PUj56|IoVmO_2A}z#!wiRG_Zm7T5_`JIYw zd<)-dAwR)ITFdXOV|?ZBIBf^nHVfw-9pyB*N>@26_UtC-#htCr6;d4g_mwN+t^?$n zc$(GeLOk${VX`;g9W47{hcR*h&N^NW!mbnLV0X0LNY?OQ!Pg*5k$KFS0+Cv{VKTWP?w>+#fiI?(+v5@G55tWG=f26wF? zf5m}rvJLkG!>!Idk{U0nFFW9)9&&Dc#_HrFMe$`Xxg7rKExX{Ptz~yy!dGsFXSA1n z@xsosKknu)_rZO-%R_N|PdNnt>?2Rb$p^^ua4D-3ku1ZNhRN%3`(Sw|j&taJK&eQAuf|m`$XoEUOL7dZe_f8nnQzMH@!-4i4IFu2euP&(mfzqMFXV67`IVd` z2j6Q}Co8eXPvhk*c&FMq*OYznY@_M|Zi@XEx36Kxq2R-DIcv5fq5)QCB zyvZHhbD;bTXB;Yj#8s`1aPre|@|^$nr^m5Y2RU)Xy+Y*zxX~236mC32u7U^6l56AP zb7fCFa)I0mCs{0a#J0=ip18Qx(M|^9Qmf_BxXgNaGHz{kz>_(+;}&@dKDt9*gXis* zx8lgX@?Ly=zkCdzKP<=L%g5xK_~!}vFev6Bpm%riCm*gb5=%c(Q+vAuUau)1= zN6w31SRMbQIDYp?u7Km8$*y?tOSu8g`&Mp_SH73q;kzH@Zg}%IxgWlsAP>hOzvc1x z-v2z^@O;C|4R0{K%kUw?XAEC8eBba(!=G^bRCLml-`0KyIVEFc{?D0kiyYdY6Bo`a z7sgHU%VqJV!g6(dt*BfNk0>cO#SNV0HaK~CxhwusQ4Yef)#Z_RW(|2VZdhBMgYD|e zOYl?=d5z(%c#fC$@5Ot)E6`^yP=I!em+m0fu}E&7vlHU%^$K7XN!_I;T)^vJ-GH7`3Pc z-;~?nRCnbrIL$-3H=g-e9)b%zlgHu?FXbt?^ILf?4vd$V;*XxyAHZ9F==hVk z+aLLo;X8((8UA4Shv8)T{yk25!;Xdv7%qipWszIrypD1Q z+`vihfg^Iu1MrZ1@<=?gkUR;GEhf*xAB)S2uzeYM6%H;dZ^l)un|S0u{Gh6Q6x+GT z=L}!RWov8yLtMSS{2JG^Zu*fgIH0kdh|_w>sq%9!=q+c))qLb!_d55paX$>VS*>t-XFhA)niBXF5<@^W0( zx(P`(;GL7@UD#o|dGSz5XT-&7cglHGB-;a?<__cy%uMCSH|KevH=^lHcNiMdWYzN(nhhAtt98goxJ5> z+|@^(fM2$eXW*OdMw7!_IHr6v`{Uw&+aaPvrc4L-6|-inK?lK0}KYvf~ilQr;! zT)-_h%Qx|et@2~b)_@f97TfHRzhT>ba+2b_P7ccUxa1Kz3wAy(=fSN`%EfS-vvPUd zE>5n2i(ZoJmx!zrvmF=QI{e=A4e-XG;C zJl7g5L!$ALZ}KjDEI~em&s&3N$Z1^8mO&!q3ieGV-@~2l6ED)KFy;37Z4`D)7V@VVOZcU-2vY+I7=Fb_EmPS#k? zibJizM8>d+!r!2)7?`3jETy2Hygx%K2g>e07xis#(QLc)IZk6lcW!7LT(ipGXE&E{m zeR3yU{(#&IKRhfC!e5Taqj9E_@?<>ptUL!dx*#vX-!92(aPU=m8yW~U*#;=#~Kty^5Fe{_ci=O9QI}Mlb;K?K8XL#lq`2*e)BLBcgC(6mn@c9-d zr^5@T%GvSnnR0$y$QsZ`O5(VAawYs=kz5P=N6HOx;BvVI4qqvEz)RQ4J@DEM@&FvS zNgj!BZj&eB8oT9LIMsjhBHVkwyb8}fC~wAfkIMhylgH$v_|hr)9KLx@zK)Z`$q%vp z75Oy|vIZNHFL=Q%IT6>rC#NdQ-}pezj0ZoFbKxJ)2ZoTA*n<1-k}VYr}SXTwzu*D>7Ku#e$R zIH0`R)(g+5C=bH-s>oyTj~a3q&Rg zh)?*)w{e^`IFvlacRI-LamUVb0#4sePFkLR&Yp5wyfjeGhCTbq`S8I0atVBAuv`%* z`#Z>#J~^Czr1pE@17l=wT-zFaO8oHJNpb*gHAN1>qpU%xBp8>NB~QTi;qnZeb-ug+ z=UyzY!0wUqCj8YJ#7cHs$E=hONM z4!4zW;U(6fUGfwkvy z%dhe7n(`OCua2CEYq`s*DlzuJL(YubG?8=TvCZV7czO%D9CmLhyWsA=vO8|zCpW`B z)*xu&i#Pbo{&;GD+y_^;21k>j*uAeDf=>s@)9_Vm&@_p_ZHCHGI67F4#_7k%JF)9H z`53lrvzT<#G-@dZki%cgjB4=Rdg<_TMk}!cz~*gRsj{c{I*>T%L>zpO)v~ z^5^A9+%`^Li+fy=x8YgWUf;1Tn|UrlAGdG_2f2qpoiQAFK#6F#wnV~ zL$Gsmc`UBcN}h^6edT$0U^{sk4(TYb$Ll-GJMf-v@&SCJr+gAO>MdWwzCrRG95O(D zhUW~CKj3A-@(+A+q@1i8@8_{{I{a&#oE>)ymGk4Esd6d2V7goxubeHr;eO$ABYbtf z+!8-pEO)@&mdZV><5$Q7aGo{tNL+uNJPCVklxN|qo8?6~Y=^uGZ`&nr#s^~L|L~au zaxDIINIs9-9+Pk2A}8cWc;*@T4UW7Zf5pcy$~M)xUbrf!#*x=$2W)po&W#-&$VIWs zBe|Sm7yRd?_PgVIZ{%k9%?H^RJA9J;alUVI9~}2X9*SH1mP2sIB$@ucwx{CIr1Cuc z-kM-RqVO_%c|AUvR^EZHSraeF0sJSkd=hubE?>gEtqB?A4xXD^euh8hmp|Y^h2$SN zu&A8O<)70T&Tcrr;gW_c8Lnlxq2U&WI~eX^cmRG=UhNra?XM|M!f|!vS$J_hc@bXW zA+N$kJmt-}j5WE0#Na#LaxCuHNq!w&g5w%;Rv#4}>#pE%-xoZOYM#fRkdxX>{<2fln#E{J{3$j-Ra1-S|iye!wo zAFj%tcF~zsJYnqABECc!Qn%1h-8izr**_$=~tYOtNiFt8YzCg9|vy zS#jxHa$f9{M=p-L7LY68EJb8jyr7ue05`NI9+Bp_cp14Ju3AA3z;CPxNhHW{u;B@Y zXBb{!c!lAOhIbo2Z1{}fYdElu+VB8}*OOo21P}Q$&Sy=KB7bn1X0lx^-kvSwOt@<+ zIVbMxD;L2x+RJ6}%8qh%Y~NL`hsy`ZO|e@qxeadCSMGwZ1j)Veqe1deylIFWg7*c> zQ*q%j@;uxmL|%sdCd%va!%%rAo;y`Oh=0$NPvJsyUDK%jdE8 zYxxH5^j?01Cx4XR;CWxt# zOe4GCme!;<;*LjVlAGa|S!G|G(NXrtd2-2p@b!H1P@Gsm9*5Hvm8aoK#pMWG*P1*> zqVUFYax@-RLEecUR*?_l1y$wKhOZdDXZVHTc*DO8r>OJqF*6v>VYrat(uS)Vu7e%x zscnt1TYcFFdp43g;a^SUUigleJP3!ilt<%jKJsLoy`4M<7w9N2!HukmgJcc%=_YT* zqr1y{@f~YIAvuQY1j!e0uL1H+JY!?QvMY94AUD8u7RlbY*;3gLw_hO#;EAi`AUu1W9E>A3$`f$@ zE%FTPyhC1qTkVop;Lb7fM(Y@BLL}LZ=N^&|5It;xN-?OsXP6#&T?8DU0%+HovaC?Bp)taNiKmm zRF^B_%(dj2_-Gy31HY~(d*fQx1XJQ?IKXg_;b6lP4bL>Z(C|vbn+)$Ue8lise5i%m za}B>}B|pFszVa*VWKDi0pYh3#@*iBft87=F*Ht$;6Yktg&WXc%%SCWCYqBgUgO?AI ztKri_%$K$KvzTpP%G+_#~d4+re`>vHQ;*j<7Z5(Dz-X%|Q_%``H-nTG1CZa(3L~sGJ|qIwqIIi%-dwaO@em7QS#nZiuT~kz3%7*W?bk&n>wJo_9wc zfEzrJN8+tdWrw%I9&cHTjs_ zz%!F%{p&}#RSNkHK4&L?!xhrXNj$h-%P8C9o|)w=cxW~`5B}vS7sGbeBxX_`JLZ>N zv0Fj8KK8aIHxn-$TwHF8r#Q=9aZPK|GwF+uR*;9`%T?rY*r&QY9jC1+&&R{-$jkBa zdh!Om%|qUWZ#9w+;nz*&)40Ahk(yjJeBba(!=DWQHk`8IzsJdF*vW8V!(|Lt!zbFR z4Rx*k0df=Es+ZgvkLoRV#!rIeK%8cvJOn#glf20oTx^6KhQExI!?B+=`I|&q$BdWP z;@P3{HvHY16i)Wx*y-|dd}+2Ehku02x3Jv;`3VkMBEQ2mmdfAp$`!J0BkudGlGEZ_ z>*Q?s#YQ%%2#pWxAJ{l z;iLQt+kBEg<740CKlp8eZ0E_f(r-BvZk{CD-^b61%UP4=Nnu>uPA-GJ(#X~EFl#bB zsfQnClAGdGS>!g@(NXS#3+Ix1<0g6JA$WHIc`UwPNS=!46qD!TWu@e$IIy(54wtMT zZ^tdH$@*kJ?o>@aVIA)(U&J-tXg=gQ@9V1(>~2U~>@NPV1dsqBTvuaMhfyVY`6oN>L}7w6n055vp0$m8+49r83h zXqOy;$Hd4{_~`*T8mB!h@5I@U$p>+*6Y?qC@Qi#J_dh4!#iK6D&$07W`6J$TUH*yp z-W;c`@#rNnV2^tU?iFD~`%8@5P0jURzSXqI~S54;|#^*cR0L+{2l)&E!#HZc`Prd!KEt6S#gzWa$a1=RW6Qu)sidV z0d-|p{LLy*K|FAhMzS|f-Bk9&<-FtoT&<-Xgy;Rw!GQ;gyCr8Qx>~h~cw_ zui>nn)P@H*zf~}Uyv8N_%b)R+!ZOOR*a>%Zj%xUG%j-?pv5{>kKxIHR4s8_!KGAI6dCcx(O(nT5j;Sg) z!LBZHYy7#E+!^PrBM0Kq_2t1h%qpNl#^7y@<>m#ql32o(VIA42t zA9n66AIGiy<%>AJn|#~wQ^W5KCm2rJ;@{7vHJr_GKEovqS2A47a6{a`zuMEn+HVzu zA?-f2YP{SZ7Y~(3;7wujM7(vnJQI(cDKEtL!sV4Xe1W_P@3V@^kUjXsQuzpe zA0?l~-&V=j@b7i<16*i>{0f({iqMeHxY7>!502R-+qL96!YWQfGT}G-D7V4AuF75T`|EOVoN!wng7e*z$KqmE@f$J)-*_s| z#qD0mOL2fz6o;(CGv3MD@t1gcKaTn;pTva{cZc!<0KFPbRt#w)_)!}!cp`3x>SOTLPi z&X(_Ef2-&bd5N#gmp|e8OXS~pRg|2vHRtmyn8rcayiIxlDG@Inoc+fVvDqgZf zu8SM*k(=P1`{dU6?g6S;9T$Jcevh1`8)RdBHOm%eUc!j!H<8+S@Fk2 zIWKm!b^81NUji3OAy>eS?POQnHjUf>ch4X<#}zWk?eLPUayOj9Di%fhVdq@(a9ll~ zJRYYkAWz4Ai^%hFL@{|eUR6rofVY>Gcj4RRuTGG+;d+zgeTI)4 zjx&7A@Ds!D41YIl+xFk%r!}0-a6UX}y3^mbmB3#X$Q5y}#d1v?x=i-K^H$0&aOc%> zdwkw1?nS!ev76-nIQdq21n#?2o`@rM%QNxHz4Ai5^`N{G-#jdD!q1M$dvH3dNEkVS zbDovY;`0~eYq+^pJd8ZR`>x5aap(>C3;t*o6(foG&jUGCJNl^}%b9Wc=W;IG_N80| z2fUTb;(;IK>Ui-dxgJjbU2cjmCdj_H+8@~;*SF32w+(%8-(>PoTsV~+f}7aOQ}Ir# zm>HRe4`-H_;g?zDX#B-d-hmH0$p>)pyz)t0si1rbw=XQ;!99x0&+x30@&|m;S^kOF zRgjbWah_ILPLJZ}F<}@;98`D)vT_w5N||ifoVFXUJKw?@T!_ZebOKBgG7tH(bMT zeZyXc+Zyg_xUb=1hQ}G6W;nud6uuIvwnba}*UP)`jScc4{Ctai8qeP$U%@$d%lB|` ztB4(Wft&A_<8g<>@-G~COitN>ey|gA2JCrO&VdJ>mkZ*1mtcL%zw2apxcM8r=7fyaiXc z$@TYl#bA$Qax89TC!fc+Qp-2+i*)iMoFSw92ItNqf5jKF%QhY9lW~$$<4$>G2Ru2S zoEy(8Bp1aiipk}0k&?0tzFt~($8F2W&2aZhvM@DxW?OV$Sa4)NfAUTQWw3jd8Wu4_a_@ux53}5Rmf54%E z@(-M*ubiwC=UM~gbok=`oE=9G)BgOp-AK749zR;HglCVFYvGs)azk7oOm2alt>T5G zJ#IBq?v6W!%L8z!dGbhn$|`V3CK;Y(c#+{%hBq6IF&u07yx|*$9~pjwJyxm>UvbcC z*`_o70PAIYyvi!LNV4FxTje}B$4kDKh3YgotZm+Rw@!?G8CbxdxHcb$;C z;v-h!M$#8gKPL~v%`eI0aEEL1G(72s9D(QDk)!b5d-4W+{E@s1UwS4V!mX?VkmNM( z^j5xtOTCxx;d!6r7x>jzIUb)*kbmJZf8-Qh`0TRD{r535;O)ue9C*K-ToAk2%g)yE z>E)_8dq%l7E}TX7#4{Y_R(Q9Q+z}tmBlon9$tMrQ-wMg2aI)fZC@xu2o{g)Pkr(6S z<>b}4cO`iX9#&0`!BH-9EKcPnpT}kE$TzTSefbggY$U(I0~^a<@mMd}#-D2(Z#gyI z^D>e%m#A&w31963I@+cg+OAf^w zV&vJlz* z_hg%HTvI%fQ{!|`We0rdg`69gd@C2l->pKYq#XADB)j0LUu1W@FhOpHlmC%@@x?^h zAKy!w=kMe6!JSjcLviNRatO|wPM(TaW{~IMUzz1)_>NUbm8{1zbI3dJ&)o6>Tp*u( z5|=3?U&5`6$aiq+67n+~Tt@zYSCo@~;?0%hYx56*2!mgwv{^BF|#KU~$fp|iDc@&=2Sq{bj`OCBM@$T|s z{H~|G8vp7eZ^5Yt$T7IwAUPJ-944Q~0aoEyasv+-EkDAy#>sE7?L_$-P8TL8>CSzw z>9RepGgHojn}*AI@Q`_OF?@faTprI|D%ZfBqU8F9y$rWC+|_Vj!@~@ZGd#_3gyAT| z(S~;#K8PP~P}@%7uAAk{c))h~F8;PteuJI%%HMGDgL0A{eD55U?eYF&au$5%l$-~D zIwKduHgR%!oaTyL16Q~vH^6SUua3mqNaRQ>K#dcjpQ}>a8r3Jj`NoH;_ofxV|c5td;#BV zC*Q=+I?9i6x-RltoFhQ~hKux)ll0CokSpL~qhwcH zDMa?bODD?Baj#Ih9nLjX?uLI)m;2$gbL8RJDMB8P>nxC`l>-|x+6*vW8F{Bfh&RvtTUk!#?hJLLMf(jM6hw~vwA z;=luPR~&vw?u!#+s^o|aPNz96drk1j>c1O$~*Cn+wwsidtW|< zXFilKV}~d5U2OMCevZq$kw4-^ALO4nAYM-1oA>xvIXxc#Lw3Y=zvTirdy;%MR!ZSo zN#)A8SxVUrC$pCu;n1{lOFTcL+!6P3kbB~*+2w)waZY&@w$CGnVn?eOHkpl|7L*rb zuVV6Q+^Lkj1y3$5$KZwK|aZMgZtN&zhYN+*`^PDi4A3Y zyr+qr1-p33d2l1E2sbH)v-!y7aY$R)70>P<*T*rPWG{TGtK1gP4UoIy#9ne=+_RrN z3|HzekHb-e*LL{8E7pEDTFVYr}SXTwzt*EZ~FxRv3KhI``4Yt@E<_{=tW6mGgx z4#kOki2zq}aFI4G~ii>;#OWDAZxCdc6Or{q{%>AZX%+s4T^anCFABkP!J@*BM5 zmi!e*-;-_nG0x$koEnEcl^yW5=W=e`#VVRkis7^Gh-^U+@zuU>x~5zZXRIST z)k5`~$~@$;tZj zoKBU~VVhZUc3gChoFA8skW1pZi{#39{}R~^ACHn7;dd+KmiXHmxdZ+aE%(47o8$pF zY@0k1Kl`628J=Z$k>OQ_Hyi%X@KM9(3|}|=$nYE7?SR_z6|akxZ3gh3KPjiiH%`l0 zu*(HGkKtmt=T+@5kArT?HSmJla(x_iU-rVM9?EU;#iw#tT#NTb@LztWBfA^olsqN*<_*xqIE_TT%Kga1E znCbz})X31S~#yN6dykV|94BuNMkHbxt$kXu7C^-U;T_H!| z+H2)#?72bSg|lyx58+YUajyL?vaEihI9w&q09EJ-Tb~aqqa2>;q z@xnc7n-9(rD|f=RkITKV$7y*G_C7C<#z!y6VYt*)IUG;BDKEu4Z_Dd&mIv~7JmI0d zABR4bPv9#rpNr!O$V=a6^(&Cay3jTFA+#;!* z54W}!#2_WGpS@fW7fUPG#G%$g8N>r`$t-*09ob|*yxUqpg9PCFx#a%1R(^Q|?p{!y zhXEHU`jEzm(8;3DqwD_pXn z{27;PBLBg@&E!-=d7rkBGvi6E3(g%R_r_zag+a&={CJo=7H zE`^WmkSpWUdt^5pw@+?_7ax#Y;v`4qjyNb*?qPU<;gNOQ_Hyi%X@KM9( z3}45&PN_W)ajDDlYr|g*CmK#Q{NM4J@y2`l*<85uYq&MI0aigztJ)G^k z+!W{eCAYy7YzqB-Ub^6owsLRmmr@>ri=~ps;@oNEDR^#1c^-CjkeA{E+2nQjnWMZN z*Uc^O$L{&%6Sz-7`4aA1RK9~Ftc7C8GrYiA{(!%flYih`73E~XjLoPjr^7F*$=Pw; znsNclb>vbwu%28QpYo91@W)1SBOKpUZizp6%N?*&E4e4m=_?P!b*%+z$S54uQ4Yn+ z{pH#CbT@f1KGRcPjnDRxx8TqHjNmhBs%($LXUbXdzS(jfoI64;hF{H>%j3pNzm9mO?W4mmAeZ!Ky>vf+&Rc_QqZnWIx=diX4DDyU0N}%vBD?vun!}aE!HR5}ARIHjo$K3!d@{?A=t}h}(F} zyKy@o`7j>eMm~c}_{mqXcL(`C-quBaiEnk4KUwY}|Hk)v%XXs~+uTpigi{WbbK-78 z<-)k!aJdYgJxZ>IW2{A-NL_qjyxaskO_p2Z=V5YZ{C2t=h_lR+2jd}gkEe=^NZ?leBEAPWCHps{Et}SvLzPC-jg&*ybpWxbi<@Y$9wWt(H zz}}Z3aDd?;!@-6p z7@lExq2U#VH{!ha)t=qB_#62!ZvIX_gJa_5tN8d=`96O4U4Dr@e#@WnxkUL7zG*F@ zMeN2hjw_{{3HMAb=fpXz#kELbTqu)V2Cs9FtKps2qFbac9-BjMf?ws9TjNamhQW zXU5Za%DHfawdffsf)DPM%i>c9~j=)JC$x(RoQ#l%!e}SaHJD1nxyDo_rhh8%Y(3MDtRcuf^GN$lLH^CwU)kl2<;C2j`dLaLFR_EnKyP`~-I@CBMU`%gW#J zyz;W`1jZ3nmeb($)*^KzE52Pr&Wr2TmW$)2*5Y-f0v^&pcE#g7We*(PME1s+yk$RJ zt)(1*U$vHla7#Zq7?12APry^U$TRTV0C@r4-$P!B3tEfgkxkgMpS%aR8YmyZ9j!(4 z$XOgZT)u{9kCGqYm@)DzoO^=&8J`K2|KNx)*={0zI5Xr-c+4z0C$4BMzDEk<8Vltz zc;h0u8t%JHu7@L*%T4jp)p8r0EL!e@<2J~>amB6j5bU>I9*ev0mZ#tWd*ylf+kSZ| zUVT_zhtD6Cx8v(4un3^*?7foZoOs!<7uzGThK`3&ZUVcQ@SM@Cd^bamM#*+f01-gS-gW{vxl!9trYh z9Q0HE4-ZY0kK$iRiv9h2&*5a&;)moqPLo=Gh;P`-uW^kG@)z7SlbncqXO&Zh^8IKn zmPj(=B{}6>cvW7x2tJozE{n?+k*nkCC1iJ;vXtBm_bMy<;yLAIf4r!&+y}3$E)T{1 zYRDnDTy1$O_N^;N;I0kiDC>A@kwy}YU7E-{aa42pAl~XDpTalW$d~a$Klv_BWi9GR zUf|6Bay-7@RsMxv_K;Id=J)lHGvFcpcz4T6}!DybWJi zE$_p(*2~AS?MC?`?!HyNjc0C`pJLbD@_W2;ubhDU?U$2=(dNT)TKxRDoDFY3Dd)$I z=j4*u&05@&RKk@n$+ZkOG~B{)d&Aug_cuHO@4lO_$s?#rysIAuJcQ7h8x=y|NDRI zi<2dn{c*{Zavwa~ULJ~# z@+sV-sC*e;EGggpe@xwXSdL#D$MKBFD#=dB%E%~NwnA1&$R?X?vdPHECS(;dviB~V zjO?9}6|%C)`n~zMuHQL-y{_+dp6C8P<9nWSpZl(Zzm<}oVau}eJ8WA~{*EhGmMv#6 zXZW)jDa{6NswL;b!|TWe@uYfk$v=HO<%)Q3W4RX2*IaIh>$Q-5uy<>@BOcX8?u93J zkO$*(UF0$N)jvvd&hU4`mb3nUejCHN3>P$95fK9#V?ZMin~x+gcn0T1MsIPkID z2~U3}_r}(V@(>*LS{{pQCCO89(g%4SPW~bwb=QWybW)&DDk&m4&Z~S|iUu!cN)b&$w(Z*T5AMZSmAc9WlB+g|cJ?BFkd#~%G<%Q=h*gXPS4 z_@B*wX}R#E5pqF1Ym8hH@AJ zo`v#Qd}N6{6%P%Q=izTFzJTrb$hUCVKKT*e zbVz=M_aBiz>h8Ncz_P9H zOR_&+d|eK}P438nIQLyS7!UjB5W``HHyGY!INETG;VXvk8cr~rWH{My>X85Qu{NC3 zZ~?>4hASAZX}E#m7KS_EJ+JjX^u#Ma$b;~@FY;(S_?sMrZ~Tb$t6F;TkYkSfBNT_KjTM^@^Ae1&*tZ} zbPHK?D=ypN0?x7no?1qB!Yy277ksFKTos?HB75L@Rb?;yt)}dY9qY(`xMV%qA6IH9 z2jEVP7G_%BOMnp7Lcpps#!vFYYHN z;Gcu!BwYB<=Iyj(>^eeDy@<7uF|svo^=DIeT25>~NiKj3PnDf< z`*DQ>@^ReZkQ|Hq9FcG0`N!mkc-blWCC(Tle=_{raJt3+_pvkVVA#p9t6?|89)`UP z`x^E$?2l($Rc--z*L67%=e{G)zzK132!8uO4#Qs`%aM3=g1i$4CCX8_`78M}KA0q5 z#wS0@arpIT`6>RGEWgEhe#+l)krbu=ewR{(^4nx7XTq)0$~o|%46-ABl1VOs6K&=4 zI3$}~1Lw*qd*Xa~WN%zAuiPFtE+F^7-wMkE@tC6WXgtAL4#HE)$a8RpvhosaQ&En< zk1ESs@bhZ&KAgFxd<+kAm(Sxo_2nDby@4E$8#IvKq3(Q*JTH(n0J zRVT^8xNDFcg8NLD!|>Y~awPsTN8W`a7Rb@K=ps1=yDXKjVBh8PT^zkqPQZQF$Vqs? zIyo7y+9ao5$~<9kKRkaObEd*lMxV!!N+t)k=#xXfX>CXP8OH#F>HxTE1-h6fuS zV|a?;xrUb-USoKx;RCpStnxX52V9gd;DD?0EgW`TeuORV$ggm!`|@X8B3@3hjCs^! zIRo}hkh9_TiE=)C_>Ei)KTDF!;@2PLYB<{$xgI|GU2cxg{g&I|4=GCj9S6GOWtQ>) z+$Oy|5>Ln|Pr@ZL%d_zIEb?N!FT1=NAI>dr#?SJ|dvQZY`6wP-P(FwAI?31Zgc9-t zyrHE00`G8kYjl*yVNXAKI*#ooFTfLe%PVl{e)4*}bAY@9cN!ue z!cT_Dr*QpI@+JIntb7OO36!7U!jt7UxbYPEE8ZC_r(D7HiP>^S{B*9I9lr^Y9dY)> zatWM&nOq(RhRZc@d6{@%{~Rd;D;d+!MdpCJ)56JLOS0_g;B2E_6_yjT=SD zp?KR-c{RRuT;7a}pO*I-K4$p5;TwkI4JR7@X!w_5tFZr%mBnx#yy1#+D1xtClgr?{ zx8y1~b)4*utslruaE`}vYrOQS+y#5Sko|G&OF01Fd@BdyM<3*1oc^;Mg0m;fVR*?8 zITA-$l=)llJMpH}ax}h{Mm~)L)618!WhOZeXR?)_;%wREx42pk`5UflFQ*Ep1|8%~ z__Cv%1CK5&JK_i@xdd+MESJZ3O35|w6j#|3zo;O4W82Dd2b`mt+!NQRArHcyb>z`_ zQ$0BdU-Ojb;Jc0GCHPS@IRbC-mbYNr*781Fxs7}bKW;Cd$Mw3%H*o*1ay%Z=Q%=Oo zddna2s($h>e0G3rwUXcWp>h^nVT7CqryM0a;jZK4GI&OyTm>(jEW6{dX>t>MI#_Ov zFU*#^;2ZPhzPQaoIRK|$DhFcM<#I5tyiyLq)z-*ixZ65868GFF@5HY*%TajIb~y%r z-7R0i`S;0pvC|y)2-&WFO6)6x2KmK@a>GU6MmRkcEO2RWjCB9 zhwOoe*vnpcnS<<$>pRMR*sHMYj{}_K0DQZI9Eektl7n$NS2+Y{t{{iuN|oddcu7@x z7d}>9j>cze%Q5&;UHJ-LR$so0e>aj7aGGXv5-#N}C*wJ-WXlNNe_z=K_vs+#!UMX< z1@Yppa!FjLr(6-+^pe`gG;(O9_`K7Cmp zjOSmK$KdKWtTO34p!I#>Ax zeo;>Th(A=4e_?w!*=im0+Zu8fT&#|q2T%UzBDj^O;$?7LL%9l0@RB|7Yj4>LXKN|@ zV#hYJANFh~`{U-FkiPv_LrySDGv*;G9$CxA=6h{0%ReC8t_XJK|M@gn%@JGl(*{ZX!B*xhgw!>tW>G2GYiFvH^w2OADC9EKBrD~Cv&C1u&awZ9Wv zTFOy)bb9$Tj>srq#vg6uID9RO{1nG!m*3)4x#Vv+ql27k1IKcdGvO))le`lLZj+<1*Y<=}+lY-JZbGrR1DZF9*UIERDmh4VPdzSzB> z+!enmBKO0Cipj%qS7&(w9_=E}z!7ETg?M8{IUJX+B5%Ous>{1^mD=)Q+{Il!gL~DN zuj1DYs^q$^T28x-b(OTTEw;-b+vD6ea$#I5vs~J66~pd^n;33wxQpSwhKCs*Z+N=l z1$c|SatOn-^2(8TK>>LuK2%7K!Y7K#r*W*ad>J<@Eyv*>uJTjdsiOQAPpvF}!*i?2 zskXC*Ttm);kJgcM;01MMN4&g&TmnZlk;~)rP30Q+n78bSf3=jov0q!cJedMFK)ByP$t~f-#jyn#MAK>mI-Ze-72{=4p=Mq!KK&9 zL-E>8@;H29i#!cq-yzS(_x8xkap(Q=I=thMyd7Id$p>+b)|U& zax+}wliU{1`X+b7S$@de`|RJuANezggw*9vv9NY@?tz9qr3_SW|lYMCt2k^ zIAad^2+n3NpT*T2o(e)$1*ca&ck{$Tj0;k0}I?{90^-f&^Vr43gx?2b=3SN!|h zo8Sp$;wHW1Z+KWAIn_SSLHf&?@WjD#4!m)w?1*=a zkW1h@qvZ1V(KxvVo;6YS#94x5Z=8F&+#au(A@{)R=Ewu_)&=q?d~=~3geNYM=U}g8 z@)F#8r5u3=u93Ik&~@@Y9KKOLhGRC%=kcL!@=bhmxBL*d-6y}qnWE%Rxcp)HH-2xZjndMiBsj53*g5EWM}-kh+F~JDK37sXY{3mH%lq&}H~AQ@P*XmSpVX0W;GT8mc)ZtB zPQ;5E$sh5Grt)vRwuPMTAZsSAWIKGljqHGZ+sjV4Q)k%)ck3p*;St^Cx_E9M*$eOY zmwj>cK-mxX8Y=r64!|ErDISOmj+29N(TQ>hz7iyd;g-|nNc?+-yc18HEl1(0^X1cc z_9FQ*-Ww{%;hZbvr}#;j{1%T~C4a;3*U704F{W*hGvP5?exKw-yzqj-3!ZK*yWxDcvIkzAU2ckxLl5z-+EG>uQWv=oD!@CSe8;&u2#qeFj35Jsle>ZFy{r_=o4CgXj&~Qn^ z6%E%i+|aO(;f{uT86IqStl_DK=NVpRc&*`Wh7aJob@YCoz_T047x3OD@@<^cTYiL( zwv=CC4`2B+ZronBILtWTSx%2f`^j1HtFCfh9N9}Qinsd9u6Wl#xhft%Sgwm72FTtx z-AK7T&NNo;fzM2k2jZHOigyAiC?qbCc;La=L6L?y< zd;zqhw%9=cWjjF)ehEsk*S({4FEKD$@WiZ2|L^Wq_g<)ZlOQMnvm zc~Y*9_nwtKv0JR%0zbYacQo7!pSh{{U>qAKkHMer$y4x`hw@zf{i(bZ7kn}|Nc;U0zu86Jf*+bD<0cusD4HeQ@p4#h|E%d2sL!t!QZw3xgXe=IH^ z#Vt$A=kZt<`39a;UXI6BmE=ThT~+>wv(%J-;q30R)iKr(>dIMgQUlom=WHxH;e5?x z7sFKz*Tpyg^=bOY?bW{xzS~*uiWhW|`{8sw<>A<;k30d7@t5b|CWGarcw2zH7MB|- z@4{8a%F+1q1UUx#Op&kPlT+n;c>GK`0k5AeC*dvgIw3D?2#z{!2Yk~ zG$$B~l4M)F?7eJ{e}9$>Ki{R4ZWf$CPg6xKUgJcifZo2G+*UXfC@xwW?AAYnz z_Q%Z^$^kgzQh5T-9461eM;thM` zdwAp_`57K}M1F_Y9h1M~ji=-^r&%93CuhcGV`Y0>;j&!Ruq(E|rFd1`@2*@IJ3o}0 z;;)b7HrOLU?uG+j$o=u;*YXJ5?5#WzXZ$G7G`t9p`=%>Yy?h;qTFVdc*DP`(?wM8oWcat?bTR+;u`}#o*vYVqVK>7bhP@2?8ul~n zZ#ckkAReAqIS1pf#pDpfVR&pA#W&z8<>g&CO+`5xr*o5I@XTuR62R5mJ{&7 zdU6tuZYU??>5b*oXSi>?nQV<;_{cf2ZELvzKG0Tn#??E>74WpqaxLuRCpW@Qz2ug- zgumPw2M?6{;8ug>p}2K`JPzL-Ay2~(#>n&Wqd<8D?mkIgk26h`ci_3x9b8Pf&F&L z<#F&HxdtwOK=#DhqGWHJ=cwEsKR+h-z@De&f!OPuJPO;#%9F9*fhjT2Gn_>HKxh>8cA$P;BYvlfhN8+KI6rY4g zZj)!>al7QjIMrTx6;69l-h=}V$$N15qw-Pw^rUjJcF&B|OVXu8osQ$c^!#l5#7Yvy|K!*DWXa!Jd`m;kZ#% zc>=yvU7mqU*O3=u*Lrd|-s356#2p*Ud+_0A@)2y`Tt18IwwABser@Cjcu)uV1-{rt z{(z_W$-nT=o^sktjMaT)TYRyfY>!k>5afDnMPZ=fG!E?vSP4N4Pa%IADkT6p!5_C*e1HH&&dAQ#E>^C9hg_Cx z;jdTahWN)#*#{T8BX`6_@5_C0!XtSY-tj~Z#MxfRGjN{Q@?!kstsH^7f0DQ0zTf11 zxYBp|7+&^UK95(Vs`0nRZ{Smway&kpPEN${GsqutF>CpkVXG_u$L$O|7&cmLu&108ziccQ!1J5QC2=Zmxgs9k zTCRo1w38d+H63IhyuORv5$EhG_cA;LKkcRXSiG{IJQZ6EmgnICL*!+6$_RNKP8cI^ z$1TUn2eIuW`6SLZRlbBnr^|Qn@>%i|>@!h^Fo|1#HSB$(6w>U4a z#N{r^+i<0;@Q40ko$&+u@=6AaHZyvXoM!y66n zHhkFd8N*i%-^2N{D$i%Qes=jiw#Xs>!29gwG&lHt%r9rg#U16`_)8JF&>t6Q<`~>#zAYZ_JyU4e2t{(CuT&tJ-3fJ_PKjUTpY;lwG#DR*Z$C(Dp zSq!lQ-jHHRQc`dL8*F-r*si!+SmD>o}^h z`~Xk$l3(DL-tq@**HZq8bGMPx-r>95LAJ&9I?47pva4Je5A80O#v^;nmGP>+avj`Y zfZP~c4wYNs%fsZ(xXdWI4=y)O9%^_T?l@WTX}H7`c|M*VEHB3{v*mTzcAmTg+bxt2 zVYkKdDg1nydnEUyGM5A8`M}6WIn^K9h4}>z8sNJm{@l3NLvlSHg8a$+dC6 zFLEP%^}E~>kNquo!fR91`8y8u#u?MdL-8Cdc^nSSC{M$6Gt2Yw*(~yMd^nrD&hU1_ zhYX)Ie9`c2!;cNWHvGkKiunJJo5654T*FcM+C%GJsEg@IOpGwO0@i!N_ zId&{3x5G}AoTtCyw%B!uY>(RvlMCYxBjwV# z+gQ0Wo;hBwgR4xI8{^Pvaw~i^Snh&P%$ED&IdkP`Tr{m$vi5)EEi`XTNd>c2;AV0=FHu4+n zXe)okle5VwA2Z*`C1=FD?d9zFU_RLq4=*H_!0tul^0>8=T*Gh!!z~PVFx=DdAj6{# z2N|AYc!}XP_?D}3*ovE1mG|S8HRa=YY;8FfpYxD!8h(g<8!P?_cW5Sm#zEe)#S^X( zw35@~#I|x)oTY=D7iaGx7sHSIi*l}Uv3;1F zh@VBspRmn3`4`^1LAH9z`S?aT3$C_Z&V#4zl8a!E{jw__a!9U#(Q7N zG1%>md<8#xC*Q^CKgtQX_g6Uy_x~X$<3+#Z)CtTDQhNNYacg`mwVV^5wvr3ra~Wl4 zyvSOvfScRNHSx%7asxarm)rtRbdWn>uY7V(ytSY_2;VF$kH$g83w~Th-iN=q$;S+zH+;izyx~N{9}WLDobK8G&u?eg!LXBI7aUMe`MBZH z4P_4;=p}pM$Y!!HZtf%d;Tx@Fe|)R09Dwh4lml^^E^;u=&|O}LXZMuDaizZU1{^v- z-i412lB03VFgXT)86jW6KgY=NxWfcF5eH3@KjLRo<=;4Lnw;)A-@Vzg9qu$wcEBSS z$xb+NvFwT)E|;s~R4e5A*kQHY90#tG+u^7Ua(8@ci#z~d*ddR^&3DU_aGU+|Y&_wh z9EztOmRIBX$K}m9$0>O)K5<4qitC@3&*7$*vSjXyccG1#Gyd<7RMD&NIx zi^~akb169q`?|`>_+B|Vbt2cuD#_OP*+1trT)?oi;R=Rp8g5{?h2ai{dm0{Oc(mal z+{0bD&B0ab$xHCV266=M)>z(xdo`2y;l4idF&y*H=W!=r#c$vv?d5oUqO+X%r++v3 zGhW|Qws^_4=00+IoWGx(72h8u=ferZm)Rg6#}&57u{h;6 z`Ig~Fc+MWhU*Qi2-`-EF5+8h zc$48hhL0FNYxo*=uA&_7<4qp&3tXnY`~jb7ApgWsP2{w1m}@ncZSkxYvORv)S}y#@ z?PM3+w6pAnuldOy_)ZVm3(x8+`{F(QWIyaTNcP9ihR6Z#@yc4&5BuC*M3G!(?`?-7>*L)@4#V6j#&v3~P zauUAxSx&~CzsYHmSabU+XU5l4)c;%Kx$)0bauIykN-l$+rI)MV57x3f{*^`c!bP&l zzSt#~?1y*T%l`OiJ~;pnEGP%!Ple@R{JWSOf}Nb@Fzi}Jj>Of<$vg4U3UU-4SVcaK zL#xV{as8TdoZ+X2-x~gAIMuuVADhW=4#SRyOBgP1xCUMRFg`>ygFe71+Y1efV6N8r}|XB8TIq$K(yT?J0Q| z?tWH|#3^4u2^Z z#4)eslKApFxg!4dL9T^Uf0Y|zn;)_duJ}vth~NHmFMK$)=ik~NjQy?TF?eJqc?w=- zBhST~?Br$mS~httj?X1;!*%n@2XL1B@(CPJNWOr_7L{+|wZ-MfI9+M^HFj~4f8h7! zWy_EJ&2nYg1{bU<=fY9d<$}1ZyIcyltt(f=ha1SXaBw5JA%4?T_Q7kL$sG;%Hayty z7{gNx&o#W%@EXHg4evL60vBno9AfdP&hkwh*iC+jEqlr@ak{?pCw$#s{*5aRlGA-+ zt#6oYhkFf|9q@qBvJ* zh01~W@KQM#_YIRn@Rika7_P8hj>Kyt<(-D3u zyyA%b4W~LOr~1qs;EbFJmpv!vz|SwrjyUrbxdhIALoSa4@5nXryEwT4ZWS-Lz~dgt z9q`ixx#yq$iSi&E^-3OtC%%)X;PRj3xp@B<^q-4}jG^2v6%enHs*w{Vi3@QI>w zIb5!|Tn+CiE!V^L<>Y2~awWMFZdgt3h4a>w2ji0N@)+z>SDu28G?3@xi%sO^_)AlH z9q!~KZ^zE9+vt!~}T`J~c^Rf;&u=BXI8-@)mq` zj=T@Aoi885+ZV~_@$FFgCVskHeu&?#lwaap5%MRze69Q&zmJsDePf=#MYh8ycE}F+ z)h^iyf88g${ONN*cEhC(%O2S6xa@`fPRhRc+!?tmz7;F?!xoq1;W*PZc>*qfL!ODl z?#K&qpSyB69uY5Zz>l8DyKwUaIU479DaYU%ujQ+_@jLk*Zu?1oh9`cJ-{Du^ky$ssqy!*atX z_rlTn<-xd3L3s>LEGAFE%}dF1aY|QtDGn+pufg*w$y@P(D)Iq*s=9mvJJ*pf;F|98 zE!@FVeuRrRlwaZ5Uh)_G-dj%bo!8z{&VaM{%GnI(GhEDYS;N%~*E8JQa67}@4G+M{ zopjuhcw}FB5`H*9o`t&&mKS4}q4FwRd4#+PyN{9g;J)MJBly}x`7Dl~B45K+)8+fP z>p#E1mFFn_0Y95B|HO?K%V~cw|6C&5;J{$sO_TOma_r&qf}EpV-Nx@v9v26r44;JP$kM zm6zcO1?06jO<{Q(-cwXQfcq7bPhj`b@&(+utb7X(EiXU9`6|n=aFeR?XWXi$Z1Ib~ zi*c7T;D>ePZ1`CNIUlxZEEmH$o5^LdqmNt--~Q)%xLI4po8i_S<+k{4XSo}m)=ln@ zGxd~5;7)zyiH2tyUSxQs;f;oO8$N9KjNz+>?-_n(_#KWPrhLBRO~Yl&-@J#TWgA>^ zoSX~SoG2H>uY=^0c>h$nA}%mXu7&5#mK)+t3*?q~$6~o79=k;Dg(t3%2jeNL`4tX6 zBY(y==Vk7Ou^4(uPLH2nmb2ouH{`sy`5n0!cD*N;#cmJfYPjZ8xgI|8Om2>2Udruo zrPp$I{PmqY09$;PN8+Mi<;l3>PkA=3mZI_BdJo0jQpu~ae_DA94oN5P!(TJW$8bg) z`8+P1Rlb2s=9J^HPj2}oZl72Fgu54zf8)eLa{3f0EZ!BB?QpIVvIEXnT6V%k%gQde zX?fWV@2V_&;PGy9Q~bDw+y=YWk-OqO9&$gNyMa6c*KQ)(KMbcy`F}jKVSB@c z4VN}t*>D}hjSaUl+!;?8uN?Z|4HM*Hcyo|E9(S7}PsbHz$_w!QIr0kJWxl)~cV8s$ zz_UW-L%7m%`4q0YQoe+btd{TKlk4Os_;sZG27lNrf5qRn%c)YOuo$yTw#N7N$vJW4 z0l5I)eOPwJ`;W^N@WYdGP5kVP+yK9hm3?rwOL9jXdPVMqYu}IuTQXYm^xX6L{R9QI~7pWwN;P;i~Fx;%V9Eo?^V6Kw~dug<8GJb%lPO& z#~FT#m&d8kTYU1KoQy9%l+&bT+X7M?-Zb!~0Xq{jftic{slQ&lB(l8^vefop$m<+$XCXj^nb)8*s)v@@`x% zuN;kY7LsFd%_8zu98p}phtE69&+xS}@;f}PoctZ9swi7prLf50CfnftHRN1)Q7yS3 zUg05^!oBOsm2vS#avj{fiQE{^X)3qE)~)2u_)crN53bQ(9)=@2%j59?KY2R7*+X7{ zSND=vV5@%edfac2yaQJmA|En*%J3z_cMLx<{KoKC!zt7K|NI#ZXE*GK4~$a|C2;i# za(SFMS+0TiOp!hD;2E+v9yLd9k8l2S58P;>;sf!e#qub8YneP5yRDRGW53mMD7INA zug29k$Xl?-7I`0TvO_+GhwYNj7<-0eF}>fXXQ+| z-32)Zo^(le#LutE&iL&uxja62N3MY{#>t+z?nBudCq0qd<3kB@4?O0jJO~$mE04xo z-pN6D&nI~f&Xp`L!L@$K5!lnB>E9aPf(NFQ_v7Jd{_`E#ysjWNUd3uG>aFf;V=M z&*9RY%i7C(o|ws^w`*&e4EDHk?e+HhsV zbqqH)+{$og!+i`7H9QUnP1bRz{fW<&=i^fI<>h$(B6%IIzEs|h(=V3~;{Ge;lla4G z`64d0R=$l>ZjvA4;#=g`_{Mhm3vRPZPLYXohkbGe-0P5>4bP31^WnwEYHaJPPl9AWz1J9?P@w&8KoGUYIDa#^2t^ zo3Z0Nc`v^3Q9g>Bf057O-QVTwxYKX>0e+IA+26W;foEIFAF!R3{1fNOD5tfi9y7~X z@U4H&gX?Eeya>LUQ!az=KHSIM{HA;V{FIhIbl{GJM+bWy5!I`8mqrDc(O%ev3~ml)vFui{(_A zdF{*POgJK3&VeVbmL2h(b#e)ua)VqR7vCh;z;-)iPwci!_Qoss$?frmLvl}iC0ZVY z?;ev!<4z~#Al&PWJO>Ymm6zbf7v%`N`l`GYJKd1?W0yPfalA54j>TQ$<(s(Q6Zs)t zm>|Ez$%*o39PviBuw~8aotz%Kev-4|HecktxZ8KRD7O18yW$Tin*Xi$s`!_sTo0d3 zD>uVsGRkeSdnUOX?wCdHk8N|vBXCZ8c_OaqAkW109p%ONd_j2?zUm}z!sANFdvK~! z@)5kvMLvt?l#{RFMU~_S__>?>0>@OBKj4eC<)8SAyPP%)HRUPW;?#|0dpy-kE`sNH z%VqFBAGr$d>?^zD6Yb?DxPB+OHU8iycfqZC%Kms9_{l%tHJo5L$?$i>mUjO?*2Zuy!vzhOG+fbe zE!=gX@@a^}!(|`*CV#=Px8xLAsh4|l2AnEh&W5)= zmh<6q3372hvzy3% z_<3{LANTc<1Mo0kIS>c7mxFO+M|mOM=_iNdirwW6_(?B$7jD>3j>dxr$T4`#5cvvT zGfcjRw~dq&@PV;%5`HvZPR5Coi`;&1I=#om_kJv=I{{0u+JAiu+}ZRGE`sjY08lkZq|*~V}#{48f@srrqN4|&``O0^&Ut9SJKGRWtgY)>wU-A7O|1oXfVKu&S9LJ4p zA|oRsdt_v9vWcunX0po2D3T;ZitNmg6|xf9du8vv_nskS<@e^}x_-C6Uf1WkJ?DE) z&-Z@r`+3fhQ|0~NnX%Pi<<@xaP`NO^>@C~jfxdE8e92#~k3+`FEpVnF*%@0;lDp$a zA+iU48zv9KDW}P!amHD4Fbh%1h3vHx51hA$z5>e19Bf+_lP_g_l=kR z@X(WT5Wap^o{F2Dm*?SaSLEgR;0<{_esN3QhCkht58%#^<&${)Q~5Fudnw<=KVHet z@!t3HCtNg9{)Jn9k<;6xOtIy=oE=;Kkn`iGDLVe`_Y(M>g=~+l)5*1P;Y@O49GX>b zjbp83SKK|9+zSWimIvWiHnK0?UO*m)GZdDm;F2ZeIk-(Jc`0@+E3d`9?d3T9ypp^R zCsdP<<2*Ixi@0!I`8K}VKz@doH-l{ zj~s^=@00gqr$h1yyggpNgpZt*@8H*`JNk=YdK1 zj)goEKT9u1;18MQRXA@}c@xf_UEYOT=aP@$E_vm%_;3OFI-Xugeu%#mm0$lEQ(XRH zI7K1$JLQ#U#5?WfoH)LUTo7NVA(z5Qwd6`TO?|lzF4sVAifcBJ+u|lI=!8i#1n$#w6-ZzOq(QU!<|Fre7NsaxfrfET`rG5&6aE6-gD%J zxWq!a6%P7m7sKv`2O1t>c&y>chQkdnF}%j`X2W~1?-JE>41bB1FW~7LV6Em&@SJ zwsIBRrsA-uD_d>Y$!lCR?Co#p$uLwETlc5|0M;m5t@UwEd6oUSOx z>@Qnk4=>pUpBW|>$8~(<3b>n}ToX_9mmA~CfwB|cF;4D;(@&J$@u^UGAf7ix9)a^s zlgHxJ;qnw5GFP61r!ABtagzu++VB>`dkr5me8KQ-!%q#rH~h_T>SF)DZWbKBN;Txh zbvDU`@yji;9roHLSHt;s$qqPjkL-w}56B&`2^o$1^PC5_n#E*&ZilmTTdomU3fUJcryG&&?^jV&}Ya zZ@i;`?1d*3l1Jj_Mdk7MT}e3%TbGgNV!!h8GW?=~ycV~tBFEv_8uC7Tqn3OeKddKT z#IG94w{i9+@>6WnLQcSqTFT$?>Nc`P37-2q%a-_12RRQu=_(h&YrD#2ah9HPHC(lq z?11a`lO1vR0J#Is?IriX{=?+{IB10IgIkZ3$Kcq}atOXLMxKQqjF%VTJ`?3t*eX=s zgng&VyK%$m@)5jdwtNkh$IyX8^XX`eg+I~9Lb2gE4;s;ITg7}%ETnZ0xk}Kh1?c_SxucO=)FY6??#ZF!2F8E@1xevbS zE)T}_`pJH{pQjvzvk#J|;#z~{c{tKrUWV8B%Ik1$KY1&@5g_l!%>(6=IKu?_GPVkl z@8X)1<>%O8n*0H0o+1A*oTd!xvAN2#;^zzGyx1aAE{e-8lgnY-m2!1FGfHlNE!WGf zaPCdA3tqHY?ulP-l?NCeZaC0zsNva$ml$4Sc(dU>hT{#NH+&NhJg9meW9MV?TipGW zoP>kV$f@kuBV3R(P|ZmdoIFcjYSh_XD{ep72<1j;B7C+v6Iq*t2U&X(3%l8ex#FYyw|Af2R%D-@yVsg5&%yp$?D;!Zqw!uxx%O&thd)XdetRmOK zRcgwOaktuXYuvlO?25x0$i49FCbAb!Y9WurwyosxxJ+9)47YDD&&6F_bU(hxgjn%LvDq~h088@;(Xa1r;m^a;%t%f2%KkyJQh1d$&+zZ zv>cAltdp1EQ8DrwygXLkjMr|J_ZW^heBSU)!;cNWHT>0Z%JTmoKa=5Hh6@=kZMd@G zy14W~)!7VRJtDWqHBQLgaL-e6KYa9@JQTmVAp7IbSLBI!$qjir&T>m$fJ@z%SKzh} zH3by(v-^12lcizPGwJjb&@k<>n^f2KG0pZ#f^H(WpIl=auwXhQ?7?c4v?GUF@xpyIOQ<8 z+n@2n<$idxpF9*7_Lu$f{Xlsl?mb?fjI3$WK@c_p43CU3;`X2?7KjF~MT!sq76 zr}5eC(cw$E{MJA z$)&JQL%A|O|Ic;tt7giZ;Zu%sJA9*!+!ar7miyv#F7gnZrHky3t9Fwo;)tH|biAUE zyZ{gGC$GR42gn=nn8EUPoN}0a2xl50pTd<#%2#lm(egc!!-tu+KC(AFeW6E{5yQlgs123*;Jj@M5_kwpk{(!b?}kop94KFbqZFsZcJ%-~ApErEd@MFVo4S&V%dsSP?s=Tk`awdHIq?`-; zoRtgVYZv9xIQg<%8JD;w*Tq@y$jxy0J-HnYekgaveV@pE@t_y-5PavQJPI#@r2}fV)kXd*F#PWltP7NA|{9=gR?jPlP-P7g{RM!p)Y;5jZhQj>3Lx zWj6@Q!WrHC%hA`~dszmR}i8G@NWWeU1OeXE&VRa0$Z|4c9W< z*l=sZu7-QzFY&5v5T1HL_QhK-$>Z?R>v9-=b5ov+Ki!p=;-rW2T5S77j>Dy2$op{E z8~HendnaGQyFSWy@WVv;8Ge-{C*bTq-TDp$vka>xyEKWn)q&XG^rEpOdgIemXHJS%`$Q*eq3IjjXf&L zi?MfAc{PrxF2~}i+VXC^slI#^UvD6v!_%6|H}JOR@*`~HB)`EY+sa??hxT%cTC8+g&b*tGLUh@Xp?HC4AUJu7h9omz(0+UUFN!Vwl_opYoCWV0%A#Fn0Bq z{qX)kIS6MBlBeS86Xki>Ayi(5ZNubsxa16ZE51Bi-j6%Yl~3TF3+2l=bdh`)&sr)! z#|u}=A8>)y@()~mot&mN-y@2VvtpN6IWNwzO)iEDY?sU9@w??3h8r4gW!S}VPs0NY zk1#ye@MOc`hL;##V|X)8c}%tK!NDiwcwG66d;xboC*Q&cFUe2vscZ5({PBjIgn!+U zQ`O;fyDw+PVUJ~NJmaiCKldbTW8L|ydIa@A{E#}Gg zI8%gN3s+t&H^w!V$*pm{DA^VFTP^p(N7u=N@XQUeFa8uOkHgR7+a?ZFq~} zy@rn&zF_#a;irb*8~$cEb$zZo2UJ@Y>~c)bjjNrM3*)_g8tNaz;&mpIBU>%!B&Wz*o%GP*TLD?2B zw3W-?rN!hb*s+vcAD=5DH^-yO%k6P=MY$W!TuttWbJmiF;yQI?f85wXo`?rEl&53w zrt$(@&{1B2SG1Bh;I(b#?Raws`5>;^Nj`-ibdj&(^xftAc#ymN64&T0f5J;V8S+Tn zEnFUt`^}fbaHWOvTwHsJyc8c>Ca=ZkqvWmlMzp*iN3D}j;0&AOOE_DcdnG@+?b?$5N9t#Ir1vJLL!BA3A3y2zDremA*3ZrMw2 zft~xw&iJ~g+ymbqBzxi)L*)_pgpWKHm-myy@SV}}T)a0>UW(&`-n&qKk1dzT-|@SpvPBd2sw-tnoFZDzgG;TGi{Oeea#_4B zR<4HE#mNqa9SwId+{3V^VQ<3$h9?=GX*j}gl;IeBZolf;i94N@596Ze+8Q;sTEnDJ-b>%!b zO+&c|F4tHti|;g(tKqPgvI8F2T6V-E+shsBb7#2+j&_wj@z!p#H?H9(2jENYatI#K zSDuM|`^yn{td|^x*9?(k@D?9=C%!d8K8&A?lF#5)f%0`ce4P9ckDVyL#%m_YpK-@2 z@^8F*x}2do>+o4}4%~FETmU;QluKgU#d1Y_cBxz&w_71M!JSvjZE)&!a%UW}LGFX! z#L9zl&N$f*=iea*;bME_sd(H!&ojKt@H)d=4evL6!tf=-cMLx>oM8C7VT%_3*JFu8 z530^QIQ<#92%dUQE{khilB?k**JKAAe?xY}XYa@zaJ&1m8}9O0?vHyvmwj;9OL+`- zcqfP8qY3gXd@fO5gdcsDSL5H`F5E zmCxXP-Q{ceshj)&zv(T%!k;|kL~JuaPR8+Ga{89c)kEd%xczWBKlb;POW+`X*&c@l z%C&IT@p5CFD_CxWOHYzJ<3?d}Z`^8z?1lHvlt<#gx$<~yw@?nlnHJ0QaQ0>LQe10= zycRcDEyv+kYvp}-@CNxf_KB4*V!y5OZEU|yeukrW%L&+GkNn-RMXUdFOT&2#7cpGU za5cjYh8+!eFxC zJ&@1fd5`34*x{M{0NcKlU*Vv)aw0DKK~Bc8pXBsT^ukv;JD&JW&X1q}l1t!ODf|4L z6YOy=3%M4~pI&Z^Uu2M55_rdaL z+}B$U#$LYi3_RCQj==FCdfN+V2FGer-Gq?1E&ij4AXTr0D@7&}|ZtMT<5axAWsN8XM5x4jd{U z!j9hZY23kAzKU=7$@lT&0QnVeHeOD|IVQ--cvOg-zCGWeoh)a^>!->2@%CAA34AYH zu83dGmuul)3*^SQV5Hm{mtG;e;&xGTFT5*S9)usRlYQ}<7#1UJbnzr(Gw$w@e0b~#lC*51}~R@~G^&Wp1bkc(pf z!g4u0vAA3vZzw4@#5v2#t#AQ**#$SLB=^Mas>uWJs2cKcJh6^E7QbzQ|*#EhF53hJBzrY*b${%r`ck)kMFHuh0 ziR)vMY=wt@m-FGm$#O9qmdfLA@0Z7M7IF=|KfT-#Kg%e$!t*R;7sKv&NKWMgan-!? z2)xTi9*YMRk|*QqMdfhZwS*jrGnJ8}u}^t<3w~Td-ixEF$j9*L>hc8~T3fz_-`1C( z;9L#mclbyXISDswE~j$k-bG6}Gw#|}w#F0M%eHu`i)@Fty2@3tdpEg0F6u6~z%6^r z&e+96?v4Zd%N}^LmplxI50eA%9v^uUJ~mRGi5>mr2<$LMj=}-spi zxZ-Eo3D^84cfx6Y$nH323eUfNJrEyEEswy<(#m7;x{UG^yv0(UgKuS%Bk`l0ax~7E zTi$|m*~oiw>HP9BysEH#0e2`a-^Mpe%1`kVJNZ3+UqSwceJaVRyD~>rle6GeHRRkl zwvJpFyE({q_;EwIDxT9+u8;GykXzv5PO>w$Zzp%huFkRt?%PTB#uYou0r*RIc@qBZ zF3-dz`^XX4#zT(63kJzC_=lIg6BqE2591~yTZw{Cu8V5hq5-wQ>F>a#LJ(x!e}lStWPD>DR~}ICz6R z42Q?cqw$)}axgx*U7mphcFPNKihc4*y!oKK5m!AT@4z9)N8xAu(7yrJa_qY^a zdM2;M_g=|yIPF_`AKsQAAICL6$ro|`ukvl&{D=G$5B()4;5xtM?|5bE{(t8XiyrI? z(#e+CKZBeH&$E<^;3nDSve+u8Tpj1nBR9Zd1>}}Eu8`aj+Z2=CaHA4(f84f=?1NL5 zm&f2>dpQJGt0K?BJ*vrz@bOymDtx7$yb1qwkayt>P2?kZSPS_quG><+j{7>v5AoS{ z@@qW0qx=~^>MZ}p8N10D-MA0aQ_hX+^^%L?9v*Tzd}5$n9Vd9n4e+mFa!Z`vSMG@I z{p6mwet`3A=BSQ}tv$A17zVwYJIDIBJ({i_h$l%i!AwQ;gyCr8s1^}5N>!?^_<4hH|48%%U$_C z4t^lN#M7V1pK#Ns@-Mvam7LCuwQ;T56wGxAy-dQOhR4(H|lhEEv2WcZHZXND6De>ZH= z=l|nd8qQ<5C_Z>gHI&0I?#R_~+lO)k+~<+p5{EpOJK|ZdWjDO*t=u2Se~^dc7Kw5o ze)2^Q#TGy1**G*=UW{j^8u+*OSL2-)axBiDLEeLlW|8A@L{|Ac{*^<%iHlpyk8!zt z@>^V`p!^kgvz1f!W$r2_XU4Bf$ksTqjBJa4l$Xokq7~&TxLj4a9$r#SZjO7@mYwmD z`f_*tx`FJ0KQ)nu;U6vJ(RgetIT%lFE6>2++Q|!X4;OhQw(cZvG`s`HbWwf?d-jq~ z<1_u_Yxv3l`95~_l3(IJ!{krc-ben07mSqC^<$4PTDHQ&17#b0J4h~pQwPiT*dq^CkuT!n2jtuM!$J8e?i4S-$77Gn-|*AZvV{lhsPnQV&T~o5 zgNt30i{Lre<+6sW8Fn!2Xt;yn9)>*)dm9cgJjw7(!x1>=W7QLdx4e^M@T~-S7jE!b zK7v0c$!D?e5BWMC`&)j9!%`3W+vBhCQVaPrKAu)i>B+S_vz!Un%_`@@yK~C6_>r|- z2EWZGSHUiYt|8CB_iD=v zag>9+5}#=(Z^WgW$vg1I7V;t7!%04m$F-MlVvCOQW1O|K{1zYRCV$0^+~kz~IS+fu znem9evNgWjU$(_ByyP-C+fca*-s>aR!$tk%=D4N5?2NYr%H8p;ak2*vohT2(4#Dzh zoHI-g#oZKQ;UwC%sTT-*CWd zIrTukxAR`kg4cbJbK{Pm#4>&Tz*je2r2zSmGrH;6f^sceN~n#(r0b1S(xuGvPefa^QUHF4uk zawD9rv+RV=cb7ZiMQ*bDpYgrrfjE_?JOX?7m&f9YgXPJ%^H4b)XBr_d!B(T>HTbT- zycstbEAPSm$IJ0}Sg?E^e-4pv;ulloCphIy`5i7jTTa6E^W;=se1|7O&WtS<%htI6 zGT9ctT_M}yFRSIMIC-61AD`MFx4>mL%g(q%oZKCE+aY`4gL~v*_{v^60FOH;2je_P z-Ah*GtKgykP&o6Rs-0!>Wg{S|NN8(Q@2LJ8r@%TV0ISj|A zmFHr+O!89foJC%XyIRR{ctQ?&9}decpTO^JjfQya=Haj)ibM_k@fcEfX8%l&cB zwz3Z%&_N!9FSyDfIH`*~3#W3E7vVDQ@+w@pue=G@?l14g2L{SV@rfbwIh-&|zJb4v zkRRbx{_-1KCP4mzE02>?3}v4iBxk~XCds+*u_zc|A_MPu_;h zACM2=>PO_0xc+hZGWIwr-@|9l$}e!@dHEw=c3J+3i(Qk`4r4!fOU{O8-;?v<-4Enq z*yD*@0iS&#*TkP+$&K*ucd`>6k|1|7>~46V;Sq+%8J=Qzj^Rkd(T2Ae-fQ@n;R}Xu z8GdT`z2R?$Q+xmazOoq3jo<&!`z?%fC(CxYaH=7H=b5Uwg@x>Z+ozXXVE>G=GcIl^ zcgLaGWe=P=mplw7=axqs4#rOkDxZm)7L_CL;No%=zF1n0!Pm>lJMr%d@?o5|ihKr_ zuO?qJ{J`)l+{Zy<67j&saxxBYDyR41H%E?gcKrFD^W&>d%1h$09c6pGrjuL?Z|*8L z#yNY+t#O@RvMX-fPws^WdCG&Z&mh?s+YXh-;V5r;3XbuW=iqC8awNVNAV=edb za)P`Udxyx!aKvQ!0&X%*zJ=G!lAqx7;qp6tZNB^sCohy!59hZek#ZJ1aD|*3heyeU zab&b?hmWn3tKzdUa(#S#i|mNIZj(FU-n--;IBbvXiR&Gdy>YXnasVE3OrC^Coswtb z2j}EPxXyVw3U9a|#~9ve_^{zKhOZfZX!y0^&xU^+&M@Nt*Ue$LfZ>vcE8?<-wuN-H1A1*Rb`EeXNM80JB4)*p{{tVailRx0*0rC&SX-2Z2 znxH%@&NoTUhg~Mi#qi!~a(P^KhFk+X&XF79h4bZBcvOV!f{R7UJ#m>8@&FtYB@f4O z(Q+WJzFwY;>u!?6ag#WCDfZeXug4X3%iHjr{qg~v@Xsf4{88oCaqvm`AuH5!`){To&&iDp$vaM#v3tvypO3{N7*g zh<(P$Zg~GVxjzmFmVIzkh&%?b36n#x-E?^t?mJUngkR2CpXBiacGSE`Oo-G@^4%vPR=lzy}&Lx2QIr`E`XB`$R+X5BXUKY z;)GlqpE)Tv!Bfu3ZSagsa%a5birgFTz9D;I>zlHl;UL3P4bL;Y%CVeo#zaZ+Hi` zFRlC#9#TO*jYn3Nui_t7<@?yNru+(9*OtE;PC16PM`Pugu}cft8V9zNZEJVE4s<9xU;+53-{hirTCP; zycT~9khkJ|W99vL)CBni9up#8!V|*eJ9zyx`5BIxB`4s5;qniBXTF>!kniCvmb2ns zk#b(_u|h72udkHL;kZ?Db-ZVt+yLj>B)7tcx5ypwtF5vdez#NZkK68(eel8k@)$hk zh#Z20j?1&~x|8xEyy2|83ST)d$KtD(<=wc_4f!ZezA2x>gKx_>u+0Pck>NLnzZgzA z_W$u24d*mm&~Pckl?>N0+|+Pe!(9ybF+9ZZD8myBPcuB<@N&cJ4R6C;Kj?Efh;RRt zPyNZ$`~00ZuHYOQTj7K%%3W}t>ash|U0WWA7uA(V;Cc<@u{froJQ-Uylf&_emU1L+ z)mmPM*R+?n;?^$metgMQK7sRflP}|P?($vyt(W`)yL!kU@z#I-h3|VQPd}c|)?3bj zGYppt;!Pvv(zx&#xiW4sR<4KFOpse*i%_{EE;~hb!{0-MTB&Q4F z_g}|kE8OOkY=cLhk&EL(7vu^!@QPd$&%P=*GVEm7)o?GvgADr`9%p!p;W>sQ4M!W^ zVtAk7hD8<1J6Z zP9x=+IE|kif%gQ+QP^j^9D_rGKg6%Y<=43R0{Jr@ z8X^D2K9O>!VCIAsaxVNWN-l(**UF`F+l_K%?6*m-i@oFI=J?z{x5o>1EANJD?3erD zo(E+goGV@)gXsC|ARwPh|&e_fmGmW!}miaK;3=2VVC{_QaPy%ij3>H+c*$l`K!f ziNEDpIDe`Ue|vus&YM)oaW3v0Gia1^(?IJL9em-q}ox8jPd-stK<6NHd89aQD zd<`!iEI+^z-twzI_LUQHMnCyCJ~l?q7|QF8lXK&g!EzCt94c49CBo#IxY|s)5xyBN zJK?u;WLI2zf!qskkCX@Dpk=ZzE*vF~!>d-yQ*es)@|-{3BuC;>o8`6m^j3MR;R87B zUgan8+5_@sY;jb+i_0F9U*dA7beIswfvG3#qIO`|*B+m9#zKriA z$#-#`U-Apw=ePV3Pfh9jx8Hx_*JUwTR|R+%U6^q;|W#eaKn+fe;wt~IGckUhfnx%1`Sc;7-f9_Npg&tvbMKMM;PVIMDmdhzT+eWG!_J1g8y;YIxZyy9d>{ANwvB#dUwl zp+z<~)C%3|bGRZFZ#6S1Mb*z*Rz|PjPuiN-@$b;+%gOuxA1OU ziElf~dGMXqa#4J*y<8Tj?I>5n={w5~*uJamh^M*99q{s=au1x`NA|?o`^nzecc2`A zD-4w<;YP#cnfT`jIpU8;$x(P*fE;oDo}cKFtIxhqb! zOYVzP?~{l8$q&i?c+wGhA`U(-PsbZi$_w!Nv+@e;bWz@5c)Q_)hEEy3V)&ln7luC? z{%JVv%>Q3E8$NqSHRQu}AIZh=$7gbRobRPv1Lt`wH^dI_k zc=s=PIG*%d4#f9U`~B_rP&_W3JlpVMoZ3?PYMd&&yd6j6k`Lp=yz*HbUO>K%eQf22 zcyKZKHTEnef5tP*$iK0Dc{#%@u89@p9Jp&$xq#s^xJn)6Rk6K;+yFmoEVsm#&14rG z<0$vSY1_zy@TIo0FTUSV9*1vrmZ#v=UFA9Wmzx}k$M=$>aX>$L3-%o#@5PaWwOPMjnm>*2;l6aHAZGQ^m@&af+?-V*G1|yc!qZ zEyw=xet9=`Iw&8*YmdqoaKdr<7A|{QeuDFyliwNsW;k{D|6{Tk&TY7`VLQWB4c9l^ z!mzX99yrHs)#HI{-<5~qc@O2$c>iNL81H>9&%nE1%M0UU(maiJVkH1@t`rGd>ar+GNC+wd|{)O{pmDA0kkFv>DctI}N2G7ka7su}k z$QAJFf^to~yO7)n*D4`9;ajEUF8Eb>xewlMFAv5^m1Tb%P)(kQ?Q6@^@#OmQ0^G5I zyaI1-B5%Z*9OWIjax3`|uF_UMjc0X`ui}(0@_k&|Rep)>y2+pL^`7!CJfp9iZZ30_ zhirv+43zWZ`(AP>d}gRz2`})L>)`Z$a#P%PwA>CK7$B?XH@of1c4*ut#IA($Jv@IUJ|UC@;YlmU6V=Er$1D%iJ1s{Euzq zi+@~5zKv%WmY?F8#pU;SXG!@x-fkybEaI7R1=$kcsVL{cHLJ-*@P~gci{0uduZE-R z%MLiSq3nq5n#vupb91=|j%_7-;`VK2Z=A86JjQT{;aT{jtHvzCPVVw5T&|BCi!XY} zyK(tJ@-b{VM81Hl4U=!-+r#B2IM7dik7tgNzvGhOh-h_AUmUkIGihYkNKZl>i%Qx_rE(y`W=8onzHBLf#y_&jDI?jt<&-nw(YfVZxOjfK5Dv7J zOJm0(a%H@{gj^RdDkC?;9%bcrxN>>9D}G){?uYACmxto&wPk;tx~@DCw{(!FW1oid z0>dkD$(G7D;`y!Q9k@)Q9g~!xyo1ZrPP;IeWc#a#lPc zLC%YV66K0d6OJ^AKcdl^9?J~(;xJ_1hB(}&Y2jNg_ zc^ZD4Po9T2<(F6Beud>2e6YB@A73dWpTLzW$d_=Jit-(tTt$9{PgRo>@Pyj(ckEJ6 zPP2lwUjsQSc5W)?#n+q5Me(Rsayk5~wOsv=+sh6A*hOxMi+7eg;u76uH(b(P?vLB_ zmVL03ha8CAJ>|)`{9t(wZa74a#G8l9(YTYJyanI(m-k|;G4e4S6eM53X@likIL&1F z2`(2Vzr%Jj8?J1)uHj~e+Z*m?xF5dxK=lvBZy(D3f5tqQC*tuh z<>`3bTX`XNPLNk(mqd9Z?vNz!zyaUoL-=O0d>W@r8TfY|xQdf4c+P{@DumuvTt^SLc;W;IoBfdwiy-Tni@_mmA}crRCOmT^ZRG@2ep9 z!g;F5gK*iZvM+Y1C6B|Nb>u1dsDnJ`j~mO8_)SxJEw17y$NkCwc^}TvPWf>>xTAa# z&+8=L#x=UiPq9Z2IRVe_DSyX%`^gronM*xoOZ<3{oDVPZl8YHGj}Q4MuZgFPk{jYC z{<0Hp94NbBhalM6P*! z{Ai7Q8uwc#U&Xy+kuJs{`A>5s?-@s*=;DLnFo zT*+`9!%YphHQdE;AH#zU`xy>0Jk{_#!^;h?H@wa80mCN^Up9Q#@N>f-4FAA8ZtA_K ziRNC=Z8<9*e_zgv(>#)kVvA>TIh^{HTpioJksII%335xk{-fLxulpjq;g;X!{`mY) z*~jo0+$i15CS=p4W?3EqaviHu&rjV6>uRNXe`}Ei2yw0b4-}n3N{kfkzPOoh6 zLAi7;94SxBi!aF;3gFvv#e(>$Jg+EzC(kL4zshS%;3RopS!}ggu7GXiN0o4X`9U@8 zknEbcyxgr0t|6y(#x8Oh7u+)0O>hUfT{GNMZr>6Ql<&31Bjxe!@Fe+u2Ru7@Oc%UZ zw&;e}$SJ+>7I|uKyhona4f75-xQk6b7l zxz#q+oE>L3TtGgMo4mL@xB#voe<_G-%3q7(hRJzx+)8d)26vK2I^te(!Af|LeCMA> z$&H=J1LUOIc)n~?7q5^9{qsiIsUi7JIdyX!AzQY>r{z>`I9e{<9^aJ%I^q~PtTTQu zx9)}$v9b2-Ns{6Vhu4S$#G{lpgG>b2iEqntD4#1zRtIprg%a6!3VT3k|onI2b?qcY*z z^7*W|u{<~jZXThx0c4sEjX84ZaXd{&)tbj$qV-4%JRYexQ=`{0ymY99m8$q>&I~y`PWI@$M6ut zV+>CyBPn}=np11HHxyoIfZkL{;{c|??$Yb*S za{lMo!Ekx`Tr7DF`QAJ1B5#hvE#)#_aR>SOcidC{^%D=2|NOxt<&>6_{>}*#<*BLh zEIGgmFOtJD;MMZZ%y_e0C@bDAKgfZP$QNw!8F_17d{s_Y5Z{;m3gH)WbqD-Wb}f#7 z$Tdr0%iX$0D33GAw=3XW@`9?kki4h{E+wa~g)7TF>*2a`FBjZYe%%PW$#0usPdTYM z_LhCyU|%_)E%uj7x#MZ_au2*fZr24bm(TXVp|X7+94@=|#Rugt18}6AZxFsDNBZL1 za^aEqsk~tnek*Sri@(Z4$KxdV@?>naN6+%6V;i~6Oq^eKn~NP}|M|Fr?63&elxr-; z4doWgaVvStYTQw7z8-tYS3Ke$Bwe&U0hvuzmJ{egh$v_ zwtI@*VY4I7^BLluFPsoJt%OkSl7xGUV{86r%3;&Q?*<#Cm|Jz#j$WLx7XDWsZ%ax1c z(sKFIxQgsj2G=#*RNhpD+)chx4SUKyHLc|&>S4BS%gI}3M^)6T;^11#9w~oc zj3>(JR^VCkrqy_nTzVZ|Eq4jQo8@9#@NT)qHhe_>6pqix!*=1T@}PbAzMSO{ej{%> zg1^WiC-5J6?P;9ufIf$_IGeoa9L^^%yNrv;PSh*dxjkYZk%Y za{pr3R}L(W{pAIvae(}`9G)-luYiN)q{=u{-sgnFWT#sApuD6Wj+Cpr;7jt6M);0= zv>ASGI8JtML;go@&>p8dr1u6p1IFYJvg$cMafO*vu!ZYWRl!L8(B zLvTm=#R%*r_Z@|O4%d~7e#A{>pE&F$Z~2P5 z%G-WmZ@En(_LU1HVSjmy<9(mpK}1tDu0}g z^U6);V0(GUJnSg@24bgVFToAuZ_98?IbkL4Aop2~d&;9j@IZOYChRA#--0K}jl=M4 zIdm6ZESK1e*U2Xi;H~oOL->%K^#nd8?>>dE8oqD%h2f8ee;Q78?Emdp8@4rE*l=mX zRpp9TsG*+R=^Ad9>|3~<{P+&;DnELF`z7a3@G!Y&3?471d4*@lWnbe!xy*aKQjYnI zH_92l;9YW`e?Baq`c57t&;Nt3$nz`${`UBNd4DSWLf)GWf0R3C!aw9EnX%<@t$S^- zwH%in+sd1B<07(U0bE9ow!_urM@4ac`9X2qT;5a?x0h2p;%;)8^0=Q|x-uRn&!~>a z%R6h}newhWI8eS<53iCZy5P<7(@xt{$yW#C5^}qtxT4%?B(5c=_s5Oo3gd8V!=2;-<4Z9ikH0*8I*Ra3g z0NE;<8WzZ-uHaSj&41n`C*C99C7*kM4=4Kxj*^SKz*pssukd~O!yEiU_I-~($`?N4 zAM&}cI8~(H3r)b*@`qp8R?hhc7nTQGO#9o{rDdNqxQe_u9j+@c%!r%Hhpe%i?3xvO z%ExkIZ`nCF_LUpu$NuslI~*W86vXr8E`@QhyrKjSkzba^VRAo5d_eZ8h@<4oRq++M zjT62n@2`WO%LkqD2YIRs{w}|0f-O$zTE02XDF14KbIMiQ;KK5v_PDG(sRMSBdvwMw za(GYNMvnBtp7MfzxSxD!ARZyN9*if-Wk%q+a{VzlSY9(8Z;*>l!n@?j0r;@|bS93H zx6j5`~SAkMd>{C5Zf5eFUP(hcaXEh;_`BicesYU>;ra@>&M}i za+7bkgFNIr_L7JH#y;|kMC>Q8wV3|5uP4cA(&5?iH7mSCcC^N8<=a{DR=HDlyjS+L z#mD4ldGI;;RRMfMep47fl=l_IujK3{aGYGT6#gwQcf{$==(%%6oI~zc85fivI^nYN zvO2h${KXkN%YF@U3prm?>>>NNz&+%UR@g`G)(-p0)7|l8c~&PpNB-3rFOfTS$7|(- zz3?`G;dMGTiQT-9(r!_5r0Gu+j1U&BKUk25^o@Iu2Y3~!K&J>j@^$aP-e zLvo*2_>{cxJ-#dlea3g?!|^yqKAM2v%O`%}1o?F$PI+GEWs4bq=Z6gPpj0@AoGTr+ zlVhxK33;tGt|+h1hHJ}%vg5{b@!YtL+$t~boIKtR_mM4%;=%Hve;zHDDM>!X@Laip zBl%LfLnRy{@2iHxWv3eWki4`GJ|)+7#?kUg7kpQ?Yl@%Cjhf>Ra?vm-f&0ld{qQik z)EGR@@C?HX<;ww#Ss@2c#~b7nbMY>@`$BwJE)#^KZ0cJ?KqoUcn8iePuzn`%1aL7O7gNJxVC)a7;Y?|io|W?`KNJb`OF#I z+wfq+qYY0nJlF6t!|M%iH@shNbe(;jkk8%07vvHT@lARAWBgcd6NBH#6<*?R^20Yc z#U-sFKjQRq_s=+oeB>)GAb0(Ni_6n~;mUGA60RfnwwU?1f1Ao)X|S7oEIsy=UuDGJ z@|!H!SMHb%`^!0U;Q-k;FJ2%&%ZHcC!G&{PR!weIR-2Xnp>{IJ4Y*1YQmn&_>&T^G->?(Wi#O`vyZroj-v>y+UA4K30^1Wktf^2aT&yu%A;YIT1^LUM1 z<`UkT?5lXM-0nI)Y51byTZW$)eq;EH;Xj70uKd6KoQ4a^%kHz^QgTo%t|E7PgX_w} zKjNlxo_OpgulkBT4R(QFbBO?x#hh)Lw za)b>&C@;^6Bjpu&@Fn?FK73mqQV2hjrxwQVAE!0vMQHP}ne8;X5o#|_v|p0Nc_lKXDQ zv*ms}@#5rsFJ2?R-;cM*A0zNyIq(=hDMz2g7n2=@ZySDU_?_JPDr3IM`LE-Y*R@`{ zjjiQ553sFV@d>s!>}a^UVQ0gxhTRSKFg(EU2*VQ$&y;t+rG_B+;|IJ-4vNE@lk;zQ zx18$-J|gE##AoE-Bz#rAo^tlzUcN7fq{T1fi&prfJTw#jAtz+UmN&GXw87SLN?U9z zPtAi1%hLUf;Ium+wk zf2xBQ%JI&4g?!8fZ;($k!8_#F&2WSq+6teR+qA>c@@RK_SN89OW8|@2@q0P6J5G?B z_rex8bwA%5XOxHc$2sMz|6EZ1J%qfZ++_r=B$x2RwdLvlxQRS#0&XKaPsE+&{Qte z-@Sp`$#?GHu5#!5xSzcLF&-uldVua+%7;V{F844*Q5&F}-m zFAaY({L^si+d9|$Vqcl%7Ku2woZ4c}-(D^%mq~@o%DK|wYI3P`xW4=?6K*cI%7)v^ zt~qfxxnOSGPxi}?hskT~@HqKpVLaXNLc=R$&k~H;AWwJ1I}9H(d`eE~#F%Sx_B!~H zJkS}(%8OiZoE+E$|CVz#$7$~9y00b9BJXdD^T?0e;i7W&j@VIl?S!k#5#6wh+{FvG zk*D^?o`${UW`oInWy>MhUyk<0)8sv)@B(?l7`$AbKLLlzfm3m~95D?alK0QTr(~Pi z__ADN0lp)54Z_dl6ie|txxsS$&2Wmlnxoc`r^Z(E-+GB3$$oEetbFYQj+g!8aiaY03r>4a=gO}*t32Qr z&MPM*Vtd1mhN~NPHr&Fnhv6QE2N)hf9HWkaw!|UMxK`oZ!x^b@Ns!z zQO2B?EsEhAa*k5?k$j*mj+LL3!*Q}hCHz~SSPiGSuX(8k&XVjpIFFpWF1DASyI@E8 zNfYcOr)!QI$h%tM7IK&y_K+*M;~sLkPI#dFyE7gsyLZQv1mHON_;mbR&N~OEeW3IBT%1*I5Qy{2 z&llrjviCCVD0{8MPI9-kxT$Qv5xdEoH)Bt^>2~Zb`-bD8@}=F_U!J-L2gp|Y@dCNt zQM_DkcMONhJ0o$p+~f>CD1SJQBju*i_>!FSD!wfby@{X7%Wvbi^3;3ytGx6vPLhv5 z#pxevo_UG0%eHTD0r~k`TwD(Lh%3l#KI5A5w=cM%eC#J~EzkOmJIU9Qa4-3Js(F9= zXo&2c7LSp?S>dUM7aCq+c!S{`h7TD&Z8+NSUBfZ*h#c(qz5Fv5PLLDw;*^hcf4Bh7 zAm=NLbI7qpa3R^z0hg8C%3vpXXL;OEUQh|Qk>6Fro#i<-ac?ml|F#w`@xuCU11dhvaD;@hN$dC%!C??Sb#eDSP2(a(!?7PLAq_zsVr^;No)9I9x&QG#=NIO9tRZ^5mJgwY+sU?j(PlhkMD5 zg79GZ!eTsHwqK5?$gV5#T)FXDyi}eSg4fG~HsUb(%vO9rJ{^uv%1w6ROY)n&__pkG z06&xaAI9(HlgDv_+%OVbJkj6VX>2XGKZ|YUe3x-y+4dSPE$_dHo#gmCxS_n^A#N=< zc#1p8XJc@0*)A6Q$|K(4aq{rbc&5BE9tX*;-|;#*_fNb{o}7gD%VRC)|Lx!7^02h{ zf?PTszG?WG;dh1;45xhh|LJkA04 zl5dp4gJd5^JW7r$kEh77mGK;TPgT4`wyKHO%4zE2t#aA=c(0tx1s{{!Hpb`VcCPq_ z+`2V>B#&x~W95G-r0lS>=;Gab7vUH@27a4Z!8(20pmDVQ1NU z7`dz5W+Zku++BV>j=aA-YZ4wV@1BAu$eCy0nR2E%I7qHM53iON2I4Jp(;&Q8_6^3z zWS>>|ocw4tzAgua;D>VaQ2a_hvIT#ZkA~r2^2;4Kb&QUEFU~CQ*@tt>hazy1WFNz2 z<$x2onp`&u*O%*^$FB0}i`ZS>6^*;gRj%Rw@~2yPxEyy6kC*d2#4}~DCpb`^{S2>^ zV_)Je@~^jekKF$~J}OU$!{_8;-|%&L%Xj=x{_+dImV2gL@V9^CxtUISm1U2EY7vSoezQZCg1f09cy#((4|&2hRH`tDldY;upb zxPW}j9ha0>cf^(CwVt@PysigsET8wnZRHEzxU(GJ5BHWA``{sR%b|FTJaRamDvub2 z=gGsz;$`y6@i!CmBm$8jII$Z6~= ze~iNZa_9v-P403LFOp-f;nm5$g*VF??&3Xi*aLi2?)?;>mFLFbYjVdI_<=n8Eq*EQ zd5=HKS>y08`S}-|`jwvXeaD%T{Tt_&t&(sNIiuymzx`WAu9O;AmG7j(_2mVbu&bOS z3+|BY?AS{lVvBv`r@8TH!&3~;HN4dDI>Xxx?>BtH@CCy+J9t{G%&gDA(_aSIE}A@CNx*U%Xc?;IiiJ~5X(zx;YWE-9~Fge%GGmf<>bu@$(fJZTMfOLhqEDsS0<`^j;e z@d&v`IG!lK+==JPGxp-8a>EF`PR@1&Z<7a}!26PY8lR9KM&S#FZ_3>-kw2CXU&XKG z+_!MNT<;D}lW%guUd;wXu)< ztu7uVw{gLfWw$1Hj$E)AULucciPy>&ZSb~ax5xYB&<^;xT%t2RpX_ey*?uf`l%pr&>T-zy>?|*vhFi$4 zv$2Ofd@k-G_gsJn%BzF0pX{*=2gn^(;`ws6bvRgd3c(@rl1(^FPP+vklwWPbk@B%! z_)>Dd2j7-s58$VAmI(Y-9(W9YmHS8HBsuUjPXAu(|8v+zu67CMmk&o{2l>c#TwZ>0 z6W5eq-Ng;%*oU~4;f`{@=j2}U!k5@bJ{61o51 zBDk3R+a8xQ>}0rs;TDEH4EHcR!0-se6AaHZ9AtQv;Z25j89r<{%J5a$zdXlsKRK_7 zU&ux4;E!^LdiaN7%a2+cHzv;{J2b<#^7WRuknGnMmoi*gp5sAYNB+|VH<3H_z-{Hp zUbsuLy|K3(-xm*&!+h`<`PN`ORW3LT&y(K`$H8*aXdII4aX3s)IT;_6r%uI@a>*I^ zlAL}vzAcB(!%yXmLHL6_e=+_pe-6fJK56`FoK4QK2IrIOZN$aohFftt*=IX;l6`k# z7dd!0ZYi(bk2}a4Be0iT>L~V+E1blm&-sG0%G(ogUb*~F zY%d4?!H%+Jiba3tf$DPaRM=U5lLouWAJb!ZxpijTL;jHs_m_+3#KYyXdGL6-eLg%x z?pP29%jfKIhrKlmloU1B!FkD`? zt4Ur%{#g&Z$b}o=mU7X?xP#ohDefu9x#EHHwN`kfeBBLCl5ct7xpKpfI9RsnhBwHA zz3>h>Z(kfCJNL(@<&}eQwA^C-4=yLKMDd_=W6qiTtyC{-1vtw)&#uy2}_FIpG1$ zZ`eVu@SME7Trn2ckUPD>O=O#oxNWlIaTmG9SKLQl@&gZ%d;Y>>;KMVIG162!;Xfl8+JDAYS_bY55oiG*_EhagnYIto*5}J@U}z_^9mL3ZIp~wZYfqi*ERVoUa3ZDUaxaKg+|q<6rWMo;dY4otygL%yRF( zIJbOqATA=G7=p{nF2is&`PE2VKiOk&bJ=|?_K?qv!(Q@)$=FBUG6Va`E#~0Ka*w%q zj$9@PFOe@T!E5E;!Fa2@W)0 zp5U=^hi7=2yyGQaAcw!f%jMheaHxFi6AqXE#NmUoM*@zN&wj_3;jgl#6;6_Ut+Ca2z0Z~v+sI3^kMx*ywC7)!{_C=3ege|?d@=N`GE&^mYa9PE#y#7>>)SofqNJp zAV+zVkCev@!~ybLU%WuhHXJXP`;EdIWUH}whdgIIJ}f_-jHBcS)9@9!+H`zRemfgK zmnYB1ALVgD_=oJb6kGn(Iw2Tml2@$4x#Ux8a3MKgC@wAAZpKxU$8W{;>&@`hkMFChwwnT&rv*DetR4T$RSa9zP$WA4wfS?;t=`B6&xn-zkv_Rk8j~9dEtG0 zO}2Q5AIj&R;aBp>m-w?>Ar}9ZU%bOp~|?n{Hq#nEN6DY zZDhYXxU+o88TXdIy5Pa`f+l#hJlz#fmAzZxd2)9*yiA_a9fOsRIH%!)a{LtXl5*Z@xRN|* z7OpKXnS&e4a~9yX@{~omi@bC(?jt8H$G)<|D(o+xT#Ezb3hVKF`O*d)ELYivLuAh| z945Q(!UyCn`*5Uu?EtdNek<2GgTKms&fz54@)EZCqkUb)+2#J% zZ~@uxHZCr&xr-~vOCREz@|&l)p`7hGZY5`o#hqmDfA*5Ey(jmPUw*)T^7k)zlKlBQ zo-OD8g%``&lJFYC+vPc_m;Idw_RG(#@Ci9A1HK?P%ZzWz9@+5|xoA%OM$VT9e>I$B zIDOLpW3n5zGhD)OCBwB1H#XeHaA(84fN^<(#eXQ`y=Lzm@N`!(ZjA9dL>i7Abai#_8ov z-Eek!ofj@3pYM&!$~*evYI2#uxW3%Z7dMw(N8tAIn$ftMeAXZLlZ%eU!{kll@i=*6 z0G=-2oQW68iL>!a`RjbVQT`BwcNvb5t(TLZmaDA9(Q?_f_^#Z3J&uvLZp0r9|B&6c zkz1y;NO5r&&Lp4Ohx5oG2XRq(~BkvbK&mJg-Fwz9o7E-Y`(f=kPx*>M$lNKRZ=u4Rjx%31SZH^V&) z4=_B!@C3s%4F?%sWq6akz@B~Wl8+b1hvlQCag%n-b++rBsAg3RVcgPj|@gdo90zM^|o`NsSZUOj?+o6yh8TBfH%mEFX0_>!>jm^eEvE< zC7->GFUu3|;5+i-hxnNs_s{R;sORJfhEt}tNKxcHc?LP~1I{5gi^q0yuCKU+JoE>y zEMG~)b>tOExT(C-a{1rBc9Ywu!=CcE^thjV-x?2-Ewkcra;hA7y4*E4UMQE!i&q%l zV0fqD2*alhM;pFt__^Wth7$~@O!I#Y8RQ!F)RRMwD2MIjIu&t=WLL$N zoL%m47Z;E{9^w*m(Z{%=TrdXLmi=Dg#&Uz#xV;?y0r!y8#bX~ibprO2U;Mz67@lc3NcMN4 zo>lUQ+IW+EzCPY1$2Gu*<#&y7l$^a8zA9&GiSNsmTjLjU*>?D&?9c)KkVkjHmg%+j z?us+X(|X`sa<~^RB=_luOUd1RaAkSMU|dI@G7LA7(~ZP!ki- za7WqUD)y3FUdKN2$J=~LqfgFWsew=IEv<=dsOzkIYT4lq35aIoPJ!(oOG7(QwE zqTySHpBR2)_=}vg8uk2<7dzv0nN+6>&L($mg7e9lTi{~y{g$}A+_ep^A$MwzUF6jr za7%f7XWT)K?23EJ*S+vS`Bg7GQcmcHC(1Q^@GN=BKQEGV4JThM*BOa7%a2Fn-SWM0 z_=xN|5ucSkrs8XI*bMwYzBLQKl;6z8pXBrN@J~5z5l&@oks{AhY@O_tIJf+A6)qw_ zUWd!bg*M=-a+l4xp6tFIHq#;MMZSf_RJkz9`-+4{^Z9l$uq*v+t~VQ<5}hW!l(7+xSZ zZbc2tlk-kE)Nr`msweqD`M4L3l=Jq*m*iRf@NIeJApBHbF%-X*PYuUk|MiOb73XW<(1%=y?wo*IN(%G(#?4s!Eg+*4k^3j4?o zYq6hvCInBCn{C9i<;Gj_V!2^BUL*VL#9QRdd+}bw$K;9;@0tLg`hkwbhir~~Xx-VB8XO@@!a~?TWS@L3Xwu-o%>{J;$ z$+xQE26F0}xP|0 zzG3*0;aJ0Qh7%2^&93!!Cu++o$9BPa<+?qvz5J*bc9eT~N{~BdEQ=JR4#iEJIdCFv6I~E zIBp<&p298U%crr2+~zFqDQ~)nePov_c$DmR6Hk`?Z{s=g*1LF#Jp3_UE5CSxx5`d0 z@LsvcD|}M6d515`7ykLS;ivMnZ;W}H>|gk+9G-}i45!QW|L z;qr!S7;b9VO@7{#dOT&X_SjpV?SXyeI$f~8T(di#CU5J37s%y$;pKAazBp8VG7#^Q z9}K}q<<}$dSvl({d`;frj~~jF#^YFd#$+5XKbeLT<#aP~T3ZYKpJAL;?)=Yr8;Wn~uDDEQLY{q?L@9o&v@K|}$Zt`jJ=L2|wy!jwrF8dzC zp>psEyhDyVjStBm&fzFI=S6%)&VB{olLz0x&*i1J@JIRcJ^WM7{Sc?ht?fL;)^e5? z*j5gDg$v6I-{P|JhIhD{Y!ip;%hum;bNOBZZZB8-jl0R6{@{MHhsD|y$v?wnw={UX z?4J(Llp{0XAh}#tyju3K!C~^AT=;-|Dj$xLix$RL<>p24BiXYAj!kwM947}j;@|R< zia1RkoxiH$Eb^A>IInD38{5mJ>f&;;Ljzphu#3Eng+*Zyq8+Vbb&BcA>g$wZz*&+y!k@qjfQ)Q18c%J-V z6%LkbtjD2p+E5%W_u7mP$;Y?jQ*vxLzAVq$jqk{r_u*%9)~j<+$WF&`%6z&H z5Q#I$0cUUyx%YWoShkDCrRBF*a22`I4O~|axr>|12kv1vx%d<8DPMh#`^rCFVqe4l za-sL+(`38Pc(Hu^3Or?>L%oCQ`QTN&PL8;V!{nIT_<-S)^2#UV7v-H#@h#c= zC4M5mi^Xr`*YEJxWPidI1uaqxjK>+}a|t-7Z2ub;LwCCAq65u5Gxf zJSRQ5n_M6h_LSGzU~hSCF6=9Ju*LrJ!2CEsb}fkKC%Y&PmOne-5IJ{A93~Ghix0>v z%i)vq>Pq;cytW#?C7*M`Pi3Fl_^sTc9{wiBHNYtfX?|#kGs-uc;XLyER=BAA-VK+P zbGYMbhMf(!HtcEG+wgG1;|@oOA9hSwVoGkn1CNy8Tn-!lBf@EgNl4F8emb)+6EdtFm>!8US4H=JLt(-S+$ zuX^M1@@{WjL(V)9yT}8F;8ybIp}33FgH zXEt6dPnw6f$|VEwUin)PJ|^#8hR@0SR^scj(;ECpp1K~tlC3u2&$9Iv{723jhSL?( z+_(d0ljHZ`d~(}^xR`7gfy>Ebk6|Y{^aO4oZ#j)y%Hij52YJi|+*7_2jR(s2uH%ui z=Pf)@PIC{>lCRyzi{zJ2@M?M2GrU>e{}S((yS%|iS9kCk0o;W+tyTl`yY;(^l?*YS45Sq$efT-0z`!_^GeH{9H?yW#GJ z`x_o^c)Z~mh64?+G`!L9PQwv~Ps@eR52Y5Yju zb{5CVu@`Whyf_*s%FD0gG$nO@zlpQR1@GZJa^nZMsNCcUE-P<)j;qOjFR`>a;nd`yKMCp_m|5j;Nf!MFFaljO2RYc!znlXoi_sI)T!}G!yDyy8OV3awX@&| z`D8YHT0W5zN6W8m@jZENJ{%)2Dv009xr^Wg+0Fr{ET#J@#c>9?Ng13&9^#1YUVhmH|CX!vz-dZr{osYOB-H6E-Q~5f~(1y zhht|s+bHZRPa2Kg<*DOvce&5jGiOx#~I|~hj0!# z@+h{GD;~!s2^l-g*o7l1JXbgXHx0@hJK36FgZ? z8H4A@A79|5a@SXQtz7y&-YUC&#CzrT@%WhRo`BEEXTIa>^20>@NS>N<l@(el1ZI6yvF4bPLOI^keBwhj)J-#FuNd0hj1&~T*TONMV7erouw;jf01 z3|l$=zb_lZ`3*Z5E^oMo+@c9}y2zK^a7+1Hd)z^G>x6sCox0+IvO{<5Cr|B#C&}CU z;MsCmf4o?}H4v|n9}K};hL#Ai5Fd0lh8#MbhQH`rEg_YN19Gk?aV<XD#RNlWBk25@7KD3H_p2tSuk9L68ylgIIQxnU%>sHFA48JtOOb^+VU(U))$ zx%4$$My`7uSChZp#`Wb^4{&q&_(R-YzWNMzlYL*}e)6|iJWNh_hsVp2AMgyhXgm&- zizncf^0ps%qr5c{@0716;RyMv<>tS=e_Fnh7Dvn9t?)g$tu=lw+hxHY<+0iE54oT% zPE}d=9`oYN$+p9}^CyzaWx5?*D;eGOoGx)f?=OVr!@4bR=$`h~QCvwf(_>Js!7k`m^Kg56Jeot|_ zYC0FhU>iB;70xf)zQGR3{(#HN`Qva6`E@*YkryQ3ma^+_+(91x2Ybo4Ew=ofPkiL{ zsj#1%!U|84Ei&PG^0Ul%nf%fQua{rv!rSFUTYONyPynBn9qjNG!}kooF#O5zZ^KsA z|KCmy!-Wi&HeAJUU3p_kYG^7~D39Ib%9XLFe6T9^mY-I~zVh>0c&z-Y9uAOay5RY; zbz>YXS80kvlHCG_%Ykk1LAhFc94R06z*ppbPpUWm+6h;(3Q}sA}7#R{WD;f|biWDM> zh!7D)iZVr+LS`}~3K_~2WhOHrRAz-lAyG&aG8D=XD#N>f-~Fz2p8MCc&bn*ey*~Hs zea~=D{oqrBqMHP#8Xny`xX8QFU4!o(9o;v0(75Qq!HYhK9u-_~QuM^&y;GuR1^1p2 zy*RkkN6{;TUz``cF}U%^(K~|QUL3tIc*wHoBmd{mqfZClxGMTm@Y1!>smg_8w)N2& zgUf7+&J~<`b9BDorr$&t34UoubjjeMJEO}7kN6?FdhmPuqMr`_e1G%{!8iRH{c`Zz zhoU2UD9ej8C=wE_MWr{u#{6gmFbHQ!1M_&mZoijS!!{J;bcXZa^`L{*i5?nlA z^qs*K3P#@-oZ+tMhk~;giGD2j_F~ab2LJH?{VZ;Z+u$y^A0C27<4JfnUV>Kz*Do8# zvnjY?#poTu2Oo?6DfsuQ(MN*M*N8qH{8g>!OTpjPjZXDQIA(q}I%Dv)2GO~KTf7jR zKX_Q<=pw=8nn#xmUfUwNd~mx~(ba-?w~MYDe5HMKqu?7lN4E^Vse5$C;0isXdj)^g zCwgG;xBa3=1phc7dVKJqLD4gUZ+ItqL2#}S(VqsFe=mA{@DpRAw+1&DAH6$x|A)~B zgO5*+J`tQ{TJ*W#)gMJ)3BGe~bh`3kU78=AHMqf|=v#vOEs4G}c<}P*;=!X&7JZ@j~ zq~I$DqGt!sITXDlxae=utAh6)kKPnq?o{-S;O2iu?+eawF8WAtuk+ETgYUW&eJS{# zE78|g2}n*$+g26kPYg=#PUJ z{(patzr^3-AMvmF5BxX2hSNWqd{z#8TX3;TaXf{BC)JL=KX~TT(dB}-)r+nYeE;*& zwS%uTjD9Y7)Qi#0gEPJq-7fgumeJjU$F+`rBlxAZ(Zhq=c8DGqT)0d0wBQBZqUQ%M z>lM8`xN+a;b-{<ph;MIeo4+Q5Q7JVYP@O#ncg6oWmz7qWG`_btthG%xh zM`sOwYhv^*!N;dY-x<7gdh~t4H_whP8~o_p=*q!W7Dm?!uDK+-LGY?iqMHT(_*rz@ z;A<1%$zqB=ac5u7x(My8Id>6ecc=GP(O~G^a zMt>Jvbbs`|;Qa@qj|BgAIQn$(KS!c31%G}bI#s1`jpAf<#^A^Pip~{0<9u|!;BFVA ziv;)mFS=y#tSiywgBPY;@V~iSE%>uE(RG7=Nf+HH_(X>2mcdzXjP4kGYqscK!Efe@ z9vD3D=I9Z@OK*)HAG|hS^z`6kcSJ7;K66*}XZVZYzD48qZ-Q&w7yU!Zt&h0qn8FBXcoODcyP<;uY)tSivB*hW4q{|gU7dzJ{CN! zQ}mhO+TEi63;w=GbehWHKV7|}vjmUo6P+ix#enF7!OPx`E*3myNOYOt3B#i+1y3It zT{F1QnCNGNcZ`c}5`5`{=+?p0CPjA+PCY%kPw>4TMGp#oU{3VN;N|n8Cj`$~7(Fw1 z!za;;f=@1sUJ*QbMf8T?uU18G3tqK0dQb4BFQN|xzwlM`$>5e-qb~*z|28^hm2j{5 zyXXwTlXpkw4F2lJ=)A$(e~K;~{Pcn762T1*MVAk5b~L(L@Xlk=b%RHqjBXUX;&gP& z;JoLeI|OgJ5ZyDl)<4k$f*V|k9v)oqTJ*T!!q+YQ-`t-TTs&R${NSbOqn8I?mnnK( z@VczgTY`^gkKP^p*GV@9Xa9tieqSN8b`$ z`o8EpgFh@0eP8gGrJ^4S-uh5~lfEqm~<4dXa(3!eB&bfMsxZKLlG z-u7yAx!^soMOO(<(IvWeaLXRi&j;VsC;Fw}3jLyA4Sr%kbob!b-iq!Y+;d3u(BOl^ zqsIo%dpCMYaK)!PO^6e;wR$YV`NPr6SNJZvN$|_xN4E}M@k4ay;9fsP_X(cJu$e!(db#h8UBb~ z9GvCP=+(ia&qRL}{Ndlx-vwX&C;F%0G*_d43oe@CYlgJtVmIgVCdde=Qq5DLDNj(X)fIRE%B{oTp0k>fob~M}HMO zw?_1L!8@Of{wa80o#@|!57mqQGk95p=zoIOHi}ODL^ywJ8hvB%lg*=V4zBldbb;XB zt)hztA8Hp}I`~w_=t{vkJ4e?D&f7h@Uhp41q8kUde?7WQaQ*(#U4r`zi0&I)VQ}=| z;OfJoM+J8r5j`>Z^- zJ-Gfi(N71j+!6gk@Y_41TLoADF}hRmGe1T534ZqnmpuHPW~O7O}?(dnKH`$^O2tie71zi+{J z;o`U~u8eEp2Dlk+i@V}}_#He3PsVfbCwMjf3V(-x!oT6a@V_{9t)$P5_-1?uz861; zAH`4LXK-WO3U|W2@!R-4{2~4be~drJU*c_e4?cuX;tM!M?WENWI0wER-;GP)M{reK z2RFnmaC_VXzln$8_wiIb4==-O@z?l!{4+j=&*1-Xnx~R(nQ?Ah5EsK`a3x$5*T+q8 zYup+4!GrNAJQ2^ri}6al5pTzP@nL)lU&JZvB&{;woH#Eoj7#80a8+CfH^eP)d)x!R ziHG6$@l-qyFT-o`*Z6zrCC75Bx1@hChI&%%rGO1u$o z$9wS+d>UWEsp=)IGU8k~A1;DR;_|o}u8Uv5FXN857aoX5;PH4mUVuNv>+x2+8z00c z@Hu=1r>mcI%ZhKocjEhSSzH;{!VPdU+!lAm{qPVx8c)V^@F#dR{tADGf5N}vKk+~K zx@VJCnea_GKfVW-!WD3J{4{<6zl=NLUU(pW7k_|f;Dz`z{0067|A2qNzvJ`x8cyFJ z>6RVeh6~~QaXDNC*T&D`=C~d1j{D=Gcr2cR=i;S!4c?4*;{Es-K7;?mX`V}3WyZO2 z0bCT9#uaf5Tn{(Ft#N1E2M@v{@dP{*FTyME2D}aL!H4ikd;zC;K52CW&Vg^ocjE`} z!}xLh6n-ARgkQzoaeq7%kHu5)T)Y&o!C&L=@z3}eK7;?mX&NToGUMF104|El;7YhA zu8*7G*0?k7g9qV}cmke@7vU9n1Kx)B;6wN%zJOCSN?K*WIdNWG7?;40;HtO|Zirjp z_P7Ur6A#DZ@H9LhFURZf7Q71|z{l}fd>N;EA?cPC--7SN_u+@|WB5t@EN+V1;I6nI z9)d^XNq9D1f>+^9cn98xf5U&`fADoLCap5zn{a-74}K6oil4yG;1}^L_%-}Geha^g zKfp8a$M|#nCH@xwh=0X@;J@)ToW60=Ejzv)-;E!@597!2Q}}uO5`GnT$8X}Hcr2cR z=i;S!4c?4*;{Et2{tN$$(=CSE?gX!#g%a_+yFPjZE;uJ z55I%Q;K_In{sgbaU*YfYPxv?dC;kUt*CuI|3EzbC<9l!^Tme_d&)^sFEBH11I(`ek zi$B0K@Iw3<{sMo4f5gAyKk(o98cyFf>6RVeh6~~QaXDNC*T&D|m+-5&JMNE%;<0!N zo{N{_HFz`r9{-Gw;WPL@oTgpUDl^WF3*e%-G_Hti;Ci?*ZiPGH-uP|&9{v!2gg?fg z;|+Kl-h&U}llTHo@oLiQ2Al)mj_<|~;74#(Tn9JAEpU6>1HXxf;rH=WJP$9&>+lx5 z3m?G8@mYKsr){5f%YyUZg7`jM23Nv0aedqbx5k}uA3O+;#1rr=ycn;<8}W9$7azu_ z@I{=mL((b(&WZEkBDf?jkE`LjxDjrNJK&yp03MFV@Gtmxd>&uJ>ANJ|vg6xuA$&hBhpXV) z_&MAhx5M3We>@bA#Z&NHycDm&oAFM(A0NYK@P9Z>*Q8ZuoEsOwMR93d5!b-=aAVvW zcgB72AUqOJz%%h8yaI2)+wfj|7@xuyamsE*Y!wRWx_Y%{P-SR3Rl2S;AilQ_!aybejUGs-^Cx`8F(T7 z41bBg#XsU-@gMkad=01XnRLsJZ^MP~{kR;if@|aFaC6)acf)VsckmcI8PCN_@fy4t z@5KA@QT!MF7pLx(w7L=J#szRuTpCxzHE=!L7`MWmaBuuJ9*HO5nRpRifj8i7cn>~= zPvQ$W#p_9{3^*swiwolt_z_$c*TD^O3)~*}z;EJV_8{ ztK+Bfi})4%8h#zWh2O;=;E(Xf_;dUv{ucj;f5m^`3pm9aNvj)h4tzVl8$W;_#*gEt z@bkC@ZjXE5H}Nq1KAwu_;bnL&{u+Oe58&hYEWV7>_D{NH!Fg~&Tnv}Nm2gd5A2-3R zacA5I55gny1UwTj!Yl9wybbTchw&+V5vP1JX_W!z#CdUHTmnCWtKvGi5pIb);GTE@ z9*)Q1X?Q+fj@RKWco#l^kK?oWGEO@n>6QiO!3A+KTn1OdHF1611h>Xra9=zakHQo2 zEW8-6#2fK;ycZwFr|>15YGBeTBhH2M;Uc&sE|06>y0{T;i96t)cpx5u$K&aE0sa)P z$6N7kd=Q_&=kOJr?yaO-Hhe3-3m3;_ab;W!H^9wsTig}Df#1Pn@MJs(e}Y%zukd&H zC;S`!6aRx#zn!$Y5#NmO!1v+@@uT<&{0x2(x5AxpZ~QiX4}XY1!XM)mcmv*s_uxbL zB)))C3`$zvfOFv6aba8nKZ2{`I=CTjf!pIAcmN)b$Kh#sK3f<1?Ry9aWPy5SHd-MecS}M#+`9rJQ$C{6Y(s(7_Y<|@pilyAI7KfMVxX-(kcVa ziSy#ZxCDL#SH*R3L)-$l$35_yco=>kPsQ`_GQ1Xljd$S#_&7d`FXOcDB;B&$Jh&h( zhRfi`@RRsi+!VLLU2tDK7>~je@hrR;ufm(~4!jQ^!Kd*hoN8#&DkIK?^Wh@66s~}) z;M({(+#J7(yW{?N zC?1Qa;JJ7yUV}H|op?V!ivPm@;?(aZt!~6O<2&%Z_(A+Au7T^}#<&&kgnQ$+@q73~ z{1IM+SKtkJ8{UHt;gk3RPVrvS>IR$x=f#C_3H%7IitFHpxCL&Hd*C6QiO!3A+KTn1OdHF1611h>YWabG+bkHQo2EW8-6#2fK; zycZwFr|?Cba#YeP1I~%_;=;HDegs#=b#Nox5_iBo@c=v=kHgdOe7qd5!&~q!d;lNE zXYpm6c68D$3(kWJ;`{JJ_%Zw>eik>yZEzRd7Z1jx@FYANFTtzuCcFdh!$9$tpm;;->8d;lNEXYpm6c6`z;3(kWJ;$pZAehfc} zpT$ja8{7r=#e?xEJQ2^rOYkbZ3GcxB@DY3(U&5(ANLppYxp01b4=#l(;Oh8k`~rR% zcf`H$Ks*AE$J6lw{3%|Kx8mLSAU=W5;VU@Zhe@}r_!fL8z7IcyAHz@LXK_>926w@I z@nAd(PsFqEV!RS>#M|*+d>Eg?7jeo7NvjMvC(ert;}ZB0Tou>F4RH(H9{0d+;$irG zJQdHw%kWyf1@FQK@Ns+=U&d)CCf%~&Jh&h(h9AO@;V1F4xG8RfyWqZfFdl^`;@Nl! zUWGT|9e5u;f=}a1IMt-2RVI8B&X4cGrEmpY9Y2jGw?$E8U6x) zgMYxk;NS6id=00coOH{MZ^MP~{kR;if@|aFaC7`B?vDH8p?EBwg6HC;cn#i+cjBM% zF?V5_y|6YFX2?Pl2#dUE}ReFgG=EGxH^6szkpxH9dR!_ z5WkB*z%%ed{2BfNe}jL(zu@2Td3+ULKRfA`4d06I!o_h}Tp8EG4RCYZ4tK+E;CJvC zJQ>fypWxMaGv0~!X5{4Y*DCuwyfz8T+v@5K+|NAVN*8T=xC1;2)0$8X{H@Q3&# z{4xFi6B1^2~+@hChI&%%rGO1u&8z;REzwk zvfx|ro%lZd5Pl3liJ!$yaU0wP_r-(pXgmqe#!K)jyb15X`|uHb8ehVx7A37R;#@c% zE`m$q^0*qViyPsVxFha`2jUTUJf4mh;7{>-ycO@pzu@2Td3+ULzc}fZ4d06I!o_h} zTm{#{4RABu7I(${@DMy2Pr|eDCwLX!gm>V5_y|6YFX2>6l2#dUE}S3VgG=EGxH^6s zzkpxH9dR!_5WkB*z%%ed{2BfNe}jL(zu@2Td3+70|0L;_9p8ov;rnqpTm{$0&*A2{ z9qxwT!0+HOcru=YKf$Z*FT4HSUc2;6ZpKo`7fK z#dsy&h_~at_%J?&FXEJ+Cap5yoH!pYf=lA^xEijD8{w9?1MZ0j;Nf^2o`&b+<#-+5 zf_LEq_&7d`ui$i_CEc>(TkxIuKKu}V3_ppV#Z7S=+y(c=gYhUl5zoSl@k+cAZ^!%a z5quh7!l^z_T4lt!a6ViFm&E09HT*Pw0l$np;$C>39MD6n}xg!9U<%@bCCM zzKXA3k#x(3Z^ec1{kR;if@|aFaC6)acf)Vsckoy|1<%Dx@fy4t@5KA@QT!MF7pGpC zw91Tg;{v!SE{!YV8n_;Aj9cMOxHlezN8$;1CSHVB;0<^i-h&U}llTHou_|eG1I~eO z$9Llg@Wc3VTn9JAEpU6>1HXxf;rH=WJRdK|>+lx53m?G8@mYKsr(K8!y4D@Fu(i@58_0Kk+~Kx;06wO!y|8AK!yZ;R?7q zeg?mYU%{{8*YR8UUHk!_ffwS>@R#^o{3HGq|AGI;*Kqo^Nw@6yHe3ilfFH(>_5nL75!3}W>+#dJ9Z{lJ2eLNM!x7GK6`HzeJ%;5@h>E`}e%kKrfrv$!d4gS+6qcrYG?C*j$630{Ra;T?D% zK7vofyasQ^JMn&e6#s?)#i_qa zTHT0m#szRuTpCxzHE=!L7`MWmaBuuJ9*HO5nRpRifj8i7cn>~=PvQ$W<>sVS2AmV; z#f5PR{0Od!>)?jC1@3@*;sJO#9*3vl`FJ^AhqvHe_y9hR&*IBC?bk`SEI1D?h>PJe zxDu|3pT$ja8{7r=#e?xEJQ2^ri}6al3GcxB@DY3(U&5)jB&{;yTsR-T2baPXaCQ7N zegVIXJK|n=ARd9o;~97%{tSPCzrjD?U-0kvJidyr-@Q@Jzf2ufQAdHoONP!YACGwy>2;gNU(o{1OX z6?g;QhWFq@_$0o7Q*2LK-GFo8+wtA_0sJt296yDh$1mYmad+Gw55;5g6g(F%#cS|p zyc6%oNAX|yUz~bJ((OikGrj}giyy>~;wNxD+!(jQop5jbHhvF(h(E#~6Q)Oitob3aamj$ z*TM~OGu#$;#r^OQJQ`2Jv+)wV3U9(Y@IHJ5pT?JPsvnb98F4P04;R5Dad}(~*Ts!+ zOWXnX!~^hfJPuF8^YL=L4sXG`@Bw@rpT(DP+C53PEI1D?i0{J>;m7ck_*vW(x4~U- zUpyF(!V~co8bKu+Y-M9pP1Xsm%a6{Yzx5qv3n|K(0A5X>e@G`s>e~rJ# zKjUNg4E_(N`8ny91?Ry9aWPy5SHd-MecS}M#+`9rJQ$C{6Y(s(7_Y<|@pilyAHk>b zC7kL&(kdg)h4bMexFjx*tKqu15pIb);GTE@9*)Q1X?Q+fj@RR@csD+XPvCR-3Ql)0 z>6R7Wg73t|aamj$*TM~OGu#$;#r^OQJQ`2Jv+)wV3U9(Y@IHJ5pT?JPs$Y^;8F4P0 z4;R5Dad}(~*Ts!+OWXnX!~^jNJRVQS3-G6SJ>H6UwitUWy81PyKr$_ z7FWi#a0A>Nx5M4=8~7bO22aLw@F#dR{tEBJ`|(ly7ycKgK9sb&5#NmO!1v*2<@74C$4kdblxeg*)Ru zcn}_mC*YZQ5nh2e;B9yhK8#P{i#X+PNvjMvC(ert;}ZB0Tou>Fjc`lc0r$iM@Nhg1 zPs8)^a=Z?2!MpGQd>o&}mvP#oNw+LG4=#v{;WD@qu8Hg8Cb%{3jQik0cqE>PXW_+o zCEkd) z;REyZEzRd7Z1jx@I*WdFUBkJM!X&G#fR}J zd=aNSk+jNybK<CfQRF8cp9FMm*aJK3*Lnf;N$o#zJk;J zo^;EKZ^3us`|v~fG5jQc7B|IhaaY_A55c4HBs?20!K?5lyaWG)f5U&`fADpGB&{;x zn{a-74=#lt#ntiC_yznj?udKgfp`QSkEi1W_*1+dZ^gUuL3{$A!&h*+lS#L1_*Q%u zE{@CM%D5J8fScjAxEp>0zk|o%$#@R_1h2+l;qUNI_&59~{s&)oDruDo--PqydvGaS z0awRQ;}`JDxFha`2jUTUJf4mh;7{>-ycO@p2k{Af4qw6PPAA>6;#=^YxHvA0E8|+Y z0d9ud;;y(Keg}`ilkpt<30{rA!r$Sa@Nf7}{4Y-ZXVU6Md^5fS--{o_kK!lrGx$aP z3Vsd0j^D!X;t%i)ybynezrf$%AMvmF5BxX2hSUF*bjyx!!-equxE!v6Yvbo|bKDMh z!*Aes@EAN9&%sOaYWx-c4*!II!++v`@O5XBR+;ckI6uA@KZqa2PvB?pi})4%8h#zW zh2O&;;*aph_;dUv{ucj;f5m^`zwtGk{%q1M2fiKOjUT`dcv$!d4gS+6qcrYG?C*oOn zF+x2+8z00c@Hu=1 zr@NSR%Z6{ocj4l=EUt`e;Rd)FZi~C(es~BTjVIyRcnMyGH{l(4A3lQr#Q)&yE+wrp z;hS)Nd=D;#E8yz*Y5W3y1;2)0$8X_x@dtPYUWh-#U*K=>5BL}SJ3f!E;_LrOx@E(+ z;=6EhTn<;kwefSfIc|r$;WzL*cnqG5=i;S!4c?4*;{Et2{tN$$Q~#T^%8Ya40=OtH zjVt0BxE^kdTj5T)H+~zxhd;z0;g9j>cmv*s_uxbLB)))C{Fk)40q4MZaba8nKZ2{` zI=CTjf!pIA_)RC zfQRF8cp6@SKgH|uR=gV@#3%4MdkPsQ`_GQ1XV z!MpGQd>o&}mvP$bl5SaW9$XL?!)0(KToc#FO>k@68TY}1@JKuX&%}%H3cLYt!+Y={ zd=g*4DN-k`ZooP4?f7o|0Dc%hj-SHM8!y4D@Fu(i@54v%X?zK%x;|-@5$D4Ba1mS* zm&es`UEBz_#2s-jJP?n-RNL0MEb+@n`r8{0;sA|AK$V=kYb1K10$iJH8DU!uR8HxC*X~pTo^@JKP=j z$3yX0JO$6iOYs`K8SlhD<74;?{tu_gn6%1_bK?TIC@zgF;u^RfZj4*uPPjLI8^4D? z#2?|0@#pwU{4M?w|BC;>f8%R7eWs*ac6=Kygzv}Ya1~q|KZl#+cDNgU0}sVx@MJs( ze}Y%zukd&HC;S`!6aR}-- z3SY!2vnH)F;G8%wE{x0IO1LJjkDK7uxHIm92jP);0-lK%;T3oT-iG(!L--WFh*M^x z70!wC;=;HDegs#=b#Wuy5_iBo@c=v=kHgdOe7qd5!&~q!d;lNEXYpm6Hha=73(kWJ z;$pZAu7qpi`nU;hjXUE$cn}_iC*oOnFcG9!)0-0TnjhA z&2U@X75BqK@Mt^<&%vMI)%Yv?9sUXbhX2I>;OlZFtuo=8@g4YH{2+c5KY^dYFXC75 zYxs5i7Je6hfM?)^_%r+k{s#Ymf5E@w^Y|*h{-&f`Hhe3-3m3;_ab;W!KZl#+cDNgU z1HXgE;K_In{sgbaoAFM(A0Nek;eT=Jo0C>I;+ydu_+DHZSHv}NJ=_?#!kut${5F0M ze~3TAALGyQm-t)!BmNctf&a$WaQfUyw;cF(d^dgoKa3y8PvPhBOZZjX9rwpW@mM?s g&&5me8oU|r#QX74d