From dd27458de8c90fa075f033c251e9a44a7974c0f6 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 15 Apr 2021 17:57:47 -0700 Subject: [PATCH 01/37] fix px4 connection for wsl 2. --- AirLib/include/common/AirSimSettings.hpp | 14 +- .../include/sensors/gps/GpsSimpleParams.hpp | 2 +- .../car/firmwares/ardurover/ArduRoverApi.hpp | 4 +- .../firmwares/arducopter/ArduCopterApi.hpp | 4 +- .../firmwares/mavlink/ArduCopterSoloApi.hpp | 4 +- .../mavlink/MavLinkMultirotorApi.hpp | 316 ++++++++++++++---- DroneServer/main.cpp | 4 +- HelloSpawnedDrones/HelloSpawnedDrones.vcxproj | 4 +- MavLinkCom/MavLinkCom.vcxproj | 1 + MavLinkCom/MavLinkCom.vcxproj.filters | 1 + MavLinkCom/common_utils/Utils.hpp | 27 +- MavLinkCom/include/AsyncResult.hpp | 9 +- MavLinkCom/include/MavLinkConnection.hpp | 7 +- MavLinkCom/include/MavLinkDebugLog.hpp | 37 ++ MavLinkCom/include/MavLinkNode.hpp | 2 +- MavLinkCom/include/MavLinkVehicle.hpp | 2 +- MavLinkCom/src/MavLinkConnection.cpp | 15 +- MavLinkCom/src/MavLinkVehicle.cpp | 4 +- MavLinkCom/src/impl/MavLinkConnectionImpl.cpp | 24 +- MavLinkCom/src/impl/MavLinkConnectionImpl.hpp | 5 +- MavLinkCom/src/impl/MavLinkVehicleImpl.cpp | 34 +- MavLinkCom/src/impl/MavLinkVehicleImpl.hpp | 2 +- PythonClient/multirotor/stability_test.py | 83 +++++ build.cmd | 69 ++-- docs/px4_logging.md | 19 +- docs/px4_sitl.md | 8 + docs/px4_sitl_wsl2.md | 106 ++++++ mkdocs.yml | 1 + 28 files changed, 652 insertions(+), 156 deletions(-) create mode 100644 MavLinkCom/include/MavLinkDebugLog.hpp create mode 100644 PythonClient/multirotor/stability_test.py create mode 100644 docs/px4_sitl_wsl2.md diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index 8300f7a777..fd3b663d1b 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -280,10 +280,10 @@ struct AirSimSettings { int tcp_port = 4560; // The PX4 SITL app requires receiving drone commands over a different mavlink channel called - // the "ground control station" channel. - // So set this to empty string to disable this separate command channel. + // the "ground control station" (or GCS) channel. std::string control_ip_address = "127.0.0.1"; - int control_port = 14580; + int control_port_local = 14540; + int control_port_remote = 14580; // The log viewer can be on a different machine, so you can configure it's ip address and port here. int logviewer_ip_port = 14388; @@ -311,6 +311,7 @@ struct AirSimSettings { std::string model = "Generic"; std::map params; + std::string logs; }; struct MavLinkVehicleSetting : public VehicleSetting { @@ -714,7 +715,9 @@ struct AirSimSettings { connection_info.qgc_ip_port = settings_json.getInt("QgcPort", connection_info.qgc_ip_port); connection_info.control_ip_address = settings_json.getString("ControlIp", connection_info.control_ip_address); - connection_info.control_port = settings_json.getInt("ControlPort", connection_info.control_port); + connection_info.control_port_local = settings_json.getInt("ControlPort", connection_info.control_port_local); // legacy + connection_info.control_port_local = settings_json.getInt("ControlPortLocal", connection_info.control_port_local); + connection_info.control_port_remote = settings_json.getInt("ControlPortRemote", connection_info.control_port_remote); std::string sitlip = settings_json.getString("SitlIp", connection_info.control_ip_address); if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0) @@ -725,7 +728,7 @@ struct AirSimSettings { if (settings_json.hasKey("SitlPort")) { // backwards compat - connection_info.control_port = settings_json.getInt("SitlPort", connection_info.control_port); + connection_info.control_port_local = settings_json.getInt("SitlPort", connection_info.control_port_local); } connection_info.local_host_ip = settings_json.getString("LocalHostIp", connection_info.local_host_ip); @@ -738,6 +741,7 @@ struct AirSimSettings { connection_info.serial_port = settings_json.getString("SerialPort", connection_info.serial_port); connection_info.baud_rate = settings_json.getInt("SerialBaudRate", connection_info.baud_rate); connection_info.model = settings_json.getString("Model", connection_info.model); + connection_info.logs = settings_json.getString("Logs", connection_info.logs); Settings params; if (settings_json.getChild("Parameters", params)) { diff --git a/AirLib/include/sensors/gps/GpsSimpleParams.hpp b/AirLib/include/sensors/gps/GpsSimpleParams.hpp index 52d8cf88c8..43e38277a5 100644 --- a/AirLib/include/sensors/gps/GpsSimpleParams.hpp +++ b/AirLib/include/sensors/gps/GpsSimpleParams.hpp @@ -12,7 +12,7 @@ namespace msr { namespace airlib { struct GpsSimpleParams { real_T eph_time_constant = 0.9f, epv_time_constant = 0.9f; real_T eph_initial = 100.0f, epv_initial = 100.0f; //initially fully diluted positions - real_T eph_final = 0.3f, epv_final = 0.4f; + real_T eph_final = 0.1f, epv_final = 0.1f; // PX4 won't converge GPS sensor fusion until we get to 10% accuracty. real_T eph_min_3d = 3.0f, eph_min_2d = 4.0f; real_T update_latency = 0.2f; //sec diff --git a/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp b/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp index 37ce927c36..b3f8966497 100644 --- a/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp +++ b/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp @@ -142,10 +142,10 @@ class ArduRoverApi : public CarApiBase { } Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); - Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); + Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); udpSocket_ = std::make_shared(); - udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port); + udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port_local); } private: diff --git a/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp index 400ac408ed..2f7d1992f6 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp @@ -318,10 +318,10 @@ class ArduCopterApi : public MultirotorApiBase { } Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); - Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); + Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); udpSocket_ = std::make_shared(); - udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port); + udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port_local); } private: diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp index 6190c86ef0..bc1db991f7 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp @@ -113,9 +113,9 @@ class ArduCopterSoloApi : public MavLinkMultirotorApi } Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo); - Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo); + Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo); - udpSocket_ = mavlinkcom::AdHocConnection::connectLocalUdp("ArduCopterSoloConnector", ip, connection_info_.control_port); + udpSocket_ = mavlinkcom::AdHocConnection::connectLocalUdp("ArduCopterSoloConnector", ip, connection_info_.control_port_local); mavlinkcom::AdHocMessageHandler handler = [this](std::shared_ptr connection, const std::vector &msg) { this->rotorPowerMessageHandler(connection, msg); }; diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 4b9c625f93..dd9912cddd 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -20,6 +20,7 @@ #include #include "common/Common.hpp" +#include "common/common_utils/FileSystem.hpp" #include "common/common_utils/SmoothingFilter.hpp" #include "common/common_utils/Timer.hpp" #include "common/CommonStructs.hpp" @@ -81,11 +82,30 @@ class MavLinkMultirotorApi : public MultirotorApiBase //reset PX4 stack virtual void resetImplementation() override { + // note this is called AFTER "initialize" when we've connected to the drone + // so this method cannot reset any of that connection state. MultirotorApiBase::resetImplementation(); - - resetState(); was_reset_ = true; - setNormalMode(); + } + + unsigned long long getSimTime() { + // This ensures HIL_SENSOR and HIL_GPS have matching clocks. + //if (lock_step_enabled_) { + if (sim_time_us_ == 0) { + sim_time_us_ = clock()->nowNanos() / 1000; + } + return sim_time_us_; + // } + //else { + // return clock()->nowNanos() / 1000; + //} + } + + void advanceTime() { + if (lock_step_enabled_) { + // sim_time_us_ += ticks_per_update_; + } + sim_time_us_ = clock()->nowNanos() / 1000; } //update sensors in PX4 stack @@ -97,10 +117,16 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) return; - if (send_params_) { - send_params_ = false; - sendParams(); - } + //auto now = clock()->nowNanos() / 1000; + + //if (last_hil_sensor_time_ != 0 && last_hil_sensor_time_ + ticks_per_update_ > now) + //{ + // // then update() is being called too often, so we just skip this one. + // // TODO: I think this needs to be aware of AirSim ClockSpeed... + // // return; + //} + + advanceTime(); //send sensor updates const auto& imu_output = getImuData(""); @@ -111,7 +137,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase imu_output.angular_velocity, mag_output.magnetic_field_body, baro_output.pressure * 0.01f /*Pa to Millibar */, baro_output.altitude); - + + sendSystemTime(); const uint count_distance_sensors = getSensors().size(SensorBase::SensorType::Distance); if (count_distance_sensors != 0) { @@ -146,7 +173,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase sendHILGps(gps_output.gnss.geo_point, gps_velocity, gps_velocity_xy.norm(), gps_cog, gps_output.gnss.eph, gps_output.gnss.epv, gps_output.gnss.fix_type, 10); } - } + } + } catch (std::exception& e) { addStatusMessage("Exception sending messages to vehicle"); @@ -273,6 +301,48 @@ class MavLinkMultirotorApi : public MultirotorApiBase return rc; } + void onArmed() { + if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { + auto con = mav_vehicle_->getConnection(); + if (con != nullptr) { + if (log_ != nullptr) { + log_->close(); + } + + std::time_t t = std::time(0); // get time now + std::tm* now = std::localtime(&t); + auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday); + auto path = common_utils::FileSystem::ensureFolder(connection_info_.logs, folder); + auto filename = Utils::stringf("%02d-%02d-%02d.mavlink", now->tm_hour, now->tm_min, now->tm_sec); + auto fullpath = common_utils::FileSystem::combine(path, filename); + addStatusMessage(Utils::stringf("Opening log file: %s", fullpath.c_str())); + log_ = std::make_shared(); + log_->openForWriting(fullpath, false); + con->startLoggingSendMessage(log_); + con->startLoggingReceiveMessage(log_); + if (con != connection_) { + // log the SITL channel also + connection_->startLoggingSendMessage(log_); + connection_->startLoggingReceiveMessage(log_); + } + } + } + } + + void onDisarmed() { + if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { + auto con = mav_vehicle_->getConnection(); + if (con != nullptr) { + con->stopLoggingSendMessage(); + addStatusMessage("Closing log file."); + } + connection_->stopLoggingSendMessage(); + if (log_ != nullptr) { + log_->close(); + } + } + } + void waitForHomeLocation(float timeout_sec) { if (!current_state_.home.is_set) { @@ -712,7 +782,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (qgc_proxy_ != nullptr) { qgc_proxy_->close(); qgc_proxy_ = nullptr; - } + } + + resetState(); } void connect_thread() @@ -724,8 +796,12 @@ class MavLinkMultirotorApi : public MultirotorApiBase connectToLogViewer(); connectToQGC(); } - connecting_ = false; - connected_ = true; + + if (connecting_) { + // only set connected if we haven't already been told to disconnect. + connecting_ = false; + connected_ = true; + } } virtual void close() @@ -743,9 +819,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase void openAllConnections() { + Utils::log("Opening mavlink connection"); close(); //just in case if connections were open resetState(); //reset all variables we might have changed during last session - connect(); } @@ -1034,11 +1110,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase close(); connecting_ = true; - got_first_heartbeat_ = false; - is_hil_mode_set_ = false; - is_armed_ = false; - has_home_ = false; - is_controls_0_1_ = true; + is_controls_0_1_ = true; + std::string remoteIpAddr; Utils::setValue(rotor_controls_, 0.0f); if (connection_info.use_tcp) { @@ -1050,7 +1123,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase addStatusMessage(msg); try { connection_ = std::make_shared(); - connection_->acceptTcp("hil", connection_info_.local_host_ip, connection_info.tcp_port); + remoteIpAddr = connection_->acceptTcp("hil", connection_info_.local_host_ip, connection_info.tcp_port); } catch (std::exception& e) { addStatusMessage("Accepting TCP socket failed, is another instance running?"); @@ -1088,28 +1161,52 @@ class MavLinkMultirotorApi : public MultirotorApiBase mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); if (connection_info_.control_ip_address != "") { - if (connection_info_.control_port == 0) { - throw std::invalid_argument("ControlPort setting has an invalid value."); + if (connection_info_.control_port_local == 0) { + throw std::invalid_argument("LocalControlPort setting has an invalid value."); + } + if (!connection_info.use_tcp || connection_info_.control_ip_address != "remote") { + remoteIpAddr = connection_info_.control_ip_address; + } + if (remoteIpAddr == "local" || remoteIpAddr == "localhost") { + remoteIpAddr = "127.0.0.1"; } // The PX4 SITL mode app cannot receive commands to control the drone over the same HIL mavlink connection. // The HIL mavlink connection can only handle HIL_SENSOR messages. This separate channel is needed for // everything else. - addStatusMessage(Utils::stringf("Connecting to PX4 Control UDP port %d, local IP %s, remote IP...", - connection_info_.control_port, connection_info_.local_host_ip.c_str(), connection_info_.control_ip_address.c_str())); + addStatusMessage(Utils::stringf("Connecting to PX4 Control UDP port %d, local IP %s, remote IP %s ...", + connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), remoteIpAddr.c_str())); // if we try and connect the UDP port too quickly it doesn't work, bug in PX4 ? for (int retries = 60; retries >= 0 && connecting_; retries--) { try { - auto gcsConnection = mavlinkcom::MavLinkConnection::connectRemoteUdp("gcs", - connection_info_.local_host_ip, connection_info_.control_ip_address, connection_info_.control_port); + std::shared_ptr gcsConnection; + if (remoteIpAddr == "127.0.0.1") { + gcsConnection = mavlinkcom::MavLinkConnection::connectLocalUdp("gcs", + connection_info_.local_host_ip, + connection_info_.control_port_local); + } + else { + gcsConnection = mavlinkcom::MavLinkConnection::connectRemoteUdp("gcs", + connection_info_.local_host_ip, + remoteIpAddr, + connection_info_.control_port_remote); + } mav_vehicle_->connect(gcsConnection); + // need to try and send something to make sure the connection is good. + mav_vehicle_->setMessageInterval(mavlinkcom::MavLinkHomePosition::kMessageId, 1); + break; } catch (std::exception&) { std::this_thread::sleep_for(std::chrono::seconds(1)); } } + if (mav_vehicle_ == nullptr) { + // play was stopped! + return; + } + if (mav_vehicle_->getConnection() != nullptr) { addStatusMessage(std::string("Ground control connected over UDP.")); } @@ -1117,31 +1214,73 @@ class MavLinkMultirotorApi : public MultirotorApiBase addStatusMessage(std::string("Timeout trying to connect ground control over UDP.")); return; } + } + try { + connectVehicle(); + } + catch (std::exception& e) { + addStatusMessage("Error connecting vehicle:"); + addStatusMessage(e.what()); } + } - connectVehicle(); + void processControlMessages(const mavlinkcom::MavLinkMessage& msg) + { + // Utils::log(Utils::stringf("Control msg %d", msg.msgid)); + // PX4 usually sends the following on the control channel. + // If nothing is arriving here it means our control channel UDP connection isn't working. + // MAVLINK_MSG_ID_HIGHRES_IMU + // MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET + // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW + // MAVLINK_MSG_ID_GPS_RAW_INT + // MAVLINK_MSG_ID_TIMESYNC + // MAVLINK_MSG_ID_ALTITUDE + // MAVLINK_MSG_ID_VFR_HUD + // MAVLINK_MSG_ID_ESTIMATOR_STATUS + // MAVLINK_MSG_ID_EXTENDED_SYS_STATE + // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN + // MAVLINK_MSG_ID_PING + // MAVLINK_MSG_ID_SYS_STATUS + // MAVLINK_MSG_ID_SYSTEM_TIME + // MAVLINK_MSG_ID_LINK_NODE_STATUS + // MAVLINK_MSG_ID_AUTOPILOT_VERSION + // MAVLINK_MSG_ID_COMMAND_ACK + // MAVLINK_MSG_ID_STATUSTEXT + // MAVLINK_MSG_ID_PARAM_VALUE + processMavMessages(msg); } void connectVehicle() { // listen to this UDP mavlink connection also auto mavcon = mav_vehicle_->getConnection(); - if (mavcon != connection_) { + if (mavcon != nullptr && mavcon != connection_) { mavcon->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { - unused(connection); - processMavMessages(msg); - }); + unused(connection); + processControlMessages(msg); + }); } else { mav_vehicle_->connect(connection_); } connected_ = true; - // now we can start our heartbeats. - mav_vehicle_->startHeartbeat(); // Also request home position messages mav_vehicle_->setMessageInterval(mavlinkcom::MavLinkHomePosition::kMessageId, 1); + + // now we can start our heartbeats. + mav_vehicle_->startHeartbeat(); + + // wait for px4 to connect so we can safely send any configured parameters + while (!send_params_ && connected_) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + + if (connected_) { + sendParams(); + send_params_ = false; + } } void createMavSerialConnection(const std::string& port_name, int baud_rate) @@ -1184,15 +1323,15 @@ class MavLinkMultirotorApi : public MultirotorApiBase hil_node_->connect(connection_); addStatusMessage(Utils::stringf("Connected to PX4 over serial port: %s", port_name_auto.c_str())); - mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); - mav_vehicle_->connect(connection_); // in this case we can use the same connection. - mav_vehicle_->startHeartbeat(); // start listening to the HITL connection. connection_->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { unused(connection); processMavMessages(msg); }); + mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); + + connectVehicle(); return; } catch (std::exception& e) { @@ -1228,24 +1367,41 @@ class MavLinkMultirotorApi : public MultirotorApiBase void sendParams() { // send any mavlink parameters from settings.json through to the connected vehicle. - if (connection_info_.params.size() > 0) { - for (auto iter : connection_info_.params) { - auto key = iter.first; - auto value = iter.second; - mavlinkcom::MavLinkParameter p; - p.name = key; - p.value = value; - bool result = false; - mav_vehicle_->setParameter(p).wait(1000, &result); - if (!result) { - Utils::log(Utils::stringf("Failed to set mavlink parameter '%s'", key.c_str())); + if (mav_vehicle_ != nullptr && connection_info_.params.size() > 0) { + try { + for (auto iter : connection_info_.params) { + auto key = iter.first; + auto value = iter.second; + mavlinkcom::MavLinkParameter p; + p.name = key; + p.value = value; + bool result = false; + mav_vehicle_->setParameter(p).wait(1000, &result); + if (!result) { + Utils::log(Utils::stringf("Failed to set mavlink parameter '%s'", key.c_str())); + } } } + catch (std::exception& ex) { + addStatusMessage("Exception sending parameters to vehicle"); + addStatusMessage(ex.what()); + } } } void setArmed(bool armed) { + if (is_armed_) { + if (!armed) { + onDisarmed(); + } + } + else { + if (armed) { + onArmed(); + } + } + is_armed_ = armed; if (!armed) { //reset motor controls @@ -1296,8 +1452,6 @@ class MavLinkMultirotorApi : public MultirotorApiBase // and it scales multi rotor servo output to 0 to 1. is_controls_0_1_ = false; } - - send_params_ = true; } else if (is_simulation_mode_ && !is_hil_mode_set_) { setHILMode(); @@ -1376,7 +1530,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase addStatusMessage("Got GPS Home Location"); has_home_ = true; } - + send_params_ = true; } else if (msg.msgid == mavlinkcom::MavLinkLocalPositionNed::kMessageId) { // we are getting position information... so we can use this to check the stability of the z coordinate before takeoff. @@ -1388,20 +1542,34 @@ class MavLinkMultirotorApi : public MultirotorApiBase else if (msg.msgid == mavlinkcom::MavLinkExtendedSysState::kMessageId) { // check landed state. getLandedState(); + send_params_ = true; } else if (msg.msgid == mavlinkcom::MavLinkHomePosition::kMessageId) { mavlinkcom::MavLinkHomePosition home; home.decode(msg); + // this is a good time to send the params + send_params_ = true; + } + else if (msg.msgid == mavlinkcom::MavLinkSysStatus::kMessageId) { + // this is a good time to send the params + send_params_ = true; + } + else if (msg.msgid == mavlinkcom::MavLinkAutopilotVersion::kMessageId) { + // this is a good time to send the params + send_params_ = true; + } + else { + // creates too much log output, only do this when debugging this issue specifically. + // Utils::log(Utils::stringf("Ignornig msg %d from %d,%d ", msg.msgid, msg.compid, msg.sysid)); } - //else ignore message } void sendHILSensor(const Vector3r& acceleration, const Vector3r& gyro, const Vector3r& mag, float abs_pressure, float pressure_alt) { if (!is_simulation_mode_) throw std::logic_error("Attempt to send simulated sensor messages while not in simulation mode"); - - auto now = clock()->nowNanos() / 1000; + + auto now = getSimTime(); if (lock_step_enabled_) { if (last_hil_sensor_time_ + 100000 < now) { // if 100 ms passes then something is terribly wrong, reset lockstep mode @@ -1457,14 +1625,28 @@ class MavLinkMultirotorApi : public MultirotorApiBase last_sensor_message_ = hil_sensor; } + void sendSystemTime() { + // SYSTEM TIME from host + auto tu = getSimTime(); + uint32_t ms = (uint32_t)(tu / 1000); + if (ms != last_sys_time_) { + last_sys_time_ = ms; + mavlinkcom::MavLinkSystemTime msg_system_time; + msg_system_time.time_unix_usec = tu; + msg_system_time.time_boot_ms = last_sys_time_; + if (hil_node_ != nullptr) { + hil_node_->sendMessage(msg_system_time); + } + } + } + void sendDistanceSensor(float min_distance, float max_distance, float current_distance, float sensor_type, float sensor_id, Quaternionr orientation) { if (!is_simulation_mode_) throw std::logic_error("Attempt to send simulated distance sensor messages while not in simulation mode"); mavlinkcom::MavLinkDistanceSensor distance_sensor; - - distance_sensor.time_boot_ms = static_cast(clock()->nowNanos() / 1000000); + distance_sensor.time_boot_ms = static_cast(getSimTime() / 1000); distance_sensor.min_distance = static_cast(min_distance); distance_sensor.max_distance = static_cast(max_distance); distance_sensor.current_distance = static_cast(current_distance); @@ -1491,6 +1673,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase void sendHILGps(const GeoPoint& geo_point, const Vector3r& velocity, float velocity_xy, float cog, float eph, float epv, int fix_type, unsigned int satellites_visible) { + unused(satellites_visible); + if (!is_simulation_mode_) throw std::logic_error("Attempt to send simulated GPS messages while not in simulation mode"); @@ -1529,10 +1713,17 @@ class MavLinkMultirotorApi : public MultirotorApiBase is_controls_0_1_ = true; hil_state_freq_ = -1; actuators_message_supported_ = false; - last_gps_time_ = 0; state_version_ = 0; current_state_ = mavlinkcom::VehicleState(); target_height_ = 0; + got_first_heartbeat_ = false; + is_armed_ = false; + has_home_ = false; + sim_time_us_ = 0; + last_sys_time_ = 0; + last_gps_time_ = 0; + last_hil_sensor_time_ = 0; + hil_sensor_clock_ = 0; is_api_control_enabled_ = false; thrust_controller_ = PidController(); Utils::setValue(rotor_controls_, 0.0f); @@ -1607,15 +1798,12 @@ class MavLinkMultirotorApi : public MultirotorApiBase std::mutex mocap_pose_mutex_, heartbeat_mutex_, set_mode_mutex_, status_text_mutex_, last_message_mutex_; //variables required for VehicleApiBase implementation - bool got_first_heartbeat_, is_hil_mode_set_, is_armed_; + bool got_first_heartbeat_ = false, is_hil_mode_set_ = false, is_armed_ = false; bool is_controls_0_1_; //Are motor controls specified in 0..1 or -1..1? bool send_params_ = false; std::queue status_messages_; int hil_state_freq_; bool actuators_message_supported_ = false; - uint64_t last_gps_time_ = 0; - uint64_t last_hil_sensor_time_ = 0; - uint64_t hil_sensor_clock_ = 0; bool was_reset_ = false; bool has_home_ = false; bool is_ready_ = false; @@ -1631,6 +1819,15 @@ class MavLinkMultirotorApi : public MultirotorApiBase double ground_variance_ = 1; const double GroundTolerance = 0.1; + // variables for throttling HIL_SENSOR and SYSTEM_TIME messages + const int DEFAULT_SIM_RATE = 250; // Hz. + const unsigned long ticks_per_update_ = 1000000 / DEFAULT_SIM_RATE; // microseconds + uint32_t last_sys_time_ = 0; + unsigned long long sim_time_us_ = 0; + uint64_t last_gps_time_ = 0; + uint64_t last_hil_sensor_time_ = 0; + uint64_t hil_sensor_clock_ = 0; + //additional variables required for MultirotorApiBase implementation //this is optional for methods that might not use vehicle commands std::shared_ptr mav_vehicle_; @@ -1639,6 +1836,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase PidController thrust_controller_; common_utils::Timer hil_message_timer_; common_utils::Timer gcs_message_timer_; + std::shared_ptr log_; //every time we return status update, we need to check if we have new data //this is why below two variables are marked as mutable diff --git a/DroneServer/main.cpp b/DroneServer/main.cpp index b64000cc43..1806ec60c4 100644 --- a/DroneServer/main.cpp +++ b/DroneServer/main.cpp @@ -58,7 +58,9 @@ int main(int argc, const char* argv[]) connection_info.qgc_ip_port = child.getInt("QgcPort", connection_info.qgc_ip_port); connection_info.control_ip_address = child.getString("ControlIp", connection_info.control_ip_address); - connection_info.control_port = child.getInt("ControlPort", connection_info.control_port); + connection_info.control_port_local = child.getInt("ControlPort", connection_info.control_port_local); + connection_info.control_port_local = child.getInt("ControlPortLocal", connection_info.control_port_local); + connection_info.control_port_remote = child.getInt("ControlPortRemote", connection_info.control_port_remote); connection_info.local_host_ip = child.getString("LocalHostIp", connection_info.local_host_ip); diff --git a/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj b/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj index d150fadca8..7b61e1a5dc 100644 --- a/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj +++ b/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj @@ -117,7 +117,7 @@ - Use + NotUsing Level3 Disabled true @@ -131,7 +131,7 @@ - Use + NotUsing Level3 MaxSpeed true diff --git a/MavLinkCom/MavLinkCom.vcxproj b/MavLinkCom/MavLinkCom.vcxproj index 319db2dadf..71c5a5fad6 100644 --- a/MavLinkCom/MavLinkCom.vcxproj +++ b/MavLinkCom/MavLinkCom.vcxproj @@ -380,6 +380,7 @@ + diff --git a/MavLinkCom/MavLinkCom.vcxproj.filters b/MavLinkCom/MavLinkCom.vcxproj.filters index 0cc6ffdbac..fcaa6c57de 100644 --- a/MavLinkCom/MavLinkCom.vcxproj.filters +++ b/MavLinkCom/MavLinkCom.vcxproj.filters @@ -218,6 +218,7 @@ + diff --git a/MavLinkCom/common_utils/Utils.hpp b/MavLinkCom/common_utils/Utils.hpp index 66f27b6d3d..7c0bd91c85 100644 --- a/MavLinkCom/common_utils/Utils.hpp +++ b/MavLinkCom/common_utils/Utils.hpp @@ -22,6 +22,7 @@ #include #include #include "type_utils.hpp" +#include "MavLinkDebugLog.hpp" #ifndef _WIN32 #include // needed for CHAR_BIT used below @@ -98,17 +99,6 @@ class Utils { public: - class Logger { - public: - virtual void log(int level, const std::string& message) - { - if (level >= 0) - std::cout << message; - else - std::cerr << message; - } - }; - static void enableImmediateConsoleFlush() { //disable buffering setbuf(stdout, NULL); @@ -136,25 +126,12 @@ class Utils { return static_cast(radians * 180.0f / M_PIf); } - static Logger* getSetLogger(Logger* logger = nullptr) - { - static Logger logger_default_; - static Logger* logger_; - - if (logger != nullptr) - logger_ = logger; - else if (logger_ == nullptr) - logger_ = &logger_default_; - - return logger_; - } - static constexpr int kLogLevelInfo = 0; static constexpr int kLogLevelWarn = -1; static constexpr int kLogLevelError = -2; static void log(std::string message, int level = kLogLevelInfo) { - getSetLogger()->log(level, message); + mavlinkcom::MavLinkDebugLog::getSetLogger()->log(level, message); } template diff --git a/MavLinkCom/include/AsyncResult.hpp b/MavLinkCom/include/AsyncResult.hpp index 0bb6df72e6..64fb1ba310 100644 --- a/MavLinkCom/include/AsyncResult.hpp +++ b/MavLinkCom/include/AsyncResult.hpp @@ -30,7 +30,8 @@ namespace mavlinkcom { ~AsyncResultState() { complete(); - } + } + int getState() { return state_; } @@ -83,6 +84,12 @@ namespace mavlinkcom { state_ = nullptr; } + static AsyncResult Completed(T state) { + AsyncResult r(nullptr); + r.setResult(state); + return r; + } + void then(ResultHandler handler) { // keep state alive while we wait for async result. diff --git a/MavLinkCom/include/MavLinkConnection.hpp b/MavLinkCom/include/MavLinkConnection.hpp index 6dc7cd3e07..c77693b770 100644 --- a/MavLinkCom/include/MavLinkConnection.hpp +++ b/MavLinkCom/include/MavLinkConnection.hpp @@ -89,7 +89,8 @@ namespace mavlinkcom { // You may need to open this port in your firewall. // The localAddr can also a specific local ip address if you need to specify which // NIC to use, for example, wifi versus hard wired ethernet adapter. For localhost pass 127.0.0.1. - void acceptTcp(const std::string& nodeName, const std::string& localAddr, int listeningPort); + // It returns the address of the remote machine that connected. + std::string acceptTcp(const std::string& nodeName, const std::string& localAddr, int listeningPort); // instance methods std::string getName(); @@ -106,6 +107,10 @@ namespace mavlinkcom { void startLoggingSendMessage(std::shared_ptr log); void stopLoggingSendMessage(); + // log every message that is "received" by a subscriber. + void startLoggingReceiveMessage(std::shared_ptr log); + void stopLoggingReceiveMessage(); + uint8_t getNextSequence(); // Advanced method that create a bridge between two connections. For example, if you use connectRemoteUdp to connect to diff --git a/MavLinkCom/include/MavLinkDebugLog.hpp b/MavLinkCom/include/MavLinkDebugLog.hpp new file mode 100644 index 0000000000..4dada3d665 --- /dev/null +++ b/MavLinkCom/include/MavLinkDebugLog.hpp @@ -0,0 +1,37 @@ +// Copyright (c) Microsoft Corporation. All rights reserved. +// Licensed under the MIT License. + +#ifndef mavlink_Logger_hpp +#define mavlink_Logger_hpp + +#include +#include + +namespace mavlinkcom +{ + class MavLinkDebugLog { + public: + virtual void log(int level, const std::string& message) + { + if (level >= 0) + std::cout << message; + else + std::cerr << message; + } + + static MavLinkDebugLog* getSetLogger(MavLinkDebugLog* logger = nullptr) + { + static MavLinkDebugLog logger_default_; + static MavLinkDebugLog* logger_; + + if (logger != nullptr) + logger_ = logger; + else if (logger_ == nullptr) + logger_ = &logger_default_; + + return logger_; + } + }; +} + +#endif \ No newline at end of file diff --git a/MavLinkCom/include/MavLinkNode.hpp b/MavLinkCom/include/MavLinkNode.hpp index 54ee613d0c..be754090eb 100644 --- a/MavLinkCom/include/MavLinkNode.hpp +++ b/MavLinkCom/include/MavLinkNode.hpp @@ -92,7 +92,7 @@ namespace mavlinkcom { // passing a message along). void sendMessage(MavLinkMessage& msg); - // send a command to the remote node + // send a command to the remote node void sendCommand(MavLinkCommand& cmd); // send a command to the remote node and get async result that tells you whether it succeeded or not. diff --git a/MavLinkCom/include/MavLinkVehicle.hpp b/MavLinkCom/include/MavLinkVehicle.hpp index 81902f83e4..9607041bbf 100644 --- a/MavLinkCom/include/MavLinkVehicle.hpp +++ b/MavLinkCom/include/MavLinkVehicle.hpp @@ -37,7 +37,7 @@ namespace mavlinkcom { AsyncResult setMissionMode(); AsyncResult waitForHomePosition(); AsyncResult allowFlightControlOverUsb(); - AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0); + AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0, bool waitForAck = true); // wait for drone to reach specified local z, ensure it is not just blowing past the z location, // wait for it to settle down with dz delta, and dvz delta velocity. diff --git a/MavLinkCom/src/MavLinkConnection.cpp b/MavLinkCom/src/MavLinkConnection.cpp index 0d1b93ee98..27070f494a 100644 --- a/MavLinkCom/src/MavLinkConnection.cpp +++ b/MavLinkCom/src/MavLinkConnection.cpp @@ -32,9 +32,9 @@ std::shared_ptr MavLinkConnection::connectTcp(const std::str return MavLinkConnectionImpl::connectTcp(nodeName, localAddr, remoteIpAddr, remotePort); } -void MavLinkConnection::acceptTcp(const std::string& nodeName, const std::string& localAddr, int listeningPort) +std::string MavLinkConnection::acceptTcp(const std::string& nodeName, const std::string& localAddr, int listeningPort) { - pImpl->acceptTcp(shared_from_this(), nodeName, localAddr, listeningPort); + return pImpl->acceptTcp(shared_from_this(), nodeName, localAddr, listeningPort); } void MavLinkConnection::startListening(const std::string& nodeName, std::shared_ptr connectedPort) @@ -53,6 +53,17 @@ void MavLinkConnection::stopLoggingSendMessage() pImpl->stopLoggingSendMessage(); } +// log every message that is "received" +void MavLinkConnection::startLoggingReceiveMessage(std::shared_ptr log) +{ + pImpl->startLoggingReceiveMessage(log); +} + +void MavLinkConnection::stopLoggingReceiveMessage() +{ + pImpl->stopLoggingReceiveMessage(); +} + void MavLinkConnection::close() { pImpl->close(); diff --git a/MavLinkCom/src/MavLinkVehicle.cpp b/MavLinkCom/src/MavLinkVehicle.cpp index 3d4a183407..8ab9fd3040 100644 --- a/MavLinkCom/src/MavLinkVehicle.cpp +++ b/MavLinkCom/src/MavLinkVehicle.cpp @@ -50,10 +50,10 @@ AsyncResult MavLinkVehicle::returnToHome() return ptr->returnToHome(); } -AsyncResult MavLinkVehicle::setMode(int modeFlags, int customMode, int customSubMode) +AsyncResult MavLinkVehicle::setMode(int modeFlags, int customMode, int customSubMode, bool waitForAck) { auto ptr = static_cast(pImpl.get()); - return ptr->setMode(modeFlags, customMode, customSubMode); + return ptr->setMode(modeFlags, customMode, customSubMode, waitForAck); } bool MavLinkVehicle::isLocalControlSupported() diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp index 2e4655b7bc..1202aa1c40 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp @@ -86,7 +86,7 @@ std::shared_ptr MavLinkConnectionImpl::connectTcp(const std: return createConnection(nodeName, socket); } -void MavLinkConnectionImpl::acceptTcp(std::shared_ptr parent, const std::string& nodeName, const std::string& localAddr, int listeningPort) +std::string MavLinkConnectionImpl::acceptTcp(std::shared_ptr parent, const std::string& nodeName, const std::string& localAddr, int listeningPort) { std::string local = localAddr; close(); @@ -95,10 +95,13 @@ void MavLinkConnectionImpl::acceptTcp(std::shared_ptr parent, port = socket; // this is so that a call to close() can cancel this blocking accept call. socket->accept(localAddr, listeningPort); + std::string remote = socket->remoteAddress(); + socket->setNonBlocking(); socket->setNoDelay(); parent->startListening(nodeName, socket); + return remote; } std::shared_ptr MavLinkConnectionImpl::connectSerial(const std::string& nodeName, const std::string& portName, int baudRate, const std::string& initString) @@ -144,6 +147,17 @@ void MavLinkConnectionImpl::stopLoggingSendMessage() sendLog_ = nullptr; } +// log every message that is "sent" using sendMessage. +void MavLinkConnectionImpl::startLoggingReceiveMessage(std::shared_ptr log) +{ + receiveLog_ = log; +} + +void MavLinkConnectionImpl::stopLoggingReceiveMessage() +{ + receiveLog_ = nullptr; +} + void MavLinkConnectionImpl::close() { closed = true; @@ -159,7 +173,8 @@ void MavLinkConnectionImpl::close() msg_available_.post(); publish_thread_.join(); } - sendLog_ = nullptr; + sendLog_ = nullptr; + receiveLog_ = nullptr; } bool MavLinkConnectionImpl::isOpen() @@ -502,7 +517,12 @@ void MavLinkConnectionImpl::drainQueue() if (!hasMsg) { return; + } + + if (receiveLog_ != nullptr) { + receiveLog_->write(message); } + // publish the message from this thread, this is safer than publishing from the readPackets thread // as it ensures we don't lose messages if the listener is slow. if (snapshot_stale) { diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp index 3f43251674..3256ae41d6 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp @@ -36,7 +36,7 @@ namespace mavlinkcom_impl { static std::shared_ptr connectLocalUdp(const std::string& nodeName, const std::string& localAddr, int localPort); static std::shared_ptr connectRemoteUdp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteAddr, int remotePort); static std::shared_ptr connectTcp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteIpAddr, int remotePort); - void acceptTcp(std::shared_ptr parent, const std::string& nodeName, const std::string& localAddr, int listeningPort); + std::string acceptTcp(std::shared_ptr parent, const std::string& nodeName, const std::string& localAddr, int listeningPort); std::string getName(); int getTargetComponentId(); @@ -45,6 +45,8 @@ namespace mavlinkcom_impl { void startListening(std::shared_ptr parent, const std::string& nodeName, std::shared_ptr connectedPort); void startLoggingSendMessage(std::shared_ptr log); void stopLoggingSendMessage(); + void startLoggingReceiveMessage(std::shared_ptr log); + void stopLoggingReceiveMessage(); void close(); bool isOpen(); void sendMessage(const MavLinkMessageBase& msg); @@ -74,6 +76,7 @@ namespace mavlinkcom_impl { std::string accept_node_name_; std::shared_ptr server_; std::shared_ptr sendLog_; + std::shared_ptr receiveLog_; struct MessageHandlerEntry { public: diff --git a/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp b/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp index 43cf5097f3..be5067fa63 100644 --- a/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp @@ -585,9 +585,8 @@ void MavLinkVehicleImpl::releaseControl() control_requested_ = false; control_request_sent_ = false; vehicle_state_.controls.offboard = false; - MavCmdNavGuidedEnable cmd{}; - cmd.Enable = 0; - sendCommand(cmd); + setMode(static_cast(MAV_MODE_FLAG::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED), + static_cast(PX4_CUSTOM_MAIN_MODE_POSCTL), 0, false); } void MavLinkVehicleImpl::checkOffboard() @@ -609,15 +608,14 @@ void MavLinkVehicleImpl::checkOffboard() offboardIdle(); } - Utils::log("MavLinkVehicleImpl::checkOffboard: sending MavCmdNavGuidedEnable \n"); - // now the command should succeed. - bool r = false; - MavCmdNavGuidedEnable cmd{}; - cmd.Enable = 1; + Utils::log("MavLinkVehicleImpl::checkOffboard: sending MavCmdNavGuidedEnable \n"); // Note: we can't wait for ACK here, I've tried it. The ACK takes too long to get back to // us by which time the PX4 times out offboard mode!! - sendCommand(cmd); - control_request_sent_ = true; + setMode(static_cast(MAV_MODE_FLAG::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED), + static_cast(PX4_CUSTOM_MAIN_MODE_OFFBOARD), 0, false); + control_request_sent_ = true; + // assume this was successful, we'll find out if so in the next heartbeat. + vehicle_state_.controls.offboard = true; } } @@ -679,11 +677,13 @@ void MavLinkVehicleImpl::moveToGlobalPosition(float lat, float lon, float alt, b writeMessage(msg); } -AsyncResult MavLinkVehicleImpl::setMode(int mode, int customMode, int customSubMode) +AsyncResult MavLinkVehicleImpl::setMode(int mode, int customMode, int customSubMode, bool waitForAck) { // this mode change take precedence over offboard mode. - control_requested_ = false; - control_request_sent_ = false; + if (customMode != static_cast(PX4_CUSTOM_MAIN_MODE_OFFBOARD)) { + control_requested_ = false; + control_request_sent_ = false; + } if ((vehicle_state_.mode & static_cast(MAV_MODE_FLAG::MAV_MODE_FLAG_HIL_ENABLED)) != 0) { mode |= static_cast(MAV_MODE_FLAG::MAV_MODE_FLAG_HIL_ENABLED); // must preserve this flag. @@ -696,7 +696,13 @@ AsyncResult MavLinkVehicleImpl::setMode(int mode, int customMode, int cust cmd.Mode = static_cast(mode); cmd.CustomMode = static_cast(customMode); cmd.CustomSubmode = static_cast(customSubMode); - return sendCommandAndWaitForAck(cmd); + if (waitForAck) { + return sendCommandAndWaitForAck(cmd); + } + else { + sendCommand(cmd); + return AsyncResult::Completed(true); + } } AsyncResult MavLinkVehicleImpl::setPositionHoldMode() diff --git a/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp b/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp index 57ab49a435..23b7b9ce25 100644 --- a/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp +++ b/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp @@ -39,7 +39,7 @@ namespace mavlinkcom_impl { AsyncResult waitForHomePosition(); AsyncResult allowFlightControlOverUsb(); AsyncResult waitForAltitude(float z, float dz, float dvz); - AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0); + AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0, bool waitForAck = true); // request OFFBOARD control. void requestControl(); diff --git a/PythonClient/multirotor/stability_test.py b/PythonClient/multirotor/stability_test.py new file mode 100644 index 0000000000..cf1530194f --- /dev/null +++ b/PythonClient/multirotor/stability_test.py @@ -0,0 +1,83 @@ +import os +import setup_path +import airsim +import time +import numpy as np +import sys + +script_dir = os.path.dirname(__file__) + +client = airsim.MultirotorClient() +client.confirmConnection() +client.enableApiControl(True) + +def play_sound(wavfile): + import speaker + import wav_reader + reader = wav_reader.WavReader() + reader.open(wavfile, 512, speaker.Speaker()) + while True: + buffer = reader.read() + if buffer is None: + break + +class Numbers: + def __init__(self, name): + self.data = [] + self.name = name + + def add(self, x): + self.data += [x] + + def is_unstable(self, amount): + a = np.array(self.data) + minimum = a.min() + maximum = a.max() + mean = np.mean(a) + stddev = np.std(a) + print("{}: min={}, max={}, mean={}, stddev={}".format(self.name, minimum, maximum, mean, stddev)) + return (maximum - minimum) > amount + +while True: + x = Numbers("x") + y = Numbers("y") + z = Numbers("z") + + print("arming the drone...") + client.armDisarm(True) + + while client.getMultirotorState().landed_state == airsim.LandedState.Landed: + print("taking off...") + client.takeoffAsync().join() + time.sleep(1) + + # fly for a minute + start = time.time() + while time.time() < start + 20: + state = client.getMultirotorState() + x_val = state.kinematics_estimated.position.x_val + y_val = state.kinematics_estimated.position.y_val + z_val = state.kinematics_estimated.position.z_val + x.add(x_val) + y.add(y_val) + z.add(z_val) + print("x: {}, y: {}, z: {}".format(x_val, y_val, z_val)) + time.sleep(1) + + print("landing...") + client.landAsync().join() + + print("disarming the drone...") + client.armDisarm(False) + + # more than 50 centimeter drift is unacceptable. + a = x.is_unstable(0.5) + b = y.is_unstable(0.5) + c = z.is_unstable(0.5) + + if a or b or c: + play_sound(os.path.join(script_dir, "Error.wav")) + + time.sleep(5) + + diff --git a/build.cmd b/build.cmd index 82682d8f2e..61f798ce7f 100644 --- a/build.cmd +++ b/build.cmd @@ -23,15 +23,31 @@ if "%VisualStudioVersion%" lss "16.0" ( if "%1"=="" goto noargs if "%1"=="--no-full-poly-car" set "noFullPolyCar=y" -if "%1"=="--Debug" set "buildMode=--Debug" -if "%1"=="--Release" set "buildMode=--Release" +if "%1"=="--Debug" set "buildMode=Debug" +if "%1"=="--Release" set "buildMode=Release" +if "%1"=="--RelWithDebInfo" set "buildMode=RelWithDebInfo" if "%2"=="" goto noargs -if "%2"=="--Debug" set "buildMode=--Debug" -if "%2"=="--Release" set "buildMode=--Release" +if "%2"=="--Debug" set "buildMode=Debug" +if "%2"=="--Release" set "buildMode=Release" +if "%2"=="--RelWithDebInfo" set "buildMode=RelWithDebInfo" :noargs +set powershell=powershell +where powershell > nul 2>&1 +if ERRORLEVEL 1 goto :pwsh +echo found Powershell && goto start +:pwsh +set powershell=pwsh +where pwsh > nul 2>&1 +if ERRORLEVEL 1 goto :nopwsh +echo found pwsh && goto start +:nopwsh +echo Powershell or pwsh not found, please install it. +goto :eof + +:start chdir /d %ROOT_DIR% REM //---------- Check cmake version ---------- @@ -48,7 +64,7 @@ if ERRORLEVEL 1 ( REM //---------- get rpclib ---------- IF NOT EXIST external\rpclib mkdir external\rpclib IF NOT EXIST external\rpclib\rpclib-2.2.1 ( - REM //leave some blank lines because powershell shows download banner at top of console + REM //leave some blank lines because %powershell% shows download banner at top of console ECHO( ECHO( ECHO( @@ -56,13 +72,13 @@ IF NOT EXIST external\rpclib\rpclib-2.2.1 ( ECHO Downloading rpclib ECHO ***************************************************************************************** @echo on - powershell -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip }" + %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip }" @echo off REM //remove any previous versions rmdir external\rpclib /q /s - powershell -command "& { Expand-Archive -Path external\rpclib.zip -DestinationPath external\rpclib }" + %powershell% -command "& { Expand-Archive -Path external\rpclib.zip -DestinationPath external\rpclib }" del external\rpclib.zip /q REM //Don't fail the build if the high-poly car is unable to be downloaded @@ -79,13 +95,11 @@ IF NOT EXIST external\rpclib\rpclib-2.2.1\build mkdir external\rpclib\rpclib-2.2 cd external\rpclib\rpclib-2.2.1\build cmake -G"Visual Studio 16 2019" .. -if "%buildMode%" == "--Debug" ( -cmake --build . --config Debug -) else if "%buildMode%" == "--Release" ( +if "%buildMode%" == "" ( +cmake --build . cmake --build . --config Release ) else ( -cmake --build . -cmake --build . --config Release +cmake --build . --config %buildMode% ) if ERRORLEVEL 1 goto :buildfailed @@ -98,20 +112,18 @@ set RPCLIB_TARGET_INCLUDE=AirLib\deps\rpclib\include if NOT exist %RPCLIB_TARGET_INCLUDE% mkdir %RPCLIB_TARGET_INCLUDE% robocopy /MIR external\rpclib\rpclib-2.2.1\include %RPCLIB_TARGET_INCLUDE% -if "%buildMode%" == "--Debug" ( +if "%buildMode%" == "" ( robocopy /MIR external\rpclib\rpclib-2.2.1\build\Debug %RPCLIB_TARGET_LIB%\Debug -) else if "%buildMode%" == "--Release" ( robocopy /MIR external\rpclib\rpclib-2.2.1\build\Release %RPCLIB_TARGET_LIB%\Release ) else ( -robocopy /MIR external\rpclib\rpclib-2.2.1\build\Debug %RPCLIB_TARGET_LIB%\Debug -robocopy /MIR external\rpclib\rpclib-2.2.1\build\Release %RPCLIB_TARGET_LIB%\Release +robocopy /MIR external\rpclib\rpclib-2.2.1\build\%buildMode% %RPCLIB_TARGET_LIB%\%buildMode% ) REM //---------- get High PolyCount SUV Car Model ------------ IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv mkdir Unreal\Plugins\AirSim\Content\VehicleAdv IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv\SUV\v1.2.0 ( IF NOT DEFINED noFullPolyCar ( - REM //leave some blank lines because powershell shows download banner at top of console + REM //leave some blank lines because %powershell% shows download banner at top of console ECHO( ECHO( ECHO( @@ -123,12 +135,12 @@ IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv\SUV\v1.2.0 ( IF EXIST suv_download_tmp rmdir suv_download_tmp /q /s mkdir suv_download_tmp @echo on - REM powershell -command "& { Start-BitsTransfer -Source https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -Destination suv_download_tmp\car_assets.zip }" - REM powershell -command "& { (New-Object System.Net.WebClient).DownloadFile('https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip', 'suv_download_tmp\car_assets.zip') }" - powershell -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -OutFile suv_download_tmp\car_assets.zip }" + REM %powershell% -command "& { Start-BitsTransfer -Source https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -Destination suv_download_tmp\car_assets.zip }" + REM %powershell% -command "& { (New-Object System.Net.WebClient).DownloadFile('https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip', 'suv_download_tmp\car_assets.zip') }" + %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -OutFile suv_download_tmp\car_assets.zip }" @echo off rmdir /S /Q Unreal\Plugins\AirSim\Content\VehicleAdv\SUV - powershell -command "& { Expand-Archive -Path suv_download_tmp\car_assets.zip -DestinationPath Unreal\Plugins\AirSim\Content\VehicleAdv }" + %powershell% -command "& { Expand-Archive -Path suv_download_tmp\car_assets.zip -DestinationPath Unreal\Plugins\AirSim\Content\VehicleAdv }" rmdir suv_download_tmp /q /s REM //Don't fail the build if the high-poly car is unable to be downloaded @@ -142,9 +154,9 @@ IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv\SUV\v1.2.0 ( REM //---------- get Eigen library ---------- IF NOT EXIST AirLib\deps mkdir AirLib\deps IF NOT EXIST AirLib\deps\eigen3 ( - powershell -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip -OutFile eigen3.zip }" - powershell -command "& { Expand-Archive -Path eigen3.zip -DestinationPath AirLib\deps }" - powershell -command "& { Move-Item -Path AirLib\deps\eigen* -Destination AirLib\deps\del_eigen }" + %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip -OutFile eigen3.zip }" + %powershell% -command "& { Expand-Archive -Path eigen3.zip -DestinationPath AirLib\deps }" + %powershell% -command "& { Move-Item -Path AirLib\deps\eigen* -Destination AirLib\deps\del_eigen }" REM move AirLib\deps\eigen* AirLib\deps\del_eigen mkdir AirLib\deps\eigen3 move AirLib\deps\del_eigen\Eigen AirLib\deps\eigen3\Eigen @@ -155,16 +167,13 @@ IF NOT EXIST AirLib\deps\eigen3 goto :buildfailed REM //---------- now we have all dependencies to compile AirSim.sln which will also compile MavLinkCom ---------- -if "%buildMode%" == "--Debug" ( +if "%buildMode%" == "" ( msbuild -maxcpucount:12 /p:Platform=x64 /p:Configuration=Debug AirSim.sln if ERRORLEVEL 1 goto :buildfailed -) else if "%buildMode%" == "--Release" ( -msbuild -maxcpucount:12 /p:Platform=x64 /p:Configuration=Release AirSim.sln +msbuild -maxcpucount:12 /p:Platform=x64 /p:Configuration=Release AirSim.sln if ERRORLEVEL 1 goto :buildfailed ) else ( -msbuild -maxcpucount:12 /p:Platform=x64 /p:Configuration=Debug AirSim.sln -if ERRORLEVEL 1 goto :buildfailed -msbuild -maxcpucount:12 /p:Platform=x64 /p:Configuration=Release AirSim.sln +msbuild -maxcpucount:12 /p:Platform=x64 /p:Configuration=%buildMode% AirSim.sln if ERRORLEVEL 1 goto :buildfailed ) diff --git a/docs/px4_logging.md b/docs/px4_logging.md index 9c91c1f55d..9962380306 100644 --- a/docs/px4_logging.md +++ b/docs/px4_logging.md @@ -4,7 +4,24 @@ Thanks to [Chris Lovett](https://github.com/clovett) for developing various tool ## Logging MavLink Messages -The following command will connect MavLinkTest app to the Simulator and enable logging +AirSim can capture mavlink log files if you add the following to the PX4 section of your `settings.json` file: + +```json +{ + "SettingsVersion": 1.2, + "SimMode": "Multirotor", + "Vehicles": { + "PX4": { + ..., + "Logs": "c:/temp/mavlink" + } + } +} +``` + +AirSim will create a timestamped log file in this folder for each "armed/disarmed" flight session. + +You can also create log files using the `MavLinkTest` app to the Simulator and enable logging of all mavlink commands to and from the PX4. ``` MavLinkTest -server:127.0.0.1:14550 -logdir:d:\temp diff --git a/docs/px4_sitl.md b/docs/px4_sitl.md index d0b242a20e..7a117aee93 100644 --- a/docs/px4_sitl.md +++ b/docs/px4_sitl.md @@ -3,6 +3,9 @@ The [PX4](http://dev.px4.io) software provides a "software-in-loop" simulation (SITL) version of their stack that runs in Linux. If you are on Windows then you must use the [Cygwin Toolchain](https://dev.px4.io/master/en/setup/dev_env_windows_cygwin.html) as the [Bash On Windows](https://dev.px4.io/master/en/setup/dev_env_windows_bash_on_win.html) toolchain no longer works for SITL. +If you are using WSL2 please read these [additional +instructions](px4_sitl_wsl2.md). + **Note** that every time you stop the unreal app you have to restart the `px4` app. @@ -136,6 +139,11 @@ Local position: x=-0.0326988, y=0.00656854, z=5.48506 If the z coordinate is large like this then takeoff might not work as expected. Resetting the SITL and simulation should fix that problem. +## WSL 2 + +Windows Subsystem for Linux version 2 operates in a Virtual Machine. This requires +additional setup - see [additional instructions](px4_sitl_wsl2.md). + ## No Remote Control Notice the above setting is provided in the `params` section of the `settings.json` file: diff --git a/docs/px4_sitl_wsl2.md b/docs/px4_sitl_wsl2.md new file mode 100644 index 0000000000..03baaa8936 --- /dev/null +++ b/docs/px4_sitl_wsl2.md @@ -0,0 +1,106 @@ +# PX4 Software-in-Loop with WSL 2 + +The [Windows subsystem for Linux version +2](https://docs.microsoft.com/en-us/windows/wsl/install-win10) uses a Virtual Machine which has a +separate IP address from your Windows host machine. This means PX4 cannot find AirSim using +"localhost" which is the default behavior for PX4. + +You will notice that on Windows `ipconfig` returns a new ethernet adapter for WSL like this (notice +the vEthernet has `(WSL)` in the name: + +```plain +Ethernet adapter vEthernet (WSL): + + Connection-specific DNS Suffix . : + Link-local IPv6 Address . . . . . : fe80::1192:f9a5:df88:53ba%44 + IPv4 Address. . . . . . . . . . . : 172.31.64.1 + Subnet Mask . . . . . . . . . . . : 255.255.240.0 + Default Gateway . . . . . . . . . : +``` + +This address `172.31.64.1` is the address that WSL 2 can use to reach your Windows host machine. + +Starting with this [PX4 Change +Request](https://github.com/PX4/PX4-Autopilot/commit/1719ff9892f3c3d034f2b44e94d15527ab09cec6) PX4 +in SITL mode can now connect to AirSim on a different (remote) IP address. To enable this make sure +you have a version of PX4 containing this fix and set the following environment variable in linux: + +```shell +export PX4_SIM_HOST_ADDR=172.31.64.1 +``` + +**Note:** Be sure to update the above address `172.31.64.1` to match what you see from your +`ipconfig` command. + +Open incoming port 4560 using your Windows Firewall settings. + +Now on the linux side run `ip address show` and copy the `eth0 inet` address, it should be something +like `172.31.66.156`. This is the address Windows needs to know in order to find PX4. + +Edit your [AirSim settings](settings.md) file and add `LocalHostIp` to tell AirSim to use the WSL +ethernet adapter address instead of the default `localhost`. This will cause AirSim to open the TCP +port on that adapter which is the address that the PX4 app will be looking for. Also tell AirSim +to connect the `ControlIp` UDP channel by setting `ControlIp` to the magic string `remote`. +This resolves to the WSL 2 remote ip address found in the TCP socket. + +```json +{ + "SettingsVersion": 1.2, + "SimMode": "Multirotor", + "Vehicles": { + "PX4": { + "VehicleType": "PX4Multirotor", + "UseSerial": false, + "UseTcp": true, + "TcpPort": 4560, + "ControlIp": "remote", + "ControlPort": 14580, + "LocalHostIp": "172.31.64.1", + "Sensors":{ + "Barometer":{ + "SensorType": 1, + "Enabled": true, + "PressureFactorSigma": 0.0001825 + } + }, + "Parameters": { + "NAV_RCL_ACT": 0, + "NAV_DLL_ACT": 0, + "COM_OBL_ACT": 1, + "LPE_LAT": 47.641468, + "LPE_LON": -122.140165 + } + } + } +} +``` + +The "Barometer" setting keeps PX4 happy because the default AirSim barometer has a bit too much +noise generation. This setting clamps that down a bit. + +Lastly, please edit the Linux file in `ROMFS/px4fmu_common/init.d-posix/rcS` and make sure +it is looking for the `PX4_SIM_HOST_ADDR` environment variable and is passing that through to the +PX4 simulator like this: + +```shell +# If PX4_SIM_HOST_ADDR environment variable is empty use localhost. +if [ -z "${PX4_SIM_HOST_ADDR}" ]; then + echo "PX4 SIM HOST: localhost" + simulator start -c $simulator_tcp_port +else + echo "PX4 SIM HOST: $PX4_SIM_HOST_ADDR" + simulator start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port +fi +``` + +**Note:** this code might already be there depending on the version of PX4 you are using. + +**Note:** please be patient when waiting for the message: + +``` +INFO [simulator] Simulator connected on TCP port 4560. +``` + +It can take a little longer to establish the remote connection than it does with `localhost`. + +Now you can proceed with the steps shown in [Setting up PX4 Software-in-Loop](px4_sitl.md). diff --git a/mkdocs.yml b/mkdocs.yml index aa373a2007..e47e8e57be 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -85,6 +85,7 @@ nav: - "MavLink and PX4": - "PX4 Setup for AirSim": 'px4_setup.md' - "PX4 in SITL": 'px4_sitl.md' + - "PX4 SITL with WSL 2": 'px4_sitl_wsl2.md' - "PX4 Multi-vehicle in SITL": 'px4_multi_vehicle.md' - "AirSim with Pixhawk": 'https://youtu.be/1oY8Qu5maQQ' - "PX4 Setup with AirSim": 'https://youtu.be/HNWdYrtw3f0' From b30ee91cd88f693bbc396df8260f9a609ee7adad Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 15 Apr 2021 18:20:18 -0700 Subject: [PATCH 02/37] enable throttling to 250 hz and fix bug in lockstep, should not send HIL_GPS until lockstep is satisfied. --- .../mavlink/MavLinkMultirotorApi.hpp | 69 +++++++++---------- 1 file changed, 33 insertions(+), 36 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index dd9912cddd..58f0af295c 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -90,22 +90,24 @@ class MavLinkMultirotorApi : public MultirotorApiBase unsigned long long getSimTime() { // This ensures HIL_SENSOR and HIL_GPS have matching clocks. - //if (lock_step_enabled_) { + if (lock_step_enabled_) { if (sim_time_us_ == 0) { sim_time_us_ = clock()->nowNanos() / 1000; } return sim_time_us_; - // } - //else { - // return clock()->nowNanos() / 1000; - //} + } + else { + return clock()->nowNanos() / 1000; + } } void advanceTime() { if (lock_step_enabled_) { - // sim_time_us_ += ticks_per_update_; + sim_time_us_ += ticks_per_update_; + } + else { + sim_time_us_ = clock()->nowNanos() / 1000; } - sim_time_us_ = clock()->nowNanos() / 1000; } //update sensors in PX4 stack @@ -117,14 +119,28 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) return; - //auto now = clock()->nowNanos() / 1000; + auto now = clock()->nowNanos() / 1000; + if (last_hil_sensor_time_ != 0 && last_hil_sensor_time_ + ticks_per_update_ > now) + { + // then update() is being called too often, so we just skip this one. + // TODO: I think this needs to be aware of AirSim ClockSpeed...but perhasp clock() has already taken that into account? + return; + } + + if (lock_step_enabled_) { + if (last_hil_sensor_time_ + 100000 < now) { + // if 100 ms passes then something is terribly wrong, reset lockstep mode + lock_step_enabled_ = false; + addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); + } + + if (!received_actuator_controls_) { + // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. + return; + } + } - //if (last_hil_sensor_time_ != 0 && last_hil_sensor_time_ + ticks_per_update_ > now) - //{ - // // then update() is being called too often, so we just skip this one. - // // TODO: I think this needs to be aware of AirSim ClockSpeed... - // // return; - //} + last_hil_sensor_time_ = now; advanceTime(); @@ -1511,7 +1527,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase // if the timestamps match then it means we are in lockstep mode. if (!lock_step_enabled_) { // && (HilActuatorControlsMessage.flags & 0x1)) // todo: enable this check when this flag is widely available... - if (hil_sensor_clock_ == HilActuatorControlsMessage.time_usec) { + if (getSimTime() == HilActuatorControlsMessage.time_usec) { addStatusMessage("Enabling lockstep mode"); lock_step_enabled_ = true; } @@ -1569,25 +1585,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (!is_simulation_mode_) throw std::logic_error("Attempt to send simulated sensor messages while not in simulation mode"); - auto now = getSimTime(); - if (lock_step_enabled_) { - if (last_hil_sensor_time_ + 100000 < now) { - // if 100 ms passes then something is terribly wrong, reset lockstep mode - lock_step_enabled_ = false; - addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); - } - - if (!received_actuator_controls_) { - // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. - return; - } - } - - hil_sensor_clock_ = now; - mavlinkcom::MavLinkHilSensor hil_sensor; - last_hil_sensor_time_ = now; - hil_sensor.time_usec = hil_sensor_clock_; + hil_sensor.time_usec = getSimTime(); hil_sensor.xacc = acceleration.x(); hil_sensor.yacc = acceleration.y(); @@ -1679,7 +1678,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase throw std::logic_error("Attempt to send simulated GPS messages while not in simulation mode"); mavlinkcom::MavLinkHilGps hil_gps; - hil_gps.time_usec = hil_sensor_clock_; + hil_gps.time_usec = getSimTime(); hil_gps.lat = static_cast(geo_point.latitude * 1E7); hil_gps.lon = static_cast(geo_point.longitude * 1E7); hil_gps.alt = static_cast(geo_point.altitude * 1000); @@ -1723,7 +1722,6 @@ class MavLinkMultirotorApi : public MultirotorApiBase last_sys_time_ = 0; last_gps_time_ = 0; last_hil_sensor_time_ = 0; - hil_sensor_clock_ = 0; is_api_control_enabled_ = false; thrust_controller_ = PidController(); Utils::setValue(rotor_controls_, 0.0f); @@ -1826,7 +1824,6 @@ class MavLinkMultirotorApi : public MultirotorApiBase unsigned long long sim_time_us_ = 0; uint64_t last_gps_time_ = 0; uint64_t last_hil_sensor_time_ = 0; - uint64_t hil_sensor_clock_ = 0; //additional variables required for MultirotorApiBase implementation //this is optional for methods that might not use vehicle commands From 1f3368b288c40e9585f487a730311c537f560714 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 00:49:37 -0700 Subject: [PATCH 03/37] add mavlink 2 support --- MavLinkCom/include/MavLinkLog.hpp | 4 +++ MavLinkCom/src/MavLinkLog.cpp | 46 +++++++++++++++++++++++++++---- 2 files changed, 44 insertions(+), 6 deletions(-) diff --git a/MavLinkCom/include/MavLinkLog.hpp b/MavLinkCom/include/MavLinkLog.hpp index 63a51f54b2..3c22f95b84 100644 --- a/MavLinkCom/include/MavLinkLog.hpp +++ b/MavLinkCom/include/MavLinkLog.hpp @@ -7,8 +7,11 @@ #include #include #include +#include #include "MavLinkMessageBase.hpp" +#define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol + namespace mavlinkcom { // This abstract class defines the interface for logging MavLinkMessages. @@ -27,6 +30,7 @@ namespace mavlinkcom bool reading_; bool writing_; bool json_; + std::mutex log_lock_; public: MavLinkFileLog(); virtual ~MavLinkFileLog(); diff --git a/MavLinkCom/src/MavLinkLog.cpp b/MavLinkCom/src/MavLinkLog.cpp index 9ee7d6dc01..9c8fb97c12 100644 --- a/MavLinkCom/src/MavLinkLog.cpp +++ b/MavLinkCom/src/MavLinkLog.cpp @@ -8,6 +8,8 @@ using namespace mavlinkcom; using namespace mavlink_utils; +#define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol + uint64_t MavLinkFileLog::getTimeStamp() { return std::chrono::duration_cast(std::chrono::high_resolution_clock::now().time_since_epoch()).count(); @@ -101,7 +103,10 @@ void MavLinkFileLog::write(const mavlinkcom::MavLinkMessage& msg, uint64_t times if (strongTypedMsg != nullptr) { strongTypedMsg->timestamp = timestamp; std::string line = strongTypedMsg->toJSon(); - fprintf(ptr_, " %s\n", line.c_str()); + { + std::lock_guard lock(log_lock_); + fprintf(ptr_, " %s\n", line.c_str()); + } delete strongTypedMsg; } } @@ -112,14 +117,29 @@ void MavLinkFileLog::write(const mavlinkcom::MavLinkMessage& msg, uint64_t times // for compatibility with QGroundControl we have to save the time field in big endian. // todo: mavlink2 support? timestamp = FlipEndianness(timestamp); + + std::lock_guard lock(log_lock_); fwrite(×tamp, sizeof(uint64_t), 1, ptr_); fwrite(&msg.magic, 1, 1, ptr_); fwrite(&msg.len, 1, 1, ptr_); fwrite(&msg.seq, 1, 1, ptr_); fwrite(&msg.sysid, 1, 1, ptr_); fwrite(&msg.compid, 1, 1, ptr_); - uint8_t msgid = msg.msgid & 0xff; // truncate to mavlink1 msgid - fwrite(&msgid, 1, 1, ptr_); + + if (msg.magic == MAVLINK_STX_MAVLINK1) { + uint8_t msgid = msg.msgid & 0xff; // truncate to mavlink 2 msgid + fwrite(&msgid, 1, 1, ptr_); + } + else { + // 24 bits. + uint8_t msgid = msg.msgid & 0xFF; + fwrite(&msgid, 1, 1, ptr_); + msgid = (msg.msgid >> 8) & 0xFF; + fwrite(&msgid, 1, 1, ptr_); + msgid = (msg.msgid >> 16) & 0xFF; + fwrite(&msgid, 1, 1, ptr_); + } + fwrite(&msg.payload64, 1, msg.len, ptr_); fwrite(&msg.checksum, sizeof(uint16_t), 1, ptr_); } @@ -162,9 +182,23 @@ bool MavLinkFileLog::read(mavlinkcom::MavLinkMessage& msg, uint64_t& timestamp) if (s == 0) { return false; } - uint8_t msgid = 0; - s = fread(&msgid, 1, 1, ptr_); - msg.msgid = msgid; + + if (msg.magic == MAVLINK_STX_MAVLINK1) { + uint8_t msgid = 0; + s = fread(&msgid, 1, 1, ptr_); + msg.msgid = msgid; + } + else { + // 24 bits. + uint8_t msgid = 0; + s = fread(&msgid, 1, 1, ptr_); + msg.msgid = msgid; + s = fread(&msgid, 1, 1, ptr_); + msg.msgid |= (msgid << 8); + s = fread(&msgid, 1, 1, ptr_); + msg.msgid |= (msgid << 16); + } + if (s < 1) { return false; } From 1c15604a3e2b14cb19fefcd6d015caca8d74e8d1 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 10:34:51 -0700 Subject: [PATCH 04/37] make test terminate when it finds a problem, so you can capture the related logs. --- PythonClient/multirotor/stability_test.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/PythonClient/multirotor/stability_test.py b/PythonClient/multirotor/stability_test.py index cf1530194f..9612892dff 100644 --- a/PythonClient/multirotor/stability_test.py +++ b/PythonClient/multirotor/stability_test.py @@ -38,7 +38,9 @@ def is_unstable(self, amount): print("{}: min={}, max={}, mean={}, stddev={}".format(self.name, minimum, maximum, mean, stddev)) return (maximum - minimum) > amount +iteration = 0 while True: + iteration += 1 x = Numbers("x") y = Numbers("y") z = Numbers("z") @@ -51,9 +53,9 @@ def is_unstable(self, amount): client.takeoffAsync().join() time.sleep(1) - # fly for a minute + # fly for 2 minutes start = time.time() - while time.time() < start + 20: + while time.time() < start + 120: state = client.getMultirotorState() x_val = state.kinematics_estimated.position.x_val y_val = state.kinematics_estimated.position.y_val @@ -71,12 +73,14 @@ def is_unstable(self, amount): client.armDisarm(False) # more than 50 centimeter drift is unacceptable. + print("Results for iteration {}".format(iteration)) a = x.is_unstable(0.5) b = y.is_unstable(0.5) c = z.is_unstable(0.5) if a or b or c: play_sound(os.path.join(script_dir, "Error.wav")) + break time.sleep(5) From 006d4e2ac54f31e33ed595c6cdfbe2d5483027fd Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 15:41:46 -0700 Subject: [PATCH 05/37] Merge settings improvements from PR 3546 --- AirLib/include/common/AirSimSettings.hpp | 151 ++++++------------ .../common/common_utils/FileSystem.hpp | 3 +- AirLib/include/physics/PhysicsEngineBase.hpp | 2 +- AirLib/include/sensors/SensorBase.hpp | 2 +- AirLib/include/sensors/SensorFactory.hpp | 21 ++- .../sensors/barometer/BarometerSimple.hpp | 4 +- .../barometer/BarometerSimpleParams.hpp | 15 +- .../sensors/distance/DistanceSimple.hpp | 2 +- .../sensors/distance/DistanceSimpleParams.hpp | 25 +-- .../include/sensors/gps/GpsSimpleParams.hpp | 13 +- .../include/sensors/imu/ImuSimpleParams.hpp | 22 ++- .../magnetometer/MagnetometerSimpleParams.hpp | 10 +- .../include/vehicles/car/api/CarApiBase.hpp | 8 +- .../vehicles/multirotor/MultiRotorParams.hpp | 8 +- .../mavlink/MavLinkMultirotorApi.hpp | 29 +++- MavLinkCom/include/MavLinkMessageBase.hpp | 23 +-- MavLinkCom/src/MavLinkMessageBase.cpp | 6 +- MavLinkCom/src/impl/MavLinkConnectionImpl.cpp | 3 +- 18 files changed, 185 insertions(+), 162 deletions(-) diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index fd3b663d1b..b0b3245d18 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -193,7 +193,8 @@ struct AirSimSettings { struct SensorSetting { SensorBase::SensorType sensor_type; std::string sensor_name; - bool enabled; + bool enabled = true; + Settings settings; // imported json data that needs to be parsed by specific sensors. }; struct BarometerSetting : SensorSetting { @@ -209,15 +210,10 @@ struct AirSimSettings { }; struct DistanceSetting : SensorSetting { - // shared defaults - real_T min_distance = 20.0f / 100; //m - real_T max_distance = 4000.0f / 100; //m - Vector3r position = VectorMath::nanVector(); - Rotation rotation = Rotation::nanRotation(); - bool draw_debug_points = false; }; struct LidarSetting : SensorSetting { + // TODO: move this to use the "Settings settings" instead. // shared defaults uint number_of_channels = 16; @@ -257,7 +253,7 @@ struct AirSimSettings { Rotation rotation = Rotation::nanRotation(); std::map cameras; - std::map> sensors; + std::map> sensors; RCSettings rc; }; @@ -375,7 +371,7 @@ struct AirSimSettings { CameraDirectorSetting camera_director; float speed_unit_factor = 1.0f; std::string speed_unit_label = "m\\s"; - std::map> sensor_defaults; + std::map> sensor_defaults; Vector3r wind = Vector3r::Zero(); std::string settings_text_ = ""; @@ -411,7 +407,7 @@ struct AirSimSettings { loadPawnPaths(settings_json, pawn_paths); loadOtherSettings(settings_json); loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults); - loadVehicleSettings(simmode_name, settings_json, vehicles); + loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults); //this should be done last because it depends on vehicles (and/or their type) we have loadRecordingSetting(settings_json); @@ -466,6 +462,19 @@ struct AirSimSettings { return it->second.get(); } + static Vector3r createVectorSetting(const Settings& settings_json, const Vector3r& default_vec) + { + return Vector3r(settings_json.getFloat("X", default_vec.x()), + settings_json.getFloat("Y", default_vec.y()), + settings_json.getFloat("Z", default_vec.z())); + } + static Rotation createRotationSetting(const Settings& settings_json, const Rotation& default_rot) + { + return Rotation(settings_json.getFloat("Yaw", default_rot.yaw), + settings_json.getFloat("Pitch", default_rot.pitch), + settings_json.getFloat("Roll", default_rot.roll)); + } + private: void checkSettingsVersion(const Settings& settings_json) { @@ -756,21 +765,9 @@ struct AirSimSettings { return vehicle_setting_p; } - static Vector3r createVectorSetting(const Settings& settings_json, const Vector3r& default_vec) - { - return Vector3r(settings_json.getFloat("X", default_vec.x()), - settings_json.getFloat("Y", default_vec.y()), - settings_json.getFloat("Z", default_vec.z())); - } - static Rotation createRotationSetting(const Settings& settings_json, const Rotation& default_rot) - { - return Rotation(settings_json.getFloat("Yaw", default_rot.yaw), - settings_json.getFloat("Pitch", default_rot.pitch), - settings_json.getFloat("Roll", default_rot.roll)); - } - static std::unique_ptr createVehicleSetting(const std::string& simmode_name, const Settings& settings_json, - const std::string vehicle_name) + const std::string vehicle_name, + std::map>& sensor_defaults) { auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", "")); @@ -814,7 +811,7 @@ struct AirSimSettings { vehicle_setting->rotation = createRotationSetting(settings_json, vehicle_setting->rotation); loadCameraSettings(settings_json, vehicle_setting->cameras); - loadSensorSettings(settings_json, "Sensors", vehicle_setting->sensors); + loadSensorSettings(settings_json, "Sensors", vehicle_setting->sensors, sensor_defaults); return vehicle_setting; } @@ -856,7 +853,8 @@ struct AirSimSettings { } static void loadVehicleSettings(const std::string& simmode_name, const Settings& settings_json, - std::map>& vehicles) + std::map>& vehicles, + std::map>& sensor_defaults) { initializeVehicleSettings(simmode_name, vehicles); @@ -872,7 +870,7 @@ struct AirSimSettings { for (const auto& key : keys) { msr::airlib::Settings child; vehicles_child.getChild(key, child); - vehicles[key] = createVehicleSetting(simmode_name, child, key); + vehicles[key] = createVehicleSetting(simmode_name, child, key, sensor_defaults); } } } @@ -950,7 +948,7 @@ struct AirSimSettings { static void initializeNoiseSettings(std::map& noise_settings) { - int image_count = Utils::toNumeric(ImageType::Count); + const int image_count = Utils::toNumeric(ImageType::Count); noise_settings.clear(); for (int i = -1; i < image_count; ++i) noise_settings[i] = NoiseSetting(); @@ -1204,48 +1202,6 @@ struct AirSimSettings { clock_speed = settings_json.getFloat("ClockSpeed", 1.0f); } - static void initializeBarometerSetting(BarometerSetting& barometer_setting, const Settings& settings_json) - { - unused(barometer_setting); - unused(settings_json); - - //TODO: set from json as needed - } - - static void initializeImuSetting(ImuSetting& imu_setting, const Settings& settings_json) - { - unused(imu_setting); - unused(settings_json); - - //TODO: set from json as needed - } - - static void initializeGpsSetting(GpsSetting& gps_setting, const Settings& settings_json) - { - unused(gps_setting); - unused(settings_json); - - //TODO: set from json as needed - } - - static void initializeMagnetometerSetting(MagnetometerSetting& magnetometer_setting, const Settings& settings_json) - { - unused(magnetometer_setting); - unused(settings_json); - - //TODO: set from json as needed - } - - static void initializeDistanceSetting(DistanceSetting& distance_setting, const Settings& settings_json) - { - distance_setting.min_distance = settings_json.getFloat("MinDistance", distance_setting.min_distance); - distance_setting.max_distance = settings_json.getFloat("MaxDistance", distance_setting.max_distance); - distance_setting.draw_debug_points = settings_json.getBool("DrawDebugPoints", distance_setting.draw_debug_points); - - distance_setting.position = createVectorSetting(settings_json, distance_setting.position); - distance_setting.rotation = createRotationSetting(settings_json, distance_setting.rotation); - } - static void initializeLidarSetting(LidarSetting& lidar_setting, const Settings& settings_json) { lidar_setting.number_of_channels = settings_json.getInt("NumberOfChannels", lidar_setting.number_of_channels); @@ -1264,30 +1220,30 @@ struct AirSimSettings { lidar_setting.rotation = createRotationSetting(settings_json, lidar_setting.rotation); } - static std::unique_ptr createSensorSetting( + static std::shared_ptr createSensorSetting( SensorBase::SensorType sensor_type, const std::string& sensor_name, bool enabled) { - std::unique_ptr sensor_setting; + std::shared_ptr sensor_setting; switch (sensor_type) { case SensorBase::SensorType::Barometer: - sensor_setting = std::unique_ptr(new BarometerSetting()); + sensor_setting = std::shared_ptr(new BarometerSetting()); break; case SensorBase::SensorType::Imu: - sensor_setting = std::unique_ptr(new ImuSetting()); + sensor_setting = std::shared_ptr(new ImuSetting()); break; case SensorBase::SensorType::Gps: - sensor_setting = std::unique_ptr(new GpsSetting()); + sensor_setting = std::shared_ptr(new GpsSetting()); break; case SensorBase::SensorType::Magnetometer: - sensor_setting = std::unique_ptr(new MagnetometerSetting()); + sensor_setting = std::shared_ptr(new MagnetometerSetting()); break; case SensorBase::SensorType::Distance: - sensor_setting = std::unique_ptr(new DistanceSetting()); + sensor_setting = std::shared_ptr(new DistanceSetting()); break; case SensorBase::SensorType::Lidar: - sensor_setting = std::unique_ptr(new LidarSetting()); + sensor_setting = std::shared_ptr(new LidarSetting()); break; default: throw std::invalid_argument("Unexpected sensor type"); @@ -1303,35 +1259,32 @@ struct AirSimSettings { static void initializeSensorSetting(SensorSetting* sensor_setting, const Settings& settings_json) { sensor_setting->enabled = settings_json.getBool("Enabled", sensor_setting->enabled); + + // pass the json Settings property bag through to the specific sensor params object where it is + // extracted there. This way default values can be kept in one place. For example, see the + // BarometerSimpleParams::initializeFromSettings method. + sensor_setting->settings = settings_json; + // TODO: delete this when we move initializeLidarSetting to LidarSimpleParams.hpp switch (sensor_setting->sensor_type) { - case SensorBase::SensorType::Barometer: - initializeBarometerSetting(*static_cast(sensor_setting), settings_json); - break; - case SensorBase::SensorType::Imu: - initializeImuSetting(*static_cast(sensor_setting), settings_json); - break; - case SensorBase::SensorType::Gps: - initializeGpsSetting(*static_cast(sensor_setting), settings_json); - break; - case SensorBase::SensorType::Magnetometer: - initializeMagnetometerSetting(*static_cast(sensor_setting), settings_json); - break; - case SensorBase::SensorType::Distance: - initializeDistanceSetting(*static_cast(sensor_setting), settings_json); - break; case SensorBase::SensorType::Lidar: initializeLidarSetting(*static_cast(sensor_setting), settings_json); break; - default: - throw std::invalid_argument("Unexpected sensor type"); } } // creates and intializes sensor settings from json static void loadSensorSettings( const Settings& settings_json, const std::string& collectionName, - std::map>& sensors) + std::map>& sensors, + std::map>& sensor_defaults) + { + // start with defaults. + for (auto ptr = sensor_defaults.begin(); ptr != sensor_defaults.end(); ptr++) { + auto key = ptr->first; + sensors[key] = sensor_defaults[key]; + } + msr::airlib::Settings sensors_child; if (settings_json.getChild(collectionName, sensors_child)) { std::vector keys; @@ -1352,7 +1305,7 @@ struct AirSimSettings { // creates default sensor list when none specified in json static void createDefaultSensorSettings(const std::string& simmode_name, - std::map>& sensors) + std::map>& sensors) { if (simmode_name == kSimModeTypeMultirotor) { sensors["imu"] = createSensorSetting(SensorBase::SensorType::Imu, "imu", true); @@ -1371,11 +1324,11 @@ struct AirSimSettings { // loads or creates default sensor list static void loadDefaultSensorSettings(const std::string& simmode_name, const Settings& settings_json, - std::map>& sensors) + std::map>& sensors) { msr::airlib::Settings sensors_child; if (settings_json.getChild("DefaultSensors", sensors_child)) - loadSensorSettings(settings_json, "DefaultSensors", sensors); + loadSensorSettings(settings_json, "DefaultSensors", sensors, sensors); else createDefaultSensorSettings(simmode_name, sensors); } diff --git a/AirLib/include/common/common_utils/FileSystem.hpp b/AirLib/include/common/common_utils/FileSystem.hpp index d6e7fba778..2d3ae8f994 100644 --- a/AirLib/include/common/common_utils/FileSystem.hpp +++ b/AirLib/include/common/common_utils/FileSystem.hpp @@ -104,8 +104,7 @@ class FileSystem break; } if (i < 0) return ""; - auto ui = static_cast(i); - return str.substr(ui, len - ui); + return str.substr(i, len - i); } static std::string getLogFolderPath(bool folder_timestamp, const std::string& parent = "") diff --git a/AirLib/include/physics/PhysicsEngineBase.hpp b/AirLib/include/physics/PhysicsEngineBase.hpp index 2dff630ab4..a8b09f28ba 100644 --- a/AirLib/include/physics/PhysicsEngineBase.hpp +++ b/AirLib/include/physics/PhysicsEngineBase.hpp @@ -44,7 +44,7 @@ class PhysicsEngineBase : public UpdatableObject { virtual void erase_remove(TUpdatableObjectPtr obj) { members_.erase(std::remove(members_.begin(), members_.end(), obj), members_.end()); } - virtual void setWind(const Vector3r& wind) {}; + virtual void setWind(const Vector3r& wind) { unused(wind); }; private: MembersContainer members_; diff --git a/AirLib/include/sensors/SensorBase.hpp b/AirLib/include/sensors/SensorBase.hpp index 765cfabcf1..44bd8531aa 100644 --- a/AirLib/include/sensors/SensorBase.hpp +++ b/AirLib/include/sensors/SensorBase.hpp @@ -59,7 +59,7 @@ class SensorBase : public UpdatableObject { private: //ground truth can be shared between many sensors - GroundTruth ground_truth_; + GroundTruth ground_truth_ = { nullptr, nullptr }; std::string name_ = ""; }; diff --git a/AirLib/include/sensors/SensorFactory.hpp b/AirLib/include/sensors/SensorFactory.hpp index ed69b4abb7..0c93412ec5 100644 --- a/AirLib/include/sensors/SensorFactory.hpp +++ b/AirLib/include/sensors/SensorFactory.hpp @@ -19,18 +19,18 @@ class SensorFactory { public: // creates one sensor from settings - virtual std::unique_ptr createSensorFromSettings( + virtual std::shared_ptr createSensorFromSettings( const AirSimSettings::SensorSetting* sensor_setting) const { switch (sensor_setting->sensor_type) { case SensorBase::SensorType::Imu: - return std::unique_ptr(new ImuSimple(*static_cast(sensor_setting))); + return std::shared_ptr(new ImuSimple(*static_cast(sensor_setting))); case SensorBase::SensorType::Magnetometer: - return std::unique_ptr(new MagnetometerSimple(*static_cast(sensor_setting))); + return std::shared_ptr(new MagnetometerSimple(*static_cast(sensor_setting))); case SensorBase::SensorType::Gps: - return std::unique_ptr(new GpsSimple(*static_cast(sensor_setting))); + return std::shared_ptr(new GpsSimple(*static_cast(sensor_setting))); case SensorBase::SensorType::Barometer: - return std::unique_ptr(new BarometerSimple(*static_cast(sensor_setting))); + return std::shared_ptr(new BarometerSimple(*static_cast(sensor_setting))); default: throw new std::invalid_argument("Unexpected sensor type"); } @@ -38,9 +38,9 @@ class SensorFactory { // creates sensor-collection virtual void createSensorsFromSettings( - const std::map>& sensors_settings, + const std::map>& sensors_settings, SensorCollection& sensors, - vector>& sensor_storage) const + vector>& sensor_storage) const { for (const auto& sensor_setting_pair : sensors_settings) { const AirSimSettings::SensorSetting* sensor_setting = sensor_setting_pair.second.get(); @@ -49,11 +49,10 @@ class SensorFactory { if (sensor_setting == nullptr || !sensor_setting->enabled) continue; - std::unique_ptr sensor = createSensorFromSettings(sensor_setting); + std::shared_ptr sensor = createSensorFromSettings(sensor_setting); if (sensor) { - SensorBase* sensor_temp = sensor.get(); - sensor_storage.push_back(std::move(sensor)); - sensors.insert(sensor_temp, sensor_setting->sensor_type); + sensor_storage.push_back(sensor); + sensors.insert(sensor.get(), sensor_setting->sensor_type); } } } diff --git a/AirLib/include/sensors/barometer/BarometerSimple.hpp b/AirLib/include/sensors/barometer/BarometerSimple.hpp index 399eb86cd7..515ae21e57 100644 --- a/AirLib/include/sensors/barometer/BarometerSimple.hpp +++ b/AirLib/include/sensors/barometer/BarometerSimple.hpp @@ -27,7 +27,7 @@ class BarometerSimple : public BarometerBase { //GM process that would do random walk for pressure factor pressure_factor_.initialize(params_.pressure_factor_tau, params_.pressure_factor_sigma, 0); - uncorrelated_noise_ = RandomGeneratorGausianR(0.0f, params_.unnorrelated_noise_sigma); + uncorrelated_noise_ = RandomGeneratorGausianR(0.0f, params_.uncorrelated_noise_sigma); //correlated_noise_.initialize(params_.correlated_noise_tau, params_.correlated_noise_sigma, 0.0f); //initialize frequency limiter @@ -76,7 +76,7 @@ class BarometerSimple : public BarometerBase { auto altitude = ground_truth.environment->getState().geo_point.altitude; auto pressure = EarthUtils::getStandardPressure(altitude); - //add drift in pressure, about 10m change per hour + //add drift in pressure, about 10m change per hour using default settings. pressure_factor_.update(); pressure += pressure * pressure_factor_.getOutput(); diff --git a/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp b/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp index 62082342dd..45b4f6601c 100644 --- a/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp +++ b/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp @@ -5,6 +5,7 @@ #define msr_airlib_BarometerSimpleParams_hpp #include "common/Common.hpp" +#include "common/AirSimSettings.hpp" namespace msr { namespace airlib { @@ -33,14 +34,14 @@ struct BarometerSimpleParams { real_T correlated_noise_sigma = 0.27f; real_T correlated_noise_tau = 0.87f; - real_T unnorrelated_noise_sigma = 0.24f; + real_T uncorrelated_noise_sigma = 0.24f; */ //Experiments for MEAS MS56112 sensor shows 0.021mbar, datasheet has resoultion of 0.027mbar @ 1024 //http://www.te.com/commerce/DocumentDelivery/DDEController?Action=srchrtrv&DocNm=MS5611-01BA03&DocType=Data+Sheet&DocLang=English - real_T unnorrelated_noise_sigma = 0.027f * 100; + real_T uncorrelated_noise_sigma = 0.027f * 100; //jMavSim uses below - //real_T unnorrelated_noise_sigma = 0.1f; + //real_T uncorrelated_noise_sigma = 0.1f; //see PX4 param reference for EKF: https://dev.px4.io/en/advanced/parameter_reference.html real_T update_latency = 0.0f; //sec @@ -49,7 +50,13 @@ struct BarometerSimpleParams { void initializeFromSettings(const AirSimSettings::BarometerSetting& settings) { - unused(settings); + const auto& json = settings.settings; + pressure_factor_sigma = json.getFloat("PressureFactorSigma", pressure_factor_sigma); + pressure_factor_tau = json.getFloat("PressureFactorTau", pressure_factor_tau); + uncorrelated_noise_sigma = json.getFloat("UncorrelatedNoiseSigma", uncorrelated_noise_sigma); + update_latency = json.getFloat("UpdateLatency", update_latency); + update_frequency = json.getFloat("UpdateFrequency", update_frequency); + startup_delay = json.getFloat("StartupDelay", startup_delay); } }; diff --git a/AirLib/include/sensors/distance/DistanceSimple.hpp b/AirLib/include/sensors/distance/DistanceSimple.hpp index 45adcdddc3..63de52c15a 100644 --- a/AirLib/include/sensors/distance/DistanceSimple.hpp +++ b/AirLib/include/sensors/distance/DistanceSimple.hpp @@ -22,7 +22,7 @@ class DistanceSimple : public DistanceBase { // initialize params params_.initializeFromSettings(setting); - uncorrelated_noise_ = RandomGeneratorGausianR(0.0f, params_.unnorrelated_noise_sigma); + uncorrelated_noise_ = RandomGeneratorGausianR(0.0f, params_.uncorrelated_noise_sigma); //correlated_noise_.initialize(params_.correlated_noise_tau, params_.correlated_noise_sigma, 0.0f); diff --git a/AirLib/include/sensors/distance/DistanceSimpleParams.hpp b/AirLib/include/sensors/distance/DistanceSimpleParams.hpp index 3af863297e..f96051b052 100644 --- a/AirLib/include/sensors/distance/DistanceSimpleParams.hpp +++ b/AirLib/include/sensors/distance/DistanceSimpleParams.hpp @@ -31,13 +31,13 @@ struct DistanceSimpleParams { real_T correlated_noise_sigma = 0.27f; real_T correlated_noise_tau = 0.87f; - real_T unnorrelated_noise_sigma = 0.24f; + real_T uncorrelated_noise_sigma = 0.24f; */ //TODO: update sigma based on documentation, maybe as a function increasing with measured distance - real_T unnorrelated_noise_sigma = 0.002f * 100; + real_T uncorrelated_noise_sigma = 0.002f * 100; //jMavSim uses below - //real_T unnorrelated_noise_sigma = 0.1f; + //real_T uncorrelated_noise_sigma = 0.1f; //see PX4 param reference for EKF: https://dev.px4.io/en/advanced/parameter_reference.html real_T update_latency = 0.0f; //sec @@ -46,14 +46,17 @@ struct DistanceSimpleParams { void initializeFromSettings(const AirSimSettings::DistanceSetting& settings) { - std::string simmode_name = AirSimSettings::singleton().simmode_name; + const auto& settings_json = settings.settings; + min_distance = settings_json.getFloat("MinDistance", min_distance); + max_distance = settings_json.getFloat("MaxDistance", max_distance); + draw_debug_points = settings_json.getBool("DrawDebugPoints", draw_debug_points); - min_distance = settings.min_distance; - max_distance = settings.max_distance; + auto position = AirSimSettings::createVectorSetting(settings_json, VectorMath::nanVector()); + auto rotation = AirSimSettings::createRotationSetting(settings_json, AirSimSettings::Rotation::nanRotation()); - draw_debug_points = settings.draw_debug_points; + std::string simmode_name = AirSimSettings::singleton().simmode_name; - relative_pose.position = settings.position; + relative_pose.position = position; if (std::isnan(relative_pose.position.x())) relative_pose.position.x() = 0; if (std::isnan(relative_pose.position.y())) @@ -66,9 +69,9 @@ struct DistanceSimpleParams { } float pitch, roll, yaw; - pitch = !std::isnan(settings.rotation.pitch) ? settings.rotation.pitch : 0; - roll = !std::isnan(settings.rotation.roll) ? settings.rotation.roll : 0; - yaw = !std::isnan(settings.rotation.yaw) ? settings.rotation.yaw : 0; + pitch = !std::isnan(rotation.pitch) ? rotation.pitch : 0; + roll = !std::isnan(rotation.roll) ? rotation.roll : 0; + yaw = !std::isnan(rotation.yaw) ? rotation.yaw : 0; relative_pose.orientation = VectorMath::toQuaternion( Utils::degreesToRadians(pitch), //pitch - rotation around Y axis Utils::degreesToRadians(roll), //roll - rotation around X axis diff --git a/AirLib/include/sensors/gps/GpsSimpleParams.hpp b/AirLib/include/sensors/gps/GpsSimpleParams.hpp index 43e38277a5..18e9949dd8 100644 --- a/AirLib/include/sensors/gps/GpsSimpleParams.hpp +++ b/AirLib/include/sensors/gps/GpsSimpleParams.hpp @@ -21,7 +21,18 @@ struct GpsSimpleParams { void initializeFromSettings(const AirSimSettings::GpsSetting& settings) { - unused(settings); + const auto& json = settings.settings; + eph_time_constant = json.getFloat("EPH_TimeConstant", eph_time_constant); + epv_time_constant = json.getFloat("EPV_TimeConstant", epv_time_constant); + eph_initial = json.getFloat("EphInitial", eph_initial); + epv_initial = json.getFloat("EpvInitial", epv_initial); + eph_final = json.getFloat("EphFinal", eph_final); + epv_final = json.getFloat("EpvFinal", epv_final); + eph_min_3d = json.getFloat("EphMin3d", eph_min_3d); + eph_min_2d = json.getFloat("EphMin2d", eph_min_2d); + update_latency = json.getFloat("UpdateLatency", update_latency); + update_frequency = json.getFloat("UpdateFrequency", update_frequency); + startup_delay = json.getFloat("StartupDelay", startup_delay); } }; diff --git a/AirLib/include/sensors/imu/ImuSimpleParams.hpp b/AirLib/include/sensors/imu/ImuSimpleParams.hpp index 6cbe166a4e..8dfb7529a8 100644 --- a/AirLib/include/sensors/imu/ImuSimpleParams.hpp +++ b/AirLib/include/sensors/imu/ImuSimpleParams.hpp @@ -25,7 +25,7 @@ struct ImuSimpleParams { For Allan Variance/Deviation plots see http://www.invensense.com/wp-content/uploads/2015/02/MPU-3300-Datasheet.pdf */ struct Gyroscope { - //angule random walk (ARW) + //angular random walk (ARW) real_T arw = 0.30f / sqrt(3600.0f) * M_PIf / 180; //deg/sqrt(hour) converted to rad/sqrt(sec) //Bias Stability (tau = 500s) real_T tau = 500; @@ -46,7 +46,25 @@ struct ImuSimpleParams { void initializeFromSettings(const AirSimSettings::ImuSetting& settings) { - unused(settings); + const auto& json = settings.settings; + float arw = json.getFloat("AngularRandomWalk", Utils::nan()); + if (!std::isnan(arw)) { + gyro.arw = arw / sqrt(3600.0f) * M_PIf / 180; // //deg/sqrt(hour) converted to rad/sqrt(sec) + } + gyro.tau = json.getFloat("GyroBiasStabilityTau", gyro.tau); + float bias_stability = json.getFloat("GyroBiasStability", Utils::nan()); + if (!std::isnan(bias_stability)) { + gyro.bias_stability = bias_stability / 3600 * M_PIf / 180; //deg/hr converted to rad/sec + } + auto vrw = json.getFloat("VelocityRandomWalk", Utils::nan()); + if (!std::isnan(vrw)) { + accel.vrw = vrw * EarthUtils::Gravity / 1.0E3f; //mg converted to m/s^2 + } + accel.tau = json.getFloat("AccelBiasStabilityTau", accel.tau); + bias_stability = json.getFloat("AccelBiasStability", Utils::nan()); + if (!std::isnan(bias_stability)) { + accel.bias_stability = bias_stability * 1E-6f * 9.80665f; //ug converted to m/s^2 + } } }; diff --git a/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp b/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp index 652cb3257c..b0a7aab325 100644 --- a/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp +++ b/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp @@ -34,7 +34,15 @@ struct MagnetometerSimpleParams { void initializeFromSettings(const AirSimSettings::MagnetometerSetting& settings) { - unused(settings); + const auto& json = settings.settings; + float noise = json.getFloat("NoiseSigma", noise_sigma.x()); + noise_sigma = Vector3r(noise, noise, noise); + scale_factor = json.getFloat("ScaleFactor", scale_factor); + float bias = json.getFloat("NoiseBias", noise_bias.x()); + noise_bias = Vector3r(bias, bias, bias); + update_latency = json.getFloat("UpdateLatency", update_latency); + update_frequency = json.getFloat("UpdateFrequency", update_frequency); + startup_delay = json.getFloat("StartupDelay", startup_delay); } }; diff --git a/AirLib/include/vehicles/car/api/CarApiBase.hpp b/AirLib/include/vehicles/car/api/CarApiBase.hpp index 3f012b51e7..2cbbb1cfb9 100644 --- a/AirLib/include/vehicles/car/api/CarApiBase.hpp +++ b/AirLib/include/vehicles/car/api/CarApiBase.hpp @@ -131,11 +131,7 @@ class CarApiBase : public VehicleApiBase { void addSensorsFromSettings(const AirSimSettings::VehicleSetting* vehicle_setting) { - // use sensors from vehicle settings; if empty list, use default sensors. - // note that the vehicle settings completely override the default sensor "list"; - // there is no piecemeal add/remove/update per sensor. - const std::map>& sensor_settings - = vehicle_setting->sensors.size() > 0 ? vehicle_setting->sensors : AirSimSettings::AirSimSettings::singleton().sensor_defaults; + const auto& sensor_settings = vehicle_setting->sensors; sensor_factory_->createSensorsFromSettings(sensor_settings, sensors_, sensor_storage_); } @@ -149,7 +145,7 @@ class CarApiBase : public VehicleApiBase { std::shared_ptr sensor_factory_; SensorCollection sensors_; //maintains sensor type indexed collection of sensors - vector> sensor_storage_; //RAII for created sensors + vector> sensor_storage_; //RAII for created sensors protected: virtual void resetImplementation() override diff --git a/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp b/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp index f04635e44a..75f24ea1c6 100644 --- a/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp +++ b/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp @@ -85,11 +85,7 @@ class MultiRotorParams { void addSensorsFromSettings(const AirSimSettings::VehicleSetting* vehicle_setting) { - // use sensors from vehicle settings; if empty list, use default sensors. - // note that the vehicle settings completely override the default sensor "list"; - // there is no piecemeal add/remove/update per sensor. - const std::map>& sensor_settings - = vehicle_setting->sensors.size() > 0 ? vehicle_setting->sensors : AirSimSettings::AirSimSettings::singleton().sensor_defaults; + const auto& sensor_settings = vehicle_setting->sensors; getSensorFactory()->createSensorsFromSettings(sensor_settings, sensors_, sensor_storage_); } @@ -412,7 +408,7 @@ class MultiRotorParams { private: Params params_; SensorCollection sensors_; //maintains sensor type indexed collection of sensors - vector> sensor_storage_; //RAII for created sensors + vector> sensor_storage_; //RAII for created sensors }; }} //namespace diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 58f0af295c..b9961cd10e 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -127,6 +127,15 @@ class MavLinkMultirotorApi : public MultirotorApiBase return; } + update_count_++; + if (last_fps_time_ == 0 || last_fps_time_ + 1000000 < now) { + // compute update rate once per second. + update_rate_ = update_count_; + update_count_ = 0; + last_fps_time_ = now; + sendTelemetry(1); + } + if (lock_step_enabled_) { if (last_hil_sensor_time_ + 100000 < now) { // if 100 ms passes then something is terribly wrong, reset lockstep mode @@ -556,7 +565,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase virtual void sendTelemetry(float last_interval = -1) override { - if (logviewer_proxy_ == nullptr || connection_ == nullptr || mav_vehicle_ == nullptr) { + if ((logviewer_proxy_ == nullptr && log_ == nullptr) || connection_ == nullptr || mav_vehicle_ == nullptr) { return; } mavlinkcom::MavLinkTelemetry data; @@ -599,7 +608,17 @@ class MavLinkMultirotorApi : public MultirotorApiBase } data.renderTime = static_cast(last_interval * 1000000);// microseconds - logviewer_proxy_->sendMessage(data); + data.udpateRateHz = update_rate_; + + if (logviewer_proxy_ != nullptr) { + logviewer_proxy_->sendMessage(data); + } + + if (log_ != nullptr) { + mavlinkcom::MavLinkMessage msg; + data.encode(msg); + log_->write(msg); + } } virtual float getCommandPeriod() const override @@ -1722,6 +1741,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase last_sys_time_ = 0; last_gps_time_ = 0; last_hil_sensor_time_ = 0; + update_rate_ = 0; + update_count_ = 0; + last_fps_time_ = 0; is_api_control_enabled_ = false; thrust_controller_ = PidController(); Utils::setValue(rotor_controls_, 0.0f); @@ -1824,6 +1846,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase unsigned long long sim_time_us_ = 0; uint64_t last_gps_time_ = 0; uint64_t last_hil_sensor_time_ = 0; + uint64_t last_fps_time_ = 0; + uint32_t update_count_ = 0; + uint32_t update_rate_ = 0; //additional variables required for MultirotorApiBase implementation //this is optional for methods that might not use vehicle commands diff --git a/MavLinkCom/include/MavLinkMessageBase.hpp b/MavLinkCom/include/MavLinkMessageBase.hpp index e17c09aef5..b49e7d9ef1 100644 --- a/MavLinkCom/include/MavLinkMessageBase.hpp +++ b/MavLinkCom/include/MavLinkMessageBase.hpp @@ -132,15 +132,19 @@ namespace mavlinkcom class MavLinkTelemetry : public MavLinkMessageBase { public: const static uint8_t kMessageId = 204; // in the user range 180-229. - MavLinkTelemetry() : wifiInterfaceName(nullptr) { msgid = kMessageId; } - uint32_t messagesSent; // number of messages sent since the last telemetry message - uint32_t messagesReceived; // number of messages received since the last telemetry message - uint32_t messagesHandled; // number of messages handled since the last telemetry message - uint32_t crcErrors; // # crc errors detected in mavlink stream since the last telemetry message - uint32_t handlerMicroseconds; // total time spent in the handlers in microseconds since the last telemetry message - uint32_t renderTime; // total time spent rendering frames since the last telemetry message - const char* wifiInterfaceName; // the name of the wifi interface we are measuring RSSI on. - int32_t wifiRssi; // if this device is communicating over wifi this is the signal strength. + const static int MessageLength = 8 * 4; + MavLinkTelemetry() { msgid = kMessageId; } + uint32_t messagesSent = 0; // number of messages sent since the last telemetry message + uint32_t messagesReceived = 0; // number of messages received since the last telemetry message + uint32_t messagesHandled = 0; // number of messages handled since the last telemetry message + uint32_t crcErrors = 0; // # crc errors detected in mavlink stream since the last telemetry message + uint32_t handlerMicroseconds = 0; // total time spent in the handlers in microseconds since the last telemetry message + uint32_t renderTime = 0; // total time spent rendering frames since the last telemetry message + int32_t wifiRssi = 0; // if this device is communicating over wifi this is the signal strength. + uint32_t udpateRateHz = 0; // HIL_SENSOR update rate in hertz + + // not serialized + const char* wifiInterfaceName = nullptr; // the name of the wifi interface we are measuring RSSI on. virtual std::string toJSon() { std::ostringstream result; @@ -152,6 +156,7 @@ namespace mavlinkcom result << "\"handlerMicroseconds\":" << this->handlerMicroseconds << ","; result << "\"renderTime\":" << this->renderTime; result << "\"wifiRssi\":" << this->wifiRssi; + result << "\"udpateRateHz\":" << this->udpateRateHz; result << "}"; return result.str(); } diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 5601d5e522..4f811bb4ac 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -242,7 +242,8 @@ int MavLinkTelemetry::pack(char* buffer) const { pack_int32_t(buffer, reinterpret_cast(&this->handlerMicroseconds), 16); pack_int32_t(buffer, reinterpret_cast(&this->renderTime), 20); pack_int32_t(buffer, reinterpret_cast(&this->wifiRssi), 24); - return 28; + pack_int32_t(buffer, reinterpret_cast(&this->udpateRateHz), 28); + return MavLinkTelemetry::MessageLength; } int MavLinkTelemetry::unpack(const char* buffer) { @@ -253,7 +254,8 @@ int MavLinkTelemetry::unpack(const char* buffer) { unpack_int32_t(buffer, reinterpret_cast(&this->handlerMicroseconds), 16); unpack_int32_t(buffer, reinterpret_cast(&this->renderTime), 20); unpack_int32_t(buffer, reinterpret_cast(&this->wifiRssi), 24); - return 28; + unpack_int32_t(buffer, reinterpret_cast(&this->udpateRateHz), 28); + return MavLinkTelemetry::MessageLength; } diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp index 1202aa1c40..e55f37e059 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp @@ -290,7 +290,7 @@ int MavLinkConnectionImpl::prepareForSending(MavLinkMessage& msg) msglen = entry->min_msg_len; } if (msg.msgid == MavLinkTelemetry::kMessageId) { - msglen = 28; // mavlink doesn't know about our custom telemetry message. + msglen = MavLinkTelemetry::MessageLength; // mavlink doesn't know about our custom telemetry message. } if (len != msglen) { @@ -602,6 +602,7 @@ void MavLinkConnectionImpl::getTelemetry(MavLinkTelemetry& result) telemetry_.messagesReceived = 0; telemetry_.messagesSent = 0; telemetry_.renderTime = 0; + telemetry_.udpateRateHz = 0; if (telemetry_.wifiInterfaceName != nullptr) { telemetry_.wifiRssi = port->getRssi(telemetry_.wifiInterfaceName); } From 3b82fef109182a9e56da7d930be9be14b94292c7 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 15:54:25 -0700 Subject: [PATCH 06/37] fix build and update docs. --- .../UnitySensors/UnitySensorFactory.cpp | 6 +- .../Source/UnitySensors/UnitySensorFactory.h | 2 +- docs/px4_setup.md | 12 ++- docs/px4_sitl.md | 11 ++- docs/sensors.md | 96 ++++++++++++++----- 5 files changed, 98 insertions(+), 29 deletions(-) diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp index 85dea1a5e4..75ff5b739b 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp @@ -12,7 +12,7 @@ void UnitySensorFactory::setActor(std::string vehicle_name, const NedTransform* ned_transform_ = ned_transform; } -std::unique_ptr UnitySensorFactory::createSensorFromSettings(const AirSimSettings::SensorSetting * sensor_setting) const +std::shared_ptr UnitySensorFactory::createSensorFromSettings(const AirSimSettings::SensorSetting * sensor_setting) const { using SensorBase = msr::airlib::SensorBase; @@ -20,10 +20,10 @@ std::unique_ptr UnitySensorFactory::createSensorFromSet switch (sensor_setting->sensor_type) { case SensorBase::SensorType::Distance: - return std::unique_ptr(new UnityDistanceSensor(vehicle_name_, ned_transform_)); + return std::make_shared(vehicle_name_, ned_transform_); default: return msr::airlib::SensorFactory::createSensorFromSettings(sensor_setting); } - return std::unique_ptr(); + return std::shared_ptr(); } diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h index 08600898e2..75565a7b3d 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h @@ -10,7 +10,7 @@ class UnitySensorFactory : public SensorFactory public: UnitySensorFactory(std::string vehicle_name, const NedTransform* ned_transform); void setActor(std::string vehicle_name, const NedTransform* ned_transform); - virtual std::unique_ptr createSensorFromSettings(const AirSimSettings::SensorSetting* sensor_setting) const override; + virtual std::shared_ptr createSensorFromSettings(const AirSimSettings::SensorSetting* sensor_setting) const override; private: std::string vehicle_name_; diff --git a/docs/px4_setup.md b/docs/px4_setup.md index 359c75ca37..db48c736e5 100644 --- a/docs/px4_setup.md +++ b/docs/px4_setup.md @@ -39,7 +39,14 @@ See also [initial firmware setup video](https://dev.px4.io/starting-initial-conf "Vehicles": { "PX4": { "VehicleType": "PX4Multirotor", - "UseSerial": true, + "UseSerial": true,, + "Sensors":{ + "Barometer":{ + "SensorType": 1, + "Enabled": true, + "PressureFactorSigma": 0.0001825 + } + }, "Parameters": { "NAV_RCL_ACT": 0, "NAV_DLL_ACT": 0, @@ -52,6 +59,9 @@ See also [initial firmware setup video](https://dev.px4.io/starting-initial-conf } ``` +The "Barometer" setting keeps PX4 happy because the default AirSim barometer has a bit too much +noise generation. This setting clamps that down a bit. + After above setup you should be able to use RC to fly with AirSim. You can usually arm the vehicle by lowering and bringing two sticks of RC together in-wards. You don't need QGroundControl after the initial setup. Typically the Stabilized (instead of Manual) mode gives better experience for beginners. See [PX4 Basic Flying Guide](https://docs.px4.io/master/en/flying/basic_flying.html). You can also control the drone from [Python APIs](apis.md). diff --git a/docs/px4_sitl.md b/docs/px4_sitl.md index 7a117aee93..4c82b0ce73 100644 --- a/docs/px4_sitl.md +++ b/docs/px4_sitl.md @@ -52,7 +52,14 @@ The default ports have changed recently, so check them closely to make sure AirS "UseSerial": false, "UseTcp": true, "TcpPort": 4560, - "ControlPort": 14580, + "ControlPort": 14580,, + "Sensors":{ + "Barometer":{ + "SensorType": 1, + "Enabled": true, + "PressureFactorSigma": 0.0001825 + } + }, "Parameters": { "NAV_RCL_ACT": 0, "NAV_DLL_ACT": 0, @@ -65,6 +72,8 @@ The default ports have changed recently, so check them closely to make sure AirS } ``` Notice the PX4 `[simulator]` is using TCP, which is why we need to add: `"UseTcp": true,`. + The "Barometer" setting keeps PX4 happy because the default AirSim barometer has a bit too much + noise generation. This setting clamps that down a bit. 6. Now run your Unreal AirSim environment and it should connect to SITL PX4 via TCP. You should see a bunch of messages from the SITL PX4 window. diff --git a/docs/sensors.md b/docs/sensors.md index 5309399158..2ef22a605a 100644 --- a/docs/sensors.md +++ b/docs/sensors.md @@ -38,39 +38,84 @@ The default sensor list can be configured in settings json: ```json "DefaultSensors": { "Barometer": { - "SensorType": 1, - "Enabled" : true + "SensorType": 1, + "Enabled" : true, + "PressureFactorSigma": 0.001825, + "PressureFactorTau": 3600, + "UncorrelatedNoiseSigma": 2.7, + "UpdateLatency": 0, + "UpdateFrequency": 50, + "StartupDelay": 0 + }, "Imu": { - "SensorType": 2, - "Enabled" : true + "SensorType": 2, + "Enabled" : true, + "AngularRandomWalk": 0.3, + "GyroBiasStabilityTau": 500, + "GyroBiasStability": 4.6, + "VelocityRandomWalk": 0.24, + "AccelBiasStabilityTau": 800, + "AccelBiasStability": 36 }, "Gps": { - "SensorType": 3, - "Enabled" : true + "SensorType": 3, + "Enabled" : true, + "EphTimeConstant": 0.9, + "EpvTimeConstant": 0.9, + "EphInitial": 25, + "EpvInitial": 25, + "EphFinal": 0.1, + "EpvFinal": 0.1, + "EphMin3d": 3, + "EphMin2d": 4, + "UpdateLatency": 0.2, + "UpdateFrequency": 50, + "StartupDelay": 1 }, "Magnetometer": { - "SensorType": 4, - "Enabled" : true + "SensorType": 4, + "Enabled" : true, + "NoiseSigma": 0.005, + "ScaleFactor": 1, + "NoiseBias": 0, + "UpdateLatency": 0, + "UpdateFrequency": 50, + "StartupDelay": 0 }, "Distance": { - "SensorType": 5, - "Enabled" : true + "SensorType": 5, + "Enabled" : true, + "MinDistance": 0.2, + "MaxDistance": 40, + "X": 0, "Y": 0, "Z": -1, + "Yaw": 0, "Pitch": 0, "Roll": 0, + "DrawDebugPoints": false }, "Lidar2": { - "SensorType": 6, - "Enabled" : true, - "NumberOfChannels": 4, - "PointsPerSecond": 10000 + "SensorType": 6, + "Enabled" : true, + "NumberOfChannels": 16, + "RotationsPerSecond": 10, + "PointsPerSecond": 100000, + "X": 0, "Y": 0, "Z": -1, + "Roll": 0, "Pitch": 0, "Yaw" : 0, + "VerticalFOVUpper": -15, + "VerticalFOVLower": -25, + "HorizontalFOVStart": -20, + "HorizontalFOVEnd": 20, + "DrawDebugPoints": true, + "DataFrame": "SensorLocalFrame" } }, ``` ## Configuring vehicle-specific sensor list -If a vehicle provides its sensor list, it **must** provide the whole list. Selective add/remove/update of the default sensor list is **NOT** supported. -A vehicle specific sensor list can be specified in the vehicle settings part of the json. -e.g., +A vehicle can override a subset of the default sensors listed above. A Lidar and Distance sensor are +not added to a vehicle by default, so those you need to add this way. Each sensor must have a valid +"SensorType" and a subset of the properties can be defined that override the default values shown +above and you can set Enabled to false to disable a specific type of sensor. ```json "Vehicles": { @@ -80,6 +125,11 @@ e.g., "AutoCreate": true, ... "Sensors": { + "Barometer":{ + "SensorType": 1, + "Enabled": true, + "PressureFactorSigma": 0.0001825 + }, "MyLidar1": { "SensorType": 6, "Enabled" : true, @@ -146,7 +196,7 @@ Be default, the points hit by distance sensor are not drawn on the viewport. To ## Sensor APIs Jump straight to [`hello_drone.py`](https://github.com/Microsoft/AirSim/blob/master/PythonClient/multirotor/hello_drone.py) or [`hello_drone.cpp`](https://github.com/Microsoft/AirSim/blob/master/HelloDrone/main.cpp) for example usage, or see follow below for the full API. -##### Barometer +### Barometer ```cpp msr::airlib::BarometerBase::Output getBarometerData(const std::string& barometer_name, const std::string& vehicle_name); ``` @@ -155,7 +205,7 @@ msr::airlib::BarometerBase::Output getBarometerData(const std::string& barometer barometer_data = client.getBarometerData(barometer_name = "", vehicle_name = "") ``` -##### IMU +### IMU ```cpp msr::airlib::ImuBase::Output getImuData(const std::string& imu_name = "", const std::string& vehicle_name = ""); ``` @@ -164,7 +214,7 @@ msr::airlib::ImuBase::Output getImuData(const std::string& imu_name = "", const imu_data = client.getImuData(imu_name = "", vehicle_name = "") ``` -##### GPS +### GPS ```cpp msr::airlib::GpsBase::Output getGpsData(const std::string& gps_name = "", const std::string& vehicle_name = ""); ``` @@ -172,7 +222,7 @@ msr::airlib::GpsBase::Output getGpsData(const std::string& gps_name = "", const gps_data = client.getGpsData(gps_name = "", vehicle_name = "") ``` -##### Magnetometer +### Magnetometer ```cpp msr::airlib::MagnetometerBase::Output getMagnetometerData(const std::string& magnetometer_name = "", const std::string& vehicle_name = ""); ``` @@ -180,7 +230,7 @@ msr::airlib::MagnetometerBase::Output getMagnetometerData(const std::string& mag magnetometer_data = client.getMagnetometerData(magnetometer_name = "", vehicle_name = "") ``` -##### Distance sensor +### Distance sensor ```cpp msr::airlib::DistanceSensorData getDistanceSensorData(const std::string& distance_sensor_name = "", const std::string& vehicle_name = ""); ``` @@ -188,5 +238,5 @@ msr::airlib::DistanceSensorData getDistanceSensorData(const std::string& distanc distance_sensor_data = client.getDistanceSensorData(distance_sensor_name = "", vehicle_name = "") ``` -##### Lidar +### Lidar See the [lidar page](lidar.md) for Lidar API. From 30ab123d36818e3402e66504228865aba5e8bf66 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 15:56:18 -0700 Subject: [PATCH 07/37] fix unreal build --- .../AirSim/Source/UnrealSensors/UnrealSensorFactory.cpp | 6 +++--- .../AirSim/Source/UnrealSensors/UnrealSensorFactory.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.cpp b/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.cpp index 4686633210..ed87adfdd3 100644 --- a/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.cpp +++ b/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.cpp @@ -9,17 +9,17 @@ UnrealSensorFactory::UnrealSensorFactory(AActor* actor, const NedTransform* ned_ setActor(actor, ned_transform); } -std::unique_ptr UnrealSensorFactory::createSensorFromSettings( +std::shared_ptr UnrealSensorFactory::createSensorFromSettings( const AirSimSettings::SensorSetting* sensor_setting) const { using SensorBase = msr::airlib::SensorBase; switch (sensor_setting->sensor_type) { case SensorBase::SensorType::Distance: - return std::unique_ptr(new UnrealDistanceSensor( + return std::shared_ptr(new UnrealDistanceSensor( *static_cast(sensor_setting), actor_, ned_transform_)); case SensorBase::SensorType::Lidar: - return std::unique_ptr(new UnrealLidarSensor( + return std::shared_ptr(new UnrealLidarSensor( *static_cast(sensor_setting), actor_, ned_transform_)); default: return msr::airlib::SensorFactory::createSensorFromSettings(sensor_setting); diff --git a/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.h b/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.h index 7034679a76..c49ba7da17 100644 --- a/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.h +++ b/Unreal/Plugins/AirSim/Source/UnrealSensors/UnrealSensorFactory.h @@ -17,7 +17,7 @@ class UnrealSensorFactory : public msr::airlib::SensorFactory { UnrealSensorFactory(AActor* actor, const NedTransform* ned_transform); virtual ~UnrealSensorFactory() {} void setActor(AActor* actor, const NedTransform* ned_transform); - virtual std::unique_ptr createSensorFromSettings( + virtual std::shared_ptr createSensorFromSettings( const AirSimSettings::SensorSetting* sensor_setting) const override; private: From b0b5de38fcbc0b46b63e4a56e5175744ec09b410 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 18:44:04 -0700 Subject: [PATCH 08/37] compute checksum on telemetry messages. --- .../mavlink/MavLinkMultirotorApi.hpp | 32 +++++---- MavLinkCom/include/MavLinkMessageBase.hpp | 3 + MavLinkCom/src/MavLinkLog.cpp | 11 ++- MavLinkCom/src/MavLinkMessageBase.cpp | 70 +++++++++++++++++++ MavLinkCom/src/impl/MavLinkConnectionImpl.cpp | 14 ++-- MavLinkCom/src/impl/MavLinkConnectionImpl.hpp | 1 - 6 files changed, 106 insertions(+), 25 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index b9961cd10e..bee2d69d38 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -120,6 +120,19 @@ class MavLinkMultirotorApi : public MultirotorApiBase return; auto now = clock()->nowNanos() / 1000; + if (lock_step_enabled_) { + if (last_hil_sensor_time_ + 100000 < now) { + // if 100 ms passes then something is terribly wrong, reset lockstep mode + lock_step_enabled_ = false; + addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); + } + + if (!received_actuator_controls_) { + // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. + return; + } + } + if (last_hil_sensor_time_ != 0 && last_hil_sensor_time_ + ticks_per_update_ > now) { // then update() is being called too often, so we just skip this one. @@ -127,6 +140,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase return; } + last_hil_sensor_time_ = now; + update_count_++; if (last_fps_time_ == 0 || last_fps_time_ + 1000000 < now) { // compute update rate once per second. @@ -136,21 +151,6 @@ class MavLinkMultirotorApi : public MultirotorApiBase sendTelemetry(1); } - if (lock_step_enabled_) { - if (last_hil_sensor_time_ + 100000 < now) { - // if 100 ms passes then something is terribly wrong, reset lockstep mode - lock_step_enabled_ = false; - addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); - } - - if (!received_actuator_controls_) { - // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. - return; - } - } - - last_hil_sensor_time_ = now; - advanceTime(); //send sensor updates @@ -616,7 +616,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (log_ != nullptr) { mavlinkcom::MavLinkMessage msg; + msg.magic = MAVLINK_STX_MAVLINK1; data.encode(msg); + msg.update_checksum(); log_->write(msg); } } diff --git a/MavLinkCom/include/MavLinkMessageBase.hpp b/MavLinkCom/include/MavLinkMessageBase.hpp index b49e7d9ef1..3f55ddd35e 100644 --- a/MavLinkCom/include/MavLinkMessageBase.hpp +++ b/MavLinkCom/include/MavLinkMessageBase.hpp @@ -41,6 +41,9 @@ namespace mavlinkcom uint8_t ck[2]; ///< incoming checksum bytes uint8_t signature[13]; uint8_t protocol_version; + + // initialize checksum + int update_checksum(); }; // This is the base class for all the strongly typed messages define in MavLinkMessages.hpp diff --git a/MavLinkCom/src/MavLinkLog.cpp b/MavLinkCom/src/MavLinkLog.cpp index 9c8fb97c12..b8824eeabd 100644 --- a/MavLinkCom/src/MavLinkLog.cpp +++ b/MavLinkCom/src/MavLinkLog.cpp @@ -9,6 +9,7 @@ using namespace mavlinkcom; using namespace mavlink_utils; #define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol +#define MAVLINK_STX 253 // marker for mavlink 2 uint64_t MavLinkFileLog::getTimeStamp() { @@ -118,15 +119,21 @@ void MavLinkFileLog::write(const mavlinkcom::MavLinkMessage& msg, uint64_t times // todo: mavlink2 support? timestamp = FlipEndianness(timestamp); + uint8_t magic = msg.magic; + if (magic != MAVLINK_STX_MAVLINK1) { + // has to be one or the other! + magic = MAVLINK_STX; + } + std::lock_guard lock(log_lock_); fwrite(×tamp, sizeof(uint64_t), 1, ptr_); - fwrite(&msg.magic, 1, 1, ptr_); + fwrite(&magic, 1, 1, ptr_); fwrite(&msg.len, 1, 1, ptr_); fwrite(&msg.seq, 1, 1, ptr_); fwrite(&msg.sysid, 1, 1, ptr_); fwrite(&msg.compid, 1, 1, ptr_); - if (msg.magic == MAVLINK_STX_MAVLINK1) { + if (magic == MAVLINK_STX_MAVLINK1) { uint8_t msgid = msg.msgid & 0xff; // truncate to mavlink 2 msgid fwrite(&msgid, 1, 1, ptr_); } diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 4f811bb4ac..89df650fcc 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -20,6 +20,76 @@ STRICT_MODE_ON using namespace mavlink_utils; using namespace mavlinkcom; +int MavLinkMessage::update_checksum() +{ + bool mavlink1 = protocol_version != 2; + uint8_t header_len = MAVLINK_CORE_HEADER_LEN + 1; + uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1]; + if (mavlink1) { + magic = MAVLINK_STX_MAVLINK1; + header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1; + } + else { + magic = MAVLINK_STX; + } + + incompat_flags = 0; + compat_flags = 0; + + // pack the payload buffer. + char* payload = reinterpret_cast(&payload64[0]); + int len = this->len; + + // calculate checksum + const mavlink_msg_entry_t* entry = mavlink_get_msg_entry(msgid); + uint8_t crc_extra = 0; + int msglen = 0; + if (entry != nullptr) { + crc_extra = entry->crc_extra; + msglen = entry->min_msg_len; + } + if (msgid == MavLinkTelemetry::kMessageId) { + msglen = MavLinkTelemetry::MessageLength; // mavlink doesn't know about our custom telemetry message. + } + + if (len != msglen) { + if (mavlink1) { + throw std::runtime_error(Utils::stringf("Message length %d doesn't match expected length%d\n", len, msglen)); + } + else { + // mavlink2 supports trimming the payload of trailing zeros so the messages + // are variable length as a result. + } + } + len = mavlink1 ? msglen : _mav_trim_payload(payload, msglen); + this->len = len; + + // form the header as a byte array for the crc + buf[0] = this->magic; + buf[1] = this->len; + if (mavlink1) { + buf[2] = this->seq; + buf[3] = this->sysid; + buf[4] = this->compid; + buf[5] = this->msgid & 0xFF; + } + else { + buf[2] = this->incompat_flags; + buf[3] = this->compat_flags; + buf[4] = this->seq; + buf[5] = this->sysid; + buf[6] = this->compid; + buf[7] = this->msgid & 0xFF; + buf[8] = (this->msgid >> 8) & 0xFF; + buf[9] = (this->msgid >> 16) & 0xFF; + } + + this->checksum = crc_calculate(&buf[1], header_len - 1); + crc_accumulate_buffer(&this->checksum, payload, len); + crc_accumulate(crc_extra, &this->checksum); + + return len + header_len + 2; +} void MavLinkMessageBase::decode(const MavLinkMessage& msg) { // unpack the message... diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp index e55f37e059..ffa94d6879 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp @@ -272,7 +272,7 @@ int MavLinkConnectionImpl::prepareForSending(MavLinkMessage& msg) msg.seq = seqno; msg.incompat_flags = 0; - if (signing_) { + if (signing) { msg.incompat_flags |= MAVLINK_IFLAG_SIGNED; } msg.compat_flags = 0; @@ -301,7 +301,7 @@ int MavLinkConnectionImpl::prepareForSending(MavLinkMessage& msg) // mavlink2 supports trimming the payload of trailing zeros so the messages // are variable length as a result. } - } + } len = mavlink1 ? msglen : _mav_trim_payload(payload, msglen); msg.len = len; @@ -335,12 +335,12 @@ int MavLinkConnectionImpl::prepareForSending(MavLinkMessage& msg) mavlink_ck_b(&msg) = (uint8_t)(msg.checksum >> 8); STRICT_MODE_ON - if (signing_) { + if (signing) { mavlink_sign_packet(mavlink_status_.signing, - reinterpret_cast(msg.signature), - reinterpret_cast(message_buf), header_len, - reinterpret_cast(payload), msg.len, - reinterpret_cast(payload) + msg.len); + reinterpret_cast(msg.signature), + reinterpret_cast(message_buf), header_len, + reinterpret_cast(payload), msg.len, + reinterpret_cast(payload) + msg.len); } return msg.len + header_len + 2 + signature_len; diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp index 3256ae41d6..2a63f190cb 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.hpp @@ -97,7 +97,6 @@ namespace mavlinkcom_impl { bool waiting_for_msg_ = false; bool supports_mavlink2_ = false; std::thread::id publish_thread_id_; - bool signing_ = false; mavlink_status_t mavlink_intermediate_status_; mavlink_status_t mavlink_status_; std::mutex telemetry_mutex_; From 71ff20619be577fa244834e59b09521c212cb260 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Fri, 16 Apr 2021 19:01:25 -0700 Subject: [PATCH 09/37] fix compiler warning. --- Unreal/Plugins/AirSim/Source/WorldSimApi.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 164778352f..c715090080 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -180,8 +180,8 @@ bool WorldSimApi::createVoxelGrid(const Vector3r& position, const int& x_size, c for (float k = 0; k < ncells_z; k++) { for (float j = 0; j < ncells_y; j++) { int idx = i + ncells_x * (k + ncells_z * j); - FVector position = FVector((i - ncells_x /2) * scale_cm, (j - ncells_y /2) * scale_cm, (k - ncells_z /2) * scale_cm) + position_in_UE_frame; - voxel_grid_[idx] = simmode_->GetWorld()->OverlapBlockingTestByChannel(position, FQuat::Identity, ECollisionChannel::ECC_Pawn, FCollisionShape::MakeBox(FVector(scale_cm /2)), params); + FVector vposition = FVector((i - ncells_x /2) * scale_cm, (j - ncells_y /2) * scale_cm, (k - ncells_z /2) * scale_cm) + position_in_UE_frame; + voxel_grid_[idx] = simmode_->GetWorld()->OverlapBlockingTestByChannel(vposition, FQuat::Identity, ECollisionChannel::ECC_Pawn, FCollisionShape::MakeBox(FVector(scale_cm /2)), params); } } } From 24d1bb6880d17c4751db846ffe77dc5c02ce0b15 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sat, 17 Apr 2021 19:39:29 -0700 Subject: [PATCH 10/37] Move telemetry to separate thread to get it out of the update() loop. Rename the telemetry message fields to follow consistent naming scheme. --- .../mavlink/MavLinkMultirotorApi.hpp | 1030 +++++++++-------- MavLinkCom/include/MavLinkMessageBase.hpp | 40 +- MavLinkCom/src/MavLinkMessageBase.cpp | 38 +- MavLinkCom/src/impl/MavLinkConnectionImpl.cpp | 37 +- 4 files changed, 606 insertions(+), 539 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index bee2d69d38..29a77e8f88 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -39,587 +39,621 @@ namespace msr { namespace airlib { -class MavLinkMultirotorApi : public MultirotorApiBase -{ -public: //methods - virtual ~MavLinkMultirotorApi() + class MavLinkMultirotorApi : public MultirotorApiBase { - closeAllConnection(); - if (this->connect_thread_.joinable()) + public: //methods + virtual ~MavLinkMultirotorApi() { - this->connect_thread_.join(); + closeAllConnection(); + if (this->connect_thread_.joinable()) + { + this->connect_thread_.join(); + } + if (this->telemetry_thread_.joinable()) { + this->telemetry_thread_.join(); + } } - } - //non-base interface specific to MavLinKDroneController - void initialize(const AirSimSettings::MavLinkConnectionInfo& connection_info, const SensorCollection* sensors, bool is_simulation) - { - connection_info_ = connection_info; - sensors_ = sensors; - is_simulation_mode_ = is_simulation; + //non-base interface specific to MavLinKDroneController + void initialize(const AirSimSettings::MavLinkConnectionInfo& connection_info, const SensorCollection* sensors, bool is_simulation) + { + connection_info_ = connection_info; + sensors_ = sensors; + is_simulation_mode_ = is_simulation; - try { - openAllConnections(); - is_ready_ = true; - } - catch (std::exception& ex) { - is_ready_ = false; - is_ready_message_ = Utils::stringf("Failed to connect: %s", ex.what()); + try { + openAllConnections(); + is_ready_ = true; + } + catch (std::exception& ex) { + is_ready_ = false; + is_ready_message_ = Utils::stringf("Failed to connect: %s", ex.what()); + } } - } - Pose getMocapPose() - { - std::lock_guard guard(mocap_pose_mutex_); - return mocap_pose_; - } + Pose getMocapPose() + { + std::lock_guard guard(mocap_pose_mutex_); + return mocap_pose_; + } - virtual const SensorCollection& getSensors() const override - { - return *sensors_; - } + virtual const SensorCollection& getSensors() const override + { + return *sensors_; + } - //reset PX4 stack - virtual void resetImplementation() override - { - // note this is called AFTER "initialize" when we've connected to the drone - // so this method cannot reset any of that connection state. - MultirotorApiBase::resetImplementation(); - was_reset_ = true; - } + //reset PX4 stack + virtual void resetImplementation() override + { + // note this is called AFTER "initialize" when we've connected to the drone + // so this method cannot reset any of that connection state. + MultirotorApiBase::resetImplementation(); + was_reset_ = true; + } - unsigned long long getSimTime() { - // This ensures HIL_SENSOR and HIL_GPS have matching clocks. - if (lock_step_enabled_) { - if (sim_time_us_ == 0) { - sim_time_us_ = clock()->nowNanos() / 1000; + unsigned long long getSimTime() { + // This ensures HIL_SENSOR and HIL_GPS have matching clocks. + if (lock_step_enabled_) { + if (sim_time_us_ == 0) { + sim_time_us_ = clock()->nowNanos() / 1000; + } + return sim_time_us_; + } + else { + return clock()->nowNanos() / 1000; } - return sim_time_us_; - } - else { - return clock()->nowNanos() / 1000; } - } - void advanceTime() { - if (lock_step_enabled_) { - sim_time_us_ += ticks_per_update_; - } - else { + void advanceTime() { sim_time_us_ = clock()->nowNanos() / 1000; } - } - //update sensors in PX4 stack - virtual void update() override - { - try { - MultirotorApiBase::update(); + //update sensors in PX4 stack + virtual void update() override + { + try { + MultirotorApiBase::update(); - if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) - return; + if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) + return; - auto now = clock()->nowNanos() / 1000; - if (lock_step_enabled_) { - if (last_hil_sensor_time_ + 100000 < now) { - // if 100 ms passes then something is terribly wrong, reset lockstep mode - lock_step_enabled_ = false; - addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); - } + update_count_++; - if (!received_actuator_controls_) { - // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. - return; + auto now = clock()->nowNanos() / 1000; + if (lock_step_enabled_) { + if (last_update_time_ + 100000 < now) { + // if 100 ms passes then something is terribly wrong, reset lockstep mode + lock_step_enabled_ = false; + lock_step_resets_++; + addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); + } + + if (!received_actuator_controls_) { + // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. + return; + } } - } - if (last_hil_sensor_time_ != 0 && last_hil_sensor_time_ + ticks_per_update_ > now) - { - // then update() is being called too often, so we just skip this one. - // TODO: I think this needs to be aware of AirSim ClockSpeed...but perhasp clock() has already taken that into account? - return; - } + last_update_time_ = now; + hil_sensor_count_++; + advanceTime(); - last_hil_sensor_time_ = now; + //send sensor updates + const auto& imu_output = getImuData(""); + const auto& mag_output = getMagnetometerData(""); + const auto& baro_output = getBarometerData(""); - update_count_++; - if (last_fps_time_ == 0 || last_fps_time_ + 1000000 < now) { - // compute update rate once per second. - update_rate_ = update_count_; - update_count_ = 0; - last_fps_time_ = now; - sendTelemetry(1); - } + sendHILSensor(imu_output.linear_acceleration, + imu_output.angular_velocity, + mag_output.magnetic_field_body, + baro_output.pressure * 0.01f /*Pa to Millibar */, baro_output.altitude); - advanceTime(); + sendSystemTime(); - //send sensor updates - const auto& imu_output = getImuData(""); - const auto& mag_output = getMagnetometerData(""); - const auto& baro_output = getBarometerData(""); + const uint count_distance_sensors = getSensors().size(SensorBase::SensorType::Distance); + if (count_distance_sensors != 0) { + const auto& distance_output = getDistanceSensorData(""); - sendHILSensor(imu_output.linear_acceleration, - imu_output.angular_velocity, - mag_output.magnetic_field_body, - baro_output.pressure * 0.01f /*Pa to Millibar */, baro_output.altitude); - - sendSystemTime(); - - const uint count_distance_sensors = getSensors().size(SensorBase::SensorType::Distance); - if (count_distance_sensors != 0) { - const auto& distance_output = getDistanceSensorData(""); - - sendDistanceSensor(distance_output.min_distance * 100, //m -> cm - distance_output.max_distance * 100, //m -> cm - distance_output.distance * 100, //m-> cm - 0, //sensor type: //TODO: allow changing in settings? - 77, //sensor id, //TODO: should this be something real? - distance_output.relative_pose.orientation); //TODO: convert from radians to degrees? - } - - const uint count_gps_sensors = getSensors().size(SensorBase::SensorType::Gps); - if (count_gps_sensors != 0) { - const auto& gps_output = getGpsData(""); - - //send GPS - if (gps_output.is_valid && gps_output.gnss.time_utc > last_gps_time_) { - last_gps_time_ = gps_output.gnss.time_utc; - Vector3r gps_velocity = gps_output.gnss.velocity; - Vector3r gps_velocity_xy = gps_velocity; - gps_velocity_xy.z() = 0; - float gps_cog; - if (Utils::isApproximatelyZero(gps_velocity.y(), 1E-2f) && Utils::isApproximatelyZero(gps_velocity.x(), 1E-2f)) - gps_cog = 0; - else - gps_cog = Utils::radiansToDegrees(atan2(gps_velocity.y(), gps_velocity.x())); - if (gps_cog < 0) - gps_cog += 360; - - sendHILGps(gps_output.gnss.geo_point, gps_velocity, gps_velocity_xy.norm(), gps_cog, - gps_output.gnss.eph, gps_output.gnss.epv, gps_output.gnss.fix_type, 10); + sendDistanceSensor(distance_output.min_distance * 100, //m -> cm + distance_output.max_distance * 100, //m -> cm + distance_output.distance * 100, //m-> cm + 0, //sensor type: //TODO: allow changing in settings? + 77, //sensor id, //TODO: should this be something real? + distance_output.relative_pose.orientation); //TODO: convert from radians to degrees? } - } - } - catch (std::exception& e) { - addStatusMessage("Exception sending messages to vehicle"); - addStatusMessage(e.what()); - disconnect(); - connect(); // re-start a new connection so PX4 can be restarted and AirSim will happily continue on. - } + const uint count_gps_sensors = getSensors().size(SensorBase::SensorType::Gps); + if (count_gps_sensors != 0) { + const auto& gps_output = getGpsData(""); + + //send GPS + if (gps_output.is_valid && gps_output.gnss.time_utc > last_gps_time_) { + last_gps_time_ = gps_output.gnss.time_utc; + Vector3r gps_velocity = gps_output.gnss.velocity; + Vector3r gps_velocity_xy = gps_velocity; + gps_velocity_xy.z() = 0; + float gps_cog; + if (Utils::isApproximatelyZero(gps_velocity.y(), 1E-2f) && Utils::isApproximatelyZero(gps_velocity.x(), 1E-2f)) + gps_cog = 0; + else + gps_cog = Utils::radiansToDegrees(atan2(gps_velocity.y(), gps_velocity.x())); + if (gps_cog < 0) + gps_cog += 360; + + sendHILGps(gps_output.gnss.geo_point, gps_velocity, gps_velocity_xy.norm(), gps_cog, + gps_output.gnss.eph, gps_output.gnss.epv, gps_output.gnss.fix_type, 10); + } + } - //must be done at the end - if (was_reset_) - was_reset_ = false; - } + } + catch (std::exception& e) { + addStatusMessage("Exception sending messages to vehicle"); + addStatusMessage(e.what()); + disconnect(); + connect(); // re-start a new connection so PX4 can be restarted and AirSim will happily continue on. + } - virtual bool isReady(std::string& message) const override - { - if (!is_ready_ && is_ready_message_.size() > 0) { - message = is_ready_message_; + //must be done at the end + if (was_reset_) + was_reset_ = false; } - return is_ready_; - } - virtual bool canArm() const override - { - return is_ready_ && has_gps_lock_; - } + virtual bool isReady(std::string& message) const override + { + if (!is_ready_ && is_ready_message_.size() > 0) { + message = is_ready_message_; + } + return is_ready_; + } - //TODO: this method can't be const yet because it clears previous messages - virtual void getStatusMessages(std::vector& messages) override - { - updateState(); + virtual bool canArm() const override + { + return is_ready_ && has_gps_lock_; + } - //clear param - messages.clear(); + //TODO: this method can't be const yet because it clears previous messages + virtual void getStatusMessages(std::vector& messages) override + { + updateState(); + + //clear param + messages.clear(); - //move messages from private vars to param - std::lock_guard guard(status_text_mutex_); - while (!status_messages_.empty()) { - messages.push_back(status_messages_.front()); - status_messages_.pop(); + //move messages from private vars to param + std::lock_guard guard(status_text_mutex_); + while (!status_messages_.empty()) { + messages.push_back(status_messages_.front()); + status_messages_.pop(); + } } - } - virtual Kinematics::State getKinematicsEstimated() const override - { - updateState(); - Kinematics::State state; - //TODO: reduce code duplication in getPosition() etc methods? - state.pose.position = Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); - state.pose.orientation = VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); - state.twist.linear = Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); - state.twist.angular = Vector3r(current_state_.attitude.roll_rate, current_state_.attitude.pitch_rate, current_state_.attitude.yaw_rate); - state.accelerations.linear = Vector3r(current_state_.local_est.acc.x, current_state_.local_est.acc.y, current_state_.local_est.acc.z); - //TODO: how do we get angular acceleration? - return state; - } + virtual Kinematics::State getKinematicsEstimated() const override + { + updateState(); + Kinematics::State state; + //TODO: reduce code duplication in getPosition() etc methods? + state.pose.position = Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); + state.pose.orientation = VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); + state.twist.linear = Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); + state.twist.angular = Vector3r(current_state_.attitude.roll_rate, current_state_.attitude.pitch_rate, current_state_.attitude.yaw_rate); + state.accelerations.linear = Vector3r(current_state_.local_est.acc.x, current_state_.local_est.acc.y, current_state_.local_est.acc.z); + //TODO: how do we get angular acceleration? + return state; + } + + virtual bool isApiControlEnabled() const override + { + return is_api_control_enabled_; + } - virtual bool isApiControlEnabled() const override - { - return is_api_control_enabled_; - } + virtual void enableApiControl(bool is_enabled) override + { + checkValidVehicle(); + if (is_enabled) { + mav_vehicle_->requestControl(); + is_api_control_enabled_ = true; + } + else { + mav_vehicle_->releaseControl(); + is_api_control_enabled_ = false; + } + } - virtual void enableApiControl(bool is_enabled) override - { - checkValidVehicle(); - if (is_enabled) { - mav_vehicle_->requestControl(); - is_api_control_enabled_ = true; + virtual Vector3r getPosition() const override + { + updateState(); + return Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); } - else { - mav_vehicle_->releaseControl(); - is_api_control_enabled_ = false; + virtual Vector3r getVelocity() const override + { + updateState(); + return Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); } - } - virtual Vector3r getPosition() const override - { - updateState(); - return Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); - } - virtual Vector3r getVelocity() const override - { - updateState(); - return Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); - } + virtual Quaternionr getOrientation() const override + { + updateState(); + return VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); + } - virtual Quaternionr getOrientation() const override - { - updateState(); - return VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); - } + virtual LandedState getLandedState() const override + { + updateState(); + return current_state_.controls.landed ? LandedState::Landed : LandedState::Flying; + } - virtual LandedState getLandedState() const override - { - updateState(); - return current_state_.controls.landed ? LandedState::Landed : LandedState::Flying; - } + virtual real_T getActuation(unsigned int rotor_index) const override + { + if (!is_simulation_mode_) + throw std::logic_error("Attempt to read motor controls while not in simulation mode"); - virtual real_T getActuation(unsigned int rotor_index) const override - { - if (!is_simulation_mode_) - throw std::logic_error("Attempt to read motor controls while not in simulation mode"); + std::lock_guard guard(hil_controls_mutex_); + return rotor_controls_[rotor_index]; + } + virtual size_t getActuatorCount() const override + { + return RotorControlsCount; + } - std::lock_guard guard(hil_controls_mutex_); - return rotor_controls_[rotor_index]; - } - virtual size_t getActuatorCount() const override - { - return RotorControlsCount; - } + virtual bool armDisarm(bool arm) override + { + SingleCall lock(this); - virtual bool armDisarm(bool arm) override - { - SingleCall lock(this); + checkValidVehicle(); + bool rc = false; + if (arm) { + float timeout_sec = 10; + waitForHomeLocation(timeout_sec); + waitForStableGroundPosition(timeout_sec); + } - checkValidVehicle(); - bool rc = false; - if (arm) { - float timeout_sec = 10; - waitForHomeLocation(timeout_sec); - waitForStableGroundPosition(timeout_sec); + mav_vehicle_->armDisarm(arm).wait(10000, &rc); + return rc; } - mav_vehicle_->armDisarm(arm).wait(10000, &rc); - return rc; - } - - void onArmed() { - if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { - auto con = mav_vehicle_->getConnection(); - if (con != nullptr) { - if (log_ != nullptr) { - log_->close(); - } + void onArmed() { + if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { + auto con = mav_vehicle_->getConnection(); + if (con != nullptr) { + if (log_ != nullptr) { + log_->close(); + log_ = nullptr; + } - std::time_t t = std::time(0); // get time now - std::tm* now = std::localtime(&t); - auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday); - auto path = common_utils::FileSystem::ensureFolder(connection_info_.logs, folder); - auto filename = Utils::stringf("%02d-%02d-%02d.mavlink", now->tm_hour, now->tm_min, now->tm_sec); - auto fullpath = common_utils::FileSystem::combine(path, filename); - addStatusMessage(Utils::stringf("Opening log file: %s", fullpath.c_str())); - log_ = std::make_shared(); - log_->openForWriting(fullpath, false); - con->startLoggingSendMessage(log_); - con->startLoggingReceiveMessage(log_); - if (con != connection_) { - // log the SITL channel also - connection_->startLoggingSendMessage(log_); - connection_->startLoggingReceiveMessage(log_); + try + { + std::time_t t = std::time(0); // get time now + std::tm* now = std::localtime(&t); + auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday); + auto path = common_utils::FileSystem::ensureFolder(connection_info_.logs, folder); + auto filename = Utils::stringf("%02d-%02d-%02d.mavlink", now->tm_hour, now->tm_min, now->tm_sec); + auto fullpath = common_utils::FileSystem::combine(path, filename); + addStatusMessage(Utils::stringf("Opening log file: %s", fullpath.c_str())); + log_file_name_ = fullpath; + log_ = std::make_shared(); + log_->openForWriting(fullpath, false); + con->startLoggingSendMessage(log_); + con->startLoggingReceiveMessage(log_); + if (con != connection_) { + // log the SITL channel also + connection_->startLoggingSendMessage(log_); + connection_->startLoggingReceiveMessage(log_); + } + start_telemtry_thread(); + } + catch (std::exception& ex) { + addStatusMessage(std::string("Opening log file failed: ") + ex.what()); + } } } } - } - void onDisarmed() { - if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { - auto con = mav_vehicle_->getConnection(); - if (con != nullptr) { - con->stopLoggingSendMessage(); - addStatusMessage("Closing log file."); + void onDisarmed() { + if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { + auto con = mav_vehicle_->getConnection(); + if (con != nullptr) { + con->stopLoggingSendMessage(); + addStatusMessage(Utils::stringf("Closing log file: %s", log_file_name_.c_str())); + } + connection_->stopLoggingSendMessage(); } - connection_->stopLoggingSendMessage(); if (log_ != nullptr) { log_->close(); + log_ = nullptr; } } - } - void waitForHomeLocation(float timeout_sec) - { - if (!current_state_.home.is_set) { - addStatusMessage("Waiting for valid GPS home location..."); - if (!waitForFunction([&]() { - return current_state_.home.is_set; - }, timeout_sec).isComplete()) { - throw VehicleMoveException("Vehicle does not have a valid GPS home location"); + void waitForHomeLocation(float timeout_sec) + { + if (!current_state_.home.is_set) { + addStatusMessage("Waiting for valid GPS home location..."); + if (!waitForFunction([&]() { + return current_state_.home.is_set; + }, timeout_sec).isComplete()) { + throw VehicleMoveException("Vehicle does not have a valid GPS home location"); + } } } - } - void waitForStableGroundPosition(float timeout_sec) - { - // wait for ground stabilization - if (ground_variance_ > GroundTolerance) { - addStatusMessage("Waiting for z-position to stabilize..."); - if (!waitForFunction([&]() { - return ground_variance_ <= GroundTolerance; - }, timeout_sec).isComplete()) - { - auto msg = Utils::stringf("Ground is not stable, variance is %f", ground_variance_); - throw VehicleMoveException(msg); + void waitForStableGroundPosition(float timeout_sec) + { + // wait for ground stabilization + if (ground_variance_ > GroundTolerance) { + addStatusMessage("Waiting for z-position to stabilize..."); + if (!waitForFunction([&]() { + return ground_variance_ <= GroundTolerance; + }, timeout_sec).isComplete()) + { + auto msg = Utils::stringf("Ground is not stable, variance is %f", ground_variance_); + throw VehicleMoveException(msg); + } } } - } - - virtual bool takeoff(float timeout_sec) override - { - SingleCall lock(this); - checkValidVehicle(); - - waitForHomeLocation(timeout_sec); - waitForStableGroundPosition(timeout_sec); - - bool rc = false; - auto vec = getPosition(); - auto yaw = current_state_.attitude.yaw; - float z = vec.z() + getTakeoffZ(); - if (!mav_vehicle_->takeoff(z, 0.0f /* pitch */, yaw).wait(static_cast(timeout_sec * 1000), &rc)) { - throw VehicleMoveException("TakeOff command - timeout waiting for response"); - } - if (!rc) { - throw VehicleMoveException("TakeOff command rejected by drone"); - } - if (timeout_sec <= 0) - return true; // client doesn't want to wait. + virtual bool takeoff(float timeout_sec) override + { + SingleCall lock(this); - return waitForZ(timeout_sec, z, getDistanceAccuracy()); - } + checkValidVehicle(); - virtual bool land(float timeout_sec) override - { - SingleCall lock(this); + waitForHomeLocation(timeout_sec); + waitForStableGroundPosition(timeout_sec); - //TODO: bugbug: really need a downward pointing distance to ground sensor to do this properly, for now - //we assume the ground is relatively flat an we are landing roughly at the home altitude. - updateState(); - checkValidVehicle(); - if (current_state_.home.is_set) { bool rc = false; - if (!mav_vehicle_->land(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.home.global_pos.alt).wait(10000, &rc)) - { - throw VehicleMoveException("Landing command - timeout waiting for response from drone"); + auto vec = getPosition(); + auto yaw = current_state_.attitude.yaw; + float z = vec.z() + getTakeoffZ(); + if (!mav_vehicle_->takeoff(z, 0.0f /* pitch */, yaw).wait(static_cast(timeout_sec * 1000), &rc)) { + throw VehicleMoveException("TakeOff command - timeout waiting for response"); } - else if (!rc) { - throw VehicleMoveException("Landing command rejected by drone"); + if (!rc) { + throw VehicleMoveException("TakeOff command rejected by drone"); } - } - else { - throw VehicleMoveException("Cannot land safely with out a home position that tells us the home altitude. Could fix this if we hook up a distance to ground sensor..."); - } + if (timeout_sec <= 0) + return true; // client doesn't want to wait. - const auto& waiter = waitForFunction([&]() { - updateState(); - return current_state_.controls.landed; - }, timeout_sec); + return waitForZ(timeout_sec, z, getDistanceAccuracy()); + } - // Wait for landed state (or user cancellation) - if (!waiter.isComplete()) + virtual bool land(float timeout_sec) override { - throw VehicleMoveException("Drone hasn't reported a landing state"); - } - return waiter.isComplete(); - } + SingleCall lock(this); - virtual bool goHome(float timeout_sec) override - { - SingleCall lock(this); + //TODO: bugbug: really need a downward pointing distance to ground sensor to do this properly, for now + //we assume the ground is relatively flat an we are landing roughly at the home altitude. + updateState(); + checkValidVehicle(); + if (current_state_.home.is_set) { + bool rc = false; + if (!mav_vehicle_->land(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.home.global_pos.alt).wait(10000, &rc)) + { + throw VehicleMoveException("Landing command - timeout waiting for response from drone"); + } + else if (!rc) { + throw VehicleMoveException("Landing command rejected by drone"); + } + } + else { + throw VehicleMoveException("Cannot land safely with out a home position that tells us the home altitude. Could fix this if we hook up a distance to ground sensor..."); + } - checkValidVehicle(); - bool rc = false; - if (mav_vehicle_ != nullptr && !mav_vehicle_->returnToHome().wait( - static_cast(timeout_sec) * 1000, &rc)) { - throw VehicleMoveException("goHome - timeout waiting for response from drone"); + const auto& waiter = waitForFunction([&]() { + updateState(); + return current_state_.controls.landed; + }, timeout_sec); + + // Wait for landed state (or user cancellation) + if (!waiter.isComplete()) + { + throw VehicleMoveException("Drone hasn't reported a landing state"); + } + return waiter.isComplete(); } - return rc; - } - virtual bool moveToPosition(float x, float y, float z, float velocity, float timeout_sec, DrivetrainType drivetrain, - const YawMode& yaw_mode, float lookahead, float adaptive_lookahead) override - { - SingleTaskCall lock(this); - - unused(adaptive_lookahead); - unused(lookahead); - unused(drivetrain); - - // save current manual, cruise, and max velocity parameters - bool result = false; - mavlinkcom::MavLinkParameter manual_velocity_parameter, cruise_velocity_parameter, max_velocity_parameter; - result = mav_vehicle_->getParameter("MPC_VEL_MANUAL").wait(1000, &manual_velocity_parameter); - result = result && mav_vehicle_->getParameter("MPC_XY_CRUISE").wait(1000, &cruise_velocity_parameter); - result = result && mav_vehicle_->getParameter("MPC_XY_VEL_MAX").wait(1000, &max_velocity_parameter); - - if (result) { - // set max velocity parameter - mavlinkcom::MavLinkParameter p; - p.name = "MPC_XY_VEL_MAX"; - p.value = velocity; - mav_vehicle_->setParameter(p).wait(1000, &result); + virtual bool goHome(float timeout_sec) override + { + SingleCall lock(this); - if (result) { - const Vector3r& goal_pos = Vector3r(x, y, z); - Vector3r goal_dist_vect; - float goal_dist; + checkValidVehicle(); + bool rc = false; + if (mav_vehicle_ != nullptr && !mav_vehicle_->returnToHome().wait( + static_cast(timeout_sec) * 1000, &rc)) { + throw VehicleMoveException("goHome - timeout waiting for response from drone"); + } + return rc; + } - Waiter waiter(getCommandPeriod(), timeout_sec, getCancelToken()); + virtual bool moveToPosition(float x, float y, float z, float velocity, float timeout_sec, DrivetrainType drivetrain, + const YawMode& yaw_mode, float lookahead, float adaptive_lookahead) override + { + SingleTaskCall lock(this); - while (!waiter.isComplete()) { - goal_dist_vect = getPosition() - goal_pos; - const Vector3r& goal_normalized = goal_dist_vect.normalized(); - goal_dist = goal_dist_vect.dot(goal_normalized); + unused(adaptive_lookahead); + unused(lookahead); + unused(drivetrain); - if (goal_dist > getDistanceAccuracy()) { - moveToPositionInternal(goal_pos, yaw_mode); + // save current manual, cruise, and max velocity parameters + bool result = false; + mavlinkcom::MavLinkParameter manual_velocity_parameter, cruise_velocity_parameter, max_velocity_parameter; + result = mav_vehicle_->getParameter("MPC_VEL_MANUAL").wait(1000, &manual_velocity_parameter); + result = result && mav_vehicle_->getParameter("MPC_XY_CRUISE").wait(1000, &cruise_velocity_parameter); + result = result && mav_vehicle_->getParameter("MPC_XY_VEL_MAX").wait(1000, &max_velocity_parameter); - //sleep for rest of the cycle - if (!waiter.sleep()) - return false; - } - else { - waiter.complete(); + if (result) { + // set max velocity parameter + mavlinkcom::MavLinkParameter p; + p.name = "MPC_XY_VEL_MAX"; + p.value = velocity; + mav_vehicle_->setParameter(p).wait(1000, &result); + + if (result) { + const Vector3r& goal_pos = Vector3r(x, y, z); + Vector3r goal_dist_vect; + float goal_dist; + + Waiter waiter(getCommandPeriod(), timeout_sec, getCancelToken()); + + while (!waiter.isComplete()) { + goal_dist_vect = getPosition() - goal_pos; + const Vector3r& goal_normalized = goal_dist_vect.normalized(); + goal_dist = goal_dist_vect.dot(goal_normalized); + + if (goal_dist > getDistanceAccuracy()) { + moveToPositionInternal(goal_pos, yaw_mode); + + //sleep for rest of the cycle + if (!waiter.sleep()) + return false; + } + else { + waiter.complete(); + } } - } - // reset manual, cruise, and max velocity parameters - bool result_temp = false; - mav_vehicle_->setParameter(manual_velocity_parameter).wait(1000, &result); - mav_vehicle_->setParameter(cruise_velocity_parameter).wait(1000, &result_temp); - result = result && result_temp; - mav_vehicle_->setParameter(max_velocity_parameter).wait(1000, &result_temp); - result = result && result_temp; + // reset manual, cruise, and max velocity parameters + bool result_temp = false; + mav_vehicle_->setParameter(manual_velocity_parameter).wait(1000, &result); + mav_vehicle_->setParameter(cruise_velocity_parameter).wait(1000, &result_temp); + result = result && result_temp; + mav_vehicle_->setParameter(max_velocity_parameter).wait(1000, &result_temp); + result = result && result_temp; - return result && waiter.isComplete(); + return result && waiter.isComplete(); + } } - } - - return result; - } - virtual bool hover() override - { - SingleCall lock(this); + return result; + } - bool rc = false; - checkValidVehicle(); - mavlinkcom::AsyncResult result = mav_vehicle_->loiter(); - //auto start_time = std::chrono::system_clock::now(); - while (!getCancelToken().isCancelled()) + virtual bool hover() override { - if (result.wait(100, &rc)) + SingleCall lock(this); + + bool rc = false; + checkValidVehicle(); + mavlinkcom::AsyncResult result = mav_vehicle_->loiter(); + //auto start_time = std::chrono::system_clock::now(); + while (!getCancelToken().isCancelled()) { - break; + if (result.wait(100, &rc)) + { + break; + } } + return rc; } - return rc; - } - virtual GeoPoint getHomeGeoPoint() const override - { - updateState(); - if (current_state_.home.is_set) - return GeoPoint(current_state_.home.global_pos.lat, current_state_.home.global_pos.lon, current_state_.home.global_pos.alt); - else - return GeoPoint(Utils::nan(), Utils::nan(), Utils::nan()); - } - - virtual GeoPoint getGpsLocation() const override - { - updateState(); - return GeoPoint(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.global_est.pos.alt); - } + virtual GeoPoint getHomeGeoPoint() const override + { + updateState(); + if (current_state_.home.is_set) + return GeoPoint(current_state_.home.global_pos.lat, current_state_.home.global_pos.lon, current_state_.home.global_pos.alt); + else + return GeoPoint(Utils::nan(), Utils::nan(), Utils::nan()); + } - virtual void sendTelemetry(float last_interval = -1) override - { - if ((logviewer_proxy_ == nullptr && log_ == nullptr) || connection_ == nullptr || mav_vehicle_ == nullptr) { - return; + virtual GeoPoint getGpsLocation() const override + { + updateState(); + return GeoPoint(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.global_est.pos.alt); } - mavlinkcom::MavLinkTelemetry data; - connection_->getTelemetry(data); - if (data.messagesReceived == 0) { - if (!hil_message_timer_.started()) { - hil_message_timer_.start(); + + virtual void sendTelemetry(float last_interval = -1) override + { + if (connection_ == nullptr || mav_vehicle_ == nullptr) { + return; } - else if (hil_message_timer_.seconds() > messageReceivedTimeout) { - addStatusMessage("not receiving any messages from HIL, please restart your HIL node and try again"); + mavlinkcom::MavLinkTelemetry data; + connection_->getTelemetry(data); + if (data.messages_received == 0) { + if (!hil_message_timer_.started()) { + hil_message_timer_.start(); + } + else if (hil_message_timer_.seconds() > messageReceivedTimeout) { + addStatusMessage("not receiving any messages from HIL, please restart your HIL node and try again"); + } + } + else { + hil_message_timer_.stop(); } - } - else { - hil_message_timer_.stop(); - } - // listen to the other mavlink connection also - auto mavcon = mav_vehicle_->getConnection(); - if (mavcon != connection_) { - mavlinkcom::MavLinkTelemetry gcs; - mavcon->getTelemetry(gcs); + if ((logviewer_proxy_ == nullptr && log_ == nullptr)) { + return; + } - data.handlerMicroseconds += gcs.handlerMicroseconds; - data.messagesHandled += gcs.messagesHandled; - data.messagesReceived += gcs.messagesReceived; - data.messagesSent += gcs.messagesSent; + // listen to the other mavlink connection also + auto mavcon = mav_vehicle_->getConnection(); + if (mavcon != connection_) { + mavlinkcom::MavLinkTelemetry gcs; + mavcon->getTelemetry(gcs); - if (gcs.messagesReceived == 0) - { - if (!gcs_message_timer_.started()) { - gcs_message_timer_.start(); + data.handler_microseconds += gcs.handler_microseconds; + data.messages_handled += gcs.messages_handled; + data.messages_received += gcs.messages_received; + data.messages_sent += gcs.messages_sent; + + if (gcs.messages_received == 0) + { + if (!gcs_message_timer_.started()) { + gcs_message_timer_.start(); + } + else if (gcs_message_timer_.seconds() > messageReceivedTimeout) { + addStatusMessage("not receiving any messages from GCS port, please restart your SITL node and try again"); + } } - else if (gcs_message_timer_.seconds() > messageReceivedTimeout) { - addStatusMessage("not receiving any messages from GCS port, please restart your SITL node and try again"); + else { + gcs_message_timer_.stop(); } } - else { - gcs_message_timer_.stop(); + + data.render_time = static_cast(last_interval * 1000000);// microseconds + data.udpate_rate = update_count_; + data.sensor_rate = hil_sensor_count_; + data.actuation_delay = actuator_delay_; + data.lock_step_resets = lock_step_resets_; + + // reset the counters we just captured. + update_count_ = 0; + hil_sensor_count_ = 0; + actuator_delay_ = 0; + + if (logviewer_proxy_ != nullptr) { + logviewer_proxy_->sendMessage(data); + } + + if (log_ != nullptr) { + mavlinkcom::MavLinkMessage msg; + msg.magic = MAVLINK_STX_MAVLINK1; + data.encode(msg); + msg.update_checksum(); + // disk I/O is unpredictable, so we have to get it out of the update loop + // which is why this thread exists. + log_->write(msg); } } - data.renderTime = static_cast(last_interval * 1000000);// microseconds - data.udpateRateHz = update_rate_; + void start_telemtry_thread() { - if (logviewer_proxy_ != nullptr) { - logviewer_proxy_->sendMessage(data); + if (this->telemetry_thread_.joinable()) + { + this->telemetry_thread_.join(); } - if (log_ != nullptr) { - mavlinkcom::MavLinkMessage msg; - msg.magic = MAVLINK_STX_MAVLINK1; - data.encode(msg); - msg.update_checksum(); - log_->write(msg); + // reset the counters we use for telemetry. + update_count_ = 0; + hil_sensor_count_ = 0; + actuator_delay_ = 0; + + this->telemetry_thread_ = std::thread(&MavLinkMultirotorApi::telemtry_thread, this); + } + + void telemtry_thread() { + while (log_ != nullptr) { + + std::this_thread::sleep_for(std::chrono::seconds(1)); + + Utils::log(Utils::stringf("sending telemetry, update_count_ is %d...", update_count_)); + sendTelemetry(1); } } @@ -782,6 +816,13 @@ class MavLinkMultirotorApi : public MultirotorApiBase addStatusMessage("Disconnecting mavlink vehicle"); connected_ = false; connecting_ = false; + + if (is_armed_) { + // close the telemetry log. + is_armed_ = false; + onDisarmed(); + } + if (connection_ != nullptr) { if (is_hil_mode_set_ && mav_vehicle_ != nullptr) { setNormalMode(); @@ -1470,6 +1511,24 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } + void handleLockStep() { + received_actuator_controls_ = true; + // if the timestamps match then it means we are in lockstep mode. + if (!lock_step_enabled_) { + // && (HilActuatorControlsMessage.flags & 0x1)) // todo: enable this check when this flag is widely available... + if (last_hil_sensor_time_ == HilActuatorControlsMessage.time_usec) { + addStatusMessage("Enabling lockstep mode"); + lock_step_enabled_ = true; + } + } + else + { + auto now = clock()->nowNanos() / 1000; + auto delay = static_cast(now - last_update_time_); + actuator_delay_ += delay; + } + } + void processMavMessages(const mavlinkcom::MavLinkMessage& msg) { if (msg.msgid == HeartbeatMessage.msgid) { @@ -1523,7 +1582,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase rotor_controls_[7] = HilControlsMessage.aux4; normalizeRotorControls(); - received_actuator_controls_ = true; + handleLockStep(); } } else if (msg.msgid == HilActuatorControlsMessage.msgid) { @@ -1544,15 +1603,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (isarmed) { normalizeRotorControls(); } - received_actuator_controls_ = true; - // if the timestamps match then it means we are in lockstep mode. - if (!lock_step_enabled_) { - // && (HilActuatorControlsMessage.flags & 0x1)) // todo: enable this check when this flag is widely available... - if (getSimTime() == HilActuatorControlsMessage.time_usec) { - addStatusMessage("Enabling lockstep mode"); - lock_step_enabled_ = true; - } - } + + handleLockStep(); } else if (msg.msgid == MavLinkGpsRawInt.msgid) { MavLinkGpsRawInt.decode(msg); @@ -1607,7 +1659,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase throw std::logic_error("Attempt to send simulated sensor messages while not in simulation mode"); mavlinkcom::MavLinkHilSensor hil_sensor; - hil_sensor.time_usec = getSimTime(); + hil_sensor.time_usec = last_hil_sensor_time_ = getSimTime(); hil_sensor.xacc = acceleration.x(); hil_sensor.yacc = acceleration.y(); @@ -1742,10 +1794,12 @@ class MavLinkMultirotorApi : public MultirotorApiBase sim_time_us_ = 0; last_sys_time_ = 0; last_gps_time_ = 0; + last_update_time_ = 0; last_hil_sensor_time_ = 0; - update_rate_ = 0; update_count_ = 0; - last_fps_time_ = 0; + hil_sensor_count_ = 0; + lock_step_resets_ = 0; + actuator_delay_ = 0; is_api_control_enabled_ = false; thrust_controller_ = PidController(); Utils::setValue(rotor_controls_, 0.0f); @@ -1842,15 +1896,18 @@ class MavLinkMultirotorApi : public MultirotorApiBase const double GroundTolerance = 0.1; // variables for throttling HIL_SENSOR and SYSTEM_TIME messages - const int DEFAULT_SIM_RATE = 250; // Hz. - const unsigned long ticks_per_update_ = 1000000 / DEFAULT_SIM_RATE; // microseconds uint32_t last_sys_time_ = 0; unsigned long long sim_time_us_ = 0; uint64_t last_gps_time_ = 0; + uint64_t last_update_time_ = 0; uint64_t last_hil_sensor_time_ = 0; - uint64_t last_fps_time_ = 0; + + // variables accumulated for MavLinkTelemetry messages. uint32_t update_count_ = 0; - uint32_t update_rate_ = 0; + uint32_t hil_sensor_count_ = 0; + uint32_t lock_step_resets_ = 0; + uint32_t actuator_delay_ = 0; + std::thread telemetry_thread_; //additional variables required for MultirotorApiBase implementation //this is optional for methods that might not use vehicle commands @@ -1861,6 +1918,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase common_utils::Timer hil_message_timer_; common_utils::Timer gcs_message_timer_; std::shared_ptr log_; + std::string log_file_name_; //every time we return status update, we need to check if we have new data //this is why below two variables are marked as mutable diff --git a/MavLinkCom/include/MavLinkMessageBase.hpp b/MavLinkCom/include/MavLinkMessageBase.hpp index 3f55ddd35e..734594ae9d 100644 --- a/MavLinkCom/include/MavLinkMessageBase.hpp +++ b/MavLinkCom/include/MavLinkMessageBase.hpp @@ -135,16 +135,19 @@ namespace mavlinkcom class MavLinkTelemetry : public MavLinkMessageBase { public: const static uint8_t kMessageId = 204; // in the user range 180-229. - const static int MessageLength = 8 * 4; + const static int MessageLength = 11 * 4; MavLinkTelemetry() { msgid = kMessageId; } - uint32_t messagesSent = 0; // number of messages sent since the last telemetry message - uint32_t messagesReceived = 0; // number of messages received since the last telemetry message - uint32_t messagesHandled = 0; // number of messages handled since the last telemetry message - uint32_t crcErrors = 0; // # crc errors detected in mavlink stream since the last telemetry message - uint32_t handlerMicroseconds = 0; // total time spent in the handlers in microseconds since the last telemetry message - uint32_t renderTime = 0; // total time spent rendering frames since the last telemetry message - int32_t wifiRssi = 0; // if this device is communicating over wifi this is the signal strength. - uint32_t udpateRateHz = 0; // HIL_SENSOR update rate in hertz + uint32_t messages_sent = 0; // number of messages sent since the last telemetry message + uint32_t messages_received = 0; // number of messages received since the last telemetry message + uint32_t messages_handled = 0; // number of messages handled since the last telemetry message + uint32_t crc_errors = 0; // # crc errors detected in mavlink stream since the last telemetry message + uint32_t handler_microseconds = 0; // total time spent in the handlers in microseconds since the last telemetry message + uint32_t render_time = 0; // total time spent rendering frames since the last telemetry message + int32_t wifi_rssi = 0; // if this device is communicating over wifi this is the signal strength. + uint32_t udpate_rate = 0; // rate at which update() is being called on MavLinkMultiRotorApi + uint32_t actuation_delay = 0; // delay from HIL_SENSOR to HIL_ACTUATORCONTROLS response + uint32_t sensor_rate = 0; // rate we are sending HIL_SENSOR messages + uint32_t lock_step_resets = 0; // total number of lock_step resets // not serialized const char* wifiInterfaceName = nullptr; // the name of the wifi interface we are measuring RSSI on. @@ -152,14 +155,17 @@ namespace mavlinkcom std::ostringstream result; result << "\"MavLinkTelemetry\"" << " : { "; - result << "\"messagesSent\":" << this->messagesSent << ","; - result << "\"messagesReceived\":" << this->messagesReceived << ","; - result << "\"messagesHandled\":" << this->messagesHandled << ","; - result << "\"crcErrors\":" << this->crcErrors << ","; - result << "\"handlerMicroseconds\":" << this->handlerMicroseconds << ","; - result << "\"renderTime\":" << this->renderTime; - result << "\"wifiRssi\":" << this->wifiRssi; - result << "\"udpateRateHz\":" << this->udpateRateHz; + result << "\"messages_sent\":" << this->messages_sent << ","; + result << "\"messages_received\":" << this->messages_received << ","; + result << "\"messages_handled\":" << this->messages_handled << ","; + result << "\"crc_errors\":" << this->crc_errors << ","; + result << "\"handler_microseconds\":" << this->handler_microseconds << ","; + result << "\"render_time\":" << this->render_time; + result << "\"wifi_rssi\":" << this->wifi_rssi; + result << "\"udpate_rate\":" << this->udpate_rate; + result << "\"actuation_delay\":" << this->actuation_delay; + result << "\"sensor_rate\":" << this->sensor_rate; + result << "\"lock_step_resets\":" << this->lock_step_resets; result << "}"; return result.str(); } diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 89df650fcc..6a76ed9521 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -305,26 +305,32 @@ void MavLinkMessageBase::unpack_float_array(int len, const char* buffer, float* } int MavLinkTelemetry::pack(char* buffer) const { - pack_int32_t(buffer, reinterpret_cast(&this->messagesSent), 0); - pack_int32_t(buffer, reinterpret_cast(&this->messagesReceived), 4); - pack_int32_t(buffer, reinterpret_cast(&this->messagesHandled), 8); - pack_int32_t(buffer, reinterpret_cast(&this->crcErrors), 12); - pack_int32_t(buffer, reinterpret_cast(&this->handlerMicroseconds), 16); - pack_int32_t(buffer, reinterpret_cast(&this->renderTime), 20); - pack_int32_t(buffer, reinterpret_cast(&this->wifiRssi), 24); - pack_int32_t(buffer, reinterpret_cast(&this->udpateRateHz), 28); + pack_int32_t(buffer, reinterpret_cast(&this->messages_sent), 0); + pack_int32_t(buffer, reinterpret_cast(&this->messages_received), 4); + pack_int32_t(buffer, reinterpret_cast(&this->messages_handled), 8); + pack_int32_t(buffer, reinterpret_cast(&this->crc_errors), 12); + pack_int32_t(buffer, reinterpret_cast(&this->handler_microseconds), 16); + pack_int32_t(buffer, reinterpret_cast(&this->render_time), 20); + pack_int32_t(buffer, reinterpret_cast(&this->wifi_rssi), 24); + pack_int32_t(buffer, reinterpret_cast(&this->udpate_rate), 28); + pack_int32_t(buffer, reinterpret_cast(&this->actuation_delay), 32); + pack_int32_t(buffer, reinterpret_cast(&this->sensor_rate), 36); + pack_int32_t(buffer, reinterpret_cast(&this->lock_step_resets), 40); return MavLinkTelemetry::MessageLength; } int MavLinkTelemetry::unpack(const char* buffer) { - unpack_int32_t(buffer, reinterpret_cast(&this->messagesSent), 0); - unpack_int32_t(buffer, reinterpret_cast(&this->messagesReceived), 4); - unpack_int32_t(buffer, reinterpret_cast(&this->messagesHandled), 8); - unpack_int32_t(buffer, reinterpret_cast(&this->crcErrors), 12); - unpack_int32_t(buffer, reinterpret_cast(&this->handlerMicroseconds), 16); - unpack_int32_t(buffer, reinterpret_cast(&this->renderTime), 20); - unpack_int32_t(buffer, reinterpret_cast(&this->wifiRssi), 24); - unpack_int32_t(buffer, reinterpret_cast(&this->udpateRateHz), 28); + unpack_int32_t(buffer, reinterpret_cast(&this->messages_sent), 0); + unpack_int32_t(buffer, reinterpret_cast(&this->messages_received), 4); + unpack_int32_t(buffer, reinterpret_cast(&this->messages_handled), 8); + unpack_int32_t(buffer, reinterpret_cast(&this->crc_errors), 12); + unpack_int32_t(buffer, reinterpret_cast(&this->handler_microseconds), 16); + unpack_int32_t(buffer, reinterpret_cast(&this->render_time), 20); + unpack_int32_t(buffer, reinterpret_cast(&this->wifi_rssi), 24); + unpack_int32_t(buffer, reinterpret_cast(&this->udpate_rate), 28); + unpack_int32_t(buffer, reinterpret_cast(&this->actuation_delay), 32); + unpack_int32_t(buffer, reinterpret_cast(&this->sensor_rate), 36); + unpack_int32_t(buffer, reinterpret_cast(&this->lock_step_resets), 40); return MavLinkTelemetry::MessageLength; } diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp index ffa94d6879..b2c2496871 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp @@ -16,12 +16,11 @@ using namespace mavlinkcom_impl; MavLinkConnectionImpl::MavLinkConnectionImpl() { // add our custom telemetry message length. - telemetry_.crcErrors = 0; - telemetry_.handlerMicroseconds = 0; - telemetry_.messagesHandled = 0; - telemetry_.messagesReceived = 0; - telemetry_.messagesSent = 0; - telemetry_.renderTime = 0; + telemetry_.crc_errors = 0; + telemetry_.handler_microseconds = 0; + telemetry_.messages_handled = 0; + telemetry_.messages_received = 0; + telemetry_.messages_sent = 0; closed = true; ::memset(&mavlink_intermediate_status_, 0, sizeof(mavlink_status_t)); ::memset(&mavlink_status_, 0, sizeof(mavlink_status_t)); @@ -246,7 +245,7 @@ void MavLinkConnectionImpl::sendMessage(const MavLinkMessage& m) } { std::lock_guard guard(telemetry_mutex_); - telemetry_.messagesSent++; + telemetry_.messages_sent++; } } @@ -441,7 +440,7 @@ void MavLinkConnectionImpl::readPackets() } else if (frame_state == MAVLINK_FRAMING_BAD_CRC) { std::lock_guard guard(telemetry_mutex_); - telemetry_.crcErrors++; + telemetry_.crc_errors++; } else if (frame_state == MAVLINK_FRAMING_OK) { @@ -463,7 +462,7 @@ void MavLinkConnectionImpl::readPackets() { { std::lock_guard guard(telemetry_mutex_); - telemetry_.messagesReceived++; + telemetry_.messages_received++; } // queue event for publishing. { @@ -490,7 +489,7 @@ void MavLinkConnectionImpl::readPackets() } else { std::lock_guard guard(telemetry_mutex_); - telemetry_.crcErrors++; + telemetry_.crc_errors++; } } @@ -565,8 +564,8 @@ void MavLinkConnectionImpl::drainQueue() auto diff = endTime - startTime; long microseconds = static_cast(std::chrono::duration_cast(diff).count()); std::lock_guard guard(telemetry_mutex_); - telemetry_.messagesHandled++; - telemetry_.handlerMicroseconds += microseconds; + telemetry_.messages_handled++; + telemetry_.handler_microseconds += microseconds; } } } @@ -596,14 +595,12 @@ void MavLinkConnectionImpl::getTelemetry(MavLinkTelemetry& result) std::lock_guard guard(telemetry_mutex_); result = telemetry_; // reset counters - telemetry_.crcErrors = 0; - telemetry_.handlerMicroseconds = 0; - telemetry_.messagesHandled = 0; - telemetry_.messagesReceived = 0; - telemetry_.messagesSent = 0; - telemetry_.renderTime = 0; - telemetry_.udpateRateHz = 0; + telemetry_.crc_errors = 0; + telemetry_.handler_microseconds = 0; + telemetry_.messages_handled = 0; + telemetry_.messages_received = 0; + telemetry_.messages_sent = 0; if (telemetry_.wifiInterfaceName != nullptr) { - telemetry_.wifiRssi = port->getRssi(telemetry_.wifiInterfaceName); + telemetry_.wifi_rssi = port->getRssi(telemetry_.wifiInterfaceName); } } From 62048e5c8b563695d973a77ea3701044eae03136 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sat, 17 Apr 2021 21:52:34 -0700 Subject: [PATCH 11/37] guard telemetry variables with a mutex. --- .../mavlink/MavLinkMultirotorApi.hpp | 69 ++++++++++++------- 1 file changed, 46 insertions(+), 23 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 29a77e8f88..f18336a6fe 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -117,25 +117,34 @@ namespace msr { namespace airlib { if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) return; - update_count_++; + { + std::lock_guard guard(telemetry_mutex_); + update_count_++; + } auto now = clock()->nowNanos() / 1000; if (lock_step_enabled_) { if (last_update_time_ + 100000 < now) { // if 100 ms passes then something is terribly wrong, reset lockstep mode lock_step_enabled_ = false; - lock_step_resets_++; + { + std::lock_guard guard(telemetry_mutex_); + lock_step_resets_++; + } addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); } - - if (!received_actuator_controls_) { + else if (!received_actuator_controls_) { // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. return; } } last_update_time_ = now; - hil_sensor_count_++; + + { + std::lock_guard guard(telemetry_mutex_); + hil_sensor_count_++; + } advanceTime(); //send sensor updates @@ -563,6 +572,8 @@ namespace msr { namespace airlib { if (connection_ == nullptr || mav_vehicle_ == nullptr) { return; } + + // This method is called at high frequence from MultirotorPawnSimApi::updateRendering. mavlinkcom::MavLinkTelemetry data; connection_->getTelemetry(data); if (data.messages_received == 0) { @@ -576,11 +587,20 @@ namespace msr { namespace airlib { else { hil_message_timer_.stop(); } + } + + void writeTelemetry(float last_interval = -1) + { + auto proxy = logviewer_proxy_; + auto log = log_; if ((logviewer_proxy_ == nullptr && log_ == nullptr)) { return; } + mavlinkcom::MavLinkTelemetry data; + connection_->getTelemetry(data); + // listen to the other mavlink connection also auto mavcon = mav_vehicle_->getConnection(); if (mavcon != connection_) { @@ -607,32 +627,35 @@ namespace msr { namespace airlib { } data.render_time = static_cast(last_interval * 1000000);// microseconds - data.udpate_rate = update_count_; - data.sensor_rate = hil_sensor_count_; - data.actuation_delay = actuator_delay_; - data.lock_step_resets = lock_step_resets_; - // reset the counters we just captured. - update_count_ = 0; - hil_sensor_count_ = 0; - actuator_delay_ = 0; + { + std::lock_guard guard(telemetry_mutex_); + data.udpate_rate = update_count_; + data.sensor_rate = hil_sensor_count_; + data.actuation_delay = actuator_delay_; + data.lock_step_resets = lock_step_resets_; + // reset the counters we just captured. + update_count_ = 0; + hil_sensor_count_ = 0; + actuator_delay_ = 0; + } - if (logviewer_proxy_ != nullptr) { - logviewer_proxy_->sendMessage(data); + if (proxy != nullptr) { + proxy->sendMessage(data); } - if (log_ != nullptr) { + if (log != nullptr) { mavlinkcom::MavLinkMessage msg; msg.magic = MAVLINK_STX_MAVLINK1; data.encode(msg); msg.update_checksum(); // disk I/O is unpredictable, so we have to get it out of the update loop // which is why this thread exists. - log_->write(msg); + log->write(msg); } } - void start_telemtry_thread() { + void start_telemtry_thread() { if (this->telemetry_thread_.joinable()) { @@ -651,9 +674,7 @@ namespace msr { namespace airlib { while (log_ != nullptr) { std::this_thread::sleep_for(std::chrono::seconds(1)); - - Utils::log(Utils::stringf("sending telemetry, update_count_ is %d...", update_count_)); - sendTelemetry(1); + writeTelemetry(1); } } @@ -1426,7 +1447,7 @@ namespace msr { namespace airlib { mavlinkcom::MavLinkHilSensor getLastSensorMessage() { - std::lock_guard guard(last_message_mutex_); + std::lock_guard guard(last_message_mutex_); return last_sensor_message_; } @@ -1525,6 +1546,8 @@ namespace msr { namespace airlib { { auto now = clock()->nowNanos() / 1000; auto delay = static_cast(now - last_update_time_); + + std::lock_guard guard(telemetry_mutex_); actuator_delay_ += delay; } } @@ -1871,7 +1894,7 @@ namespace msr { namespace airlib { mavlinkcom::MavLinkDistanceSensor last_distance_message_; mavlinkcom::MavLinkHilGps last_gps_message_; - std::mutex mocap_pose_mutex_, heartbeat_mutex_, set_mode_mutex_, status_text_mutex_, last_message_mutex_; + std::mutex mocap_pose_mutex_, heartbeat_mutex_, set_mode_mutex_, status_text_mutex_, last_message_mutex_, telemetry_mutex_; //variables required for VehicleApiBase implementation bool got_first_heartbeat_ = false, is_hil_mode_set_ = false, is_armed_ = false; From 938046f8f08ccfe4112aa0286fcbb148c2d2b368 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sat, 17 Apr 2021 22:08:02 -0700 Subject: [PATCH 12/37] make actuator delay an average --- .../multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index f18336a6fe..ae39c32fc5 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -632,7 +632,7 @@ namespace msr { namespace airlib { std::lock_guard guard(telemetry_mutex_); data.udpate_rate = update_count_; data.sensor_rate = hil_sensor_count_; - data.actuation_delay = actuator_delay_; + data.actuation_delay = hil_sensor_count_ == 0 ? actuator_delay_ : actuator_delay_ / hil_sensor_count_; data.lock_step_resets = lock_step_resets_; // reset the counters we just captured. update_count_ = 0; From 9608bb4a1bf910283756e818995d7262016bcde1 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sun, 18 Apr 2021 10:32:53 -0700 Subject: [PATCH 13/37] add missing script files --- PythonClient/multirotor/Error.wav | Bin 0 -> 331108 bytes PythonClient/multirotor/speaker.py | 37 +++++ PythonClient/multirotor/stability_test.py | 2 +- PythonClient/multirotor/wav_reader.py | 158 ++++++++++++++++++++++ 4 files changed, 196 insertions(+), 1 deletion(-) create mode 100644 PythonClient/multirotor/Error.wav create mode 100644 PythonClient/multirotor/speaker.py create mode 100644 PythonClient/multirotor/wav_reader.py diff --git a/PythonClient/multirotor/Error.wav b/PythonClient/multirotor/Error.wav new file mode 100644 index 0000000000000000000000000000000000000000..c4a01cb2b4b7af6445d018a7407d2d55d2378b44 GIT binary patch literal 331108 zcmZ_0b(|DOv^Lz{J-RcyKyV0d!2^Wg?(XiI;DHc=6Ck)-&=A}uKyW7z+%34XyR$pi z-u*o_bNA-He|+=&c3DQc>r|aO@|;uCs$so)T|7M1zGl0+{k|WS*GEwlO)*ryb`&+U z15I(1kLuHNRL@~99&Mji}4El?um zqMVe6@=^)7M+V6MT$G!V0ES|5FALYxaD|8+1Oh-R5U|tibRZ0@{th{kkQ9~lY5de{)hN8@pq6l)UaL(?n>?)my!HG zE}wzOJK7=6)S+)2Y#-$|k5j`RIBs0%q&IN#c zKE8hB4(|VzPsD5F-ehgaTE$l-L&l6X{C_1Rt4PL7-c4qLtT&P6zcq}+VU>Hlo91yyTi>ej@*)qht*;Ky;QoPjr;L@4vYt+CeluE+zS! z+$%00(NUuNWDSXI85&BiV8&!7uf?Ux*nvd8`1{FTi0?u&s`wg`zf{Of)`DD|g-pB41Q{w6aY z*HJz;Z)AqaOogDO#IF3m^2K$O+>bnnZv0;zB`X-eUVIOd*E04Xc|Xz0xO`;f1Vrk% zgk%jfY-vnjjE21apNPYvLm))aUG4XAF(lHzR6g~ULkiR zpU=?I4E-dM5-UUYV0?dDSVIAw=zUFGG7^cP>Q`Cw=o$K#@8^uesTH8D;XM^ zv5G`mG8Xdg3|~RyBOWonit#lht4ux{x1$-pFfJjHk62MM=fn?Y_=&h3RUiq`Q6gh} zClVV<)|JRd=8lXYzJg?blT{;<#X;7O%$WcQiH(V`VB9Xo*Dt=7aTzjpVO&Gw>m8T+ zzcnP@o=6x6v8rSp{u>9`D?~@h43qWq#H1tt5*w4T2g$XG_K=y1Kt5tOGbAK`5#K>{ zB)$iU{UUxM!_LH4F}{Xm55|2D8lWKwKsw#eeoBeqAyqGOGCKh`o*fpS()ugUC&;N5(~dXMp@KZk;T=i)c0Z zWc<_dagyKhzsR-8>;Lzf|MzPDNl#{j?CJQ`$-U$9lTT*MK*n|BGaA2c#+t-O8y|1R zRpR4}uONAy>?ZOl0&>m&5PyzbD;@*HuRz8^_UM0-$LAt0J&~PUk;opGHe-EAR1^Q3 zJWuZO-zei(Cf6ad$9DnwD}Il-^l|Y zA@T8Mj5=e5{{Pk}V}-~FGjt(Clj8G9l-xZ-OUaeuR)+kJdw%j987YyJjEUG05>XNSUz8%GRUr}d%g5H+)sS<#|uG%GMK zGB45~QZLdl(m1jUXc=u0ts&Qte^P!@-l^}^Y5G+C8}l2Jvw8aw^^p3V`JHLcwdYd! zRKA_qPMj|NB8_p3b>w#Da!vtOIe&9@2VOW{I5Go1DM7j>To*d=o%wU@S=P_^nYI|y za%+Y4&UkAy)*I^&)raa5Wr;FFo+1AgJrXS*EfM_~`4CBq1R_Kcca_nZSr5r zQN>Vob$~uV4;x`)k+sPBhWdtjL_em#XTN7(aj&@2LTRCy*i5V-eJ#C}-brm7Z5&g8 z?;L|2iNILtCuxhgNn9hW5&H0bc!3kR*~~1)rfh1k{hj^9d}4Msx)>2HqU~4rt810D z%4zwOoC7!#Jse#cT^2nEWRbJThk!-OVr7&1hx$f)qt!R+8yC$BW^22R{f>G^jbcVI z>1;aNns37|5atWNiNA?Mq@j}F5FA~B;Xn;XO~(!Cx|9njEtV1ef?v4EUF15j9of6| z9l9n}liFqNwhEX9%-#BKy@S?4E2b7xODZLm0rEikW%NaKRdjW91@H*yB6pQ@Dmj(R zY9_UcR#ls)&(%%CG^SWnEI*YEaG)hg8T>*wGW{ z0Jwnh(gf+Ccu+hb91y1RQ~9D?QEo4@mnlFOq!-u=Y|FIFamF~qr~CCQ>J@d5vRnCE z{#(u^=avsf4@74JTccZ|f-K6LfJw?EWr4aty`f##${J;jJ?37sx?Rn_P2Hw?Fg=;4 z>{GT1Uxgnd{3uKlr-@yp&Qe5@rB;qsSiM1x>cDO3wp36mB-IeBi-m+j!VB&t_ai%o zjnGlLAJvb#W8Japn+?pH`VIXDZM0TLt)tddYAR#oG4iMAr|3FhDR47-JK9WcDmxXY zVj&DFs1?+H(0|b1LMI1XgDtW*=hAcOBsPhi%uV5L@i+O15Eb5wAH?6K4N@*gE=PNy zsiT>L0Y*!srM==Falf!%n8yFYm*L8ACzumVMYm z_mxyR6+5kld<&!bJ-RV^2yn|T`FCKXGD`Vb{Yl-Y?bEzQg7K?4!^~`Fwzp7QsR~R* z<`8>`&CX}%I|-eH!Qx=Cq0~V72sCyyj?GnlM}5aj>4j7U=p=R$>j?$@p zla2Y6`jwI`*&1vPHiLRlU#>0JdaHfZ?n-xMfxJMrqE>V_K<4Xi^iH&a+(6cWkIF|y z(nPJL-bz1i95aAPn?>wm zR^v3Tnovz>FSZveOW(pWypvjBOk*5BIywWUWJ+CuDdH4ym@r%@&6nn{uvgdyOatam z>Q5?%ox`4qH4qKa*r09D$o*O<&7oI6%1@$CqEmqHqu*gK{ucGhUiplCR^F@ZRc@=d z)qHwBeX+6F$Z6%Y4%i3nCUj%^G4q&d%eCe9@O$}}!VBSr_)^>|ZI#M8$~k_5J)Phf z@2CnKm5xfPs3Lr|ggg9Qej+!CbFnUV3O$7;xl&iFi*?VqXY|wi=~=WaT0luv4B3!t z0_UR_umfjB7XvSV@8uzKWu>xGMXjn1(}rpP=>O<-%sS?6>$cUO8bE2ZN{?qJu|DD>^^A5ZeA{G^dDBMjzvi`Pv*|kF*6^q?a&D7!T*=2J?gX4Z`ojHgTIcP8ugAI1(JafDu47 z;F5GnN|gN4mtsD+ZkylB?c-{(wb-NdQMxcyh$8+1%WN*v7wOet8xz$;HLH?U=^%HI z??JDY!7eNZ{snr=z2(A6Atk?>Pi?L>*EZ{$^c-eRbCb0x=5wynSLv2)OZFspigO80 zp_o`)%p!duT?WXy4Rs8O*?7qzIz~t%rS;-^afPs4=+5`xZPsR|G1HhR6{ULEJ?xw2 zO|!Yt-1wk<&^D=?)kVreWxsqtP5^dAcSh$#=SKHM_eQ^vzmSgutCiKtKKQ1P7ScKx z9gTACh?_#E4uWK1%$>)G`O z>I3zZa$0#RKbA`a7or#830KGLs89CGJLMhn6lIDsSDmL`)-G#BjiSaTbCX%tE^A+) z&Qq2tT8uV^^kDb@bYppfb85Q&j@HuJfUFEKlBB#LP zREN*G72Op5BYGlwESe-IVQ21;C&NF_Qh!y?YG<{)Ms8!dx!nBH{?gt@?W4YBs=((Q zW;63y_!dGdp_|x4tSEgW-IpFp6&&AS_1ZhiI?6k)NjET4#iYh!W3i%8QBXLUTf#16 zGc%dsbAF)|D{KujzcUp*qOZ|bXoJ+gY9FPCvQ%Cqb22UOhn^GrejjKoH<3-5Rz4{y z@Hrl>mEJ)=X`C}^SoN)&_5-^o-JgEXq%s}3Zrm<@AOApjB-|G7ic6)XQg%mHM-N9Q zL^E9+c^%mtYw_GO@t*h=KIa&0Zhx*T7iK;&gX!M%L;IFp&#G>nG>#c9^kyKqXzhve zO!*|I$>rp49oyneJ&N2nVXKc|9Xy2DhD`c}q{LxAoX~Vhq#= z>)EyJT387wltL>F<%aUL=(U(#SQA|z{TxljT#c9OC=HZ)Y7_NGZGv`7f2cRaUb%xk z)1MkbskB9pV<)n2xer{4n9r#vmXeCY=iHMTBHkP6=nsu=;xMEXsfW~DnjwxB#|Zs| zZ}?*TJ@#+59n+Y(NS&g}*d^=@<_0sLQOG!jy*>qT=4fTQvPRx7Q*u^$bM!RkY6~Lx z+tK`TRr!YeUj9?LqTEnls$b{@^r^;d!(q9t)%Hre3|)ji!R%owa{0Lh{Ez%uVY6^v z+$_$MhCr`0sXtowx(MTo2OvIW`Y^zSr7B~jm7Q?1vA zWeh_co=dBOxylS$F^^JH?g{_=GCC8wz6eqBi)dPOh&)#QMyak;gMS{WeXrfn&+Cnl zdp)$ySwoRC(abw~8rz>u6T-~D1RhBD<=Kn z$6*`RMz2TDMZb}Y%daq7=Mc+0RxhYIbY7om3^pwDlliOtqn(v@(i@m%Ocwa(q5NQe zov>cmfc)w^_&gn%PGi`Gj#$I|uns$=c1v$H% z4>{pUL=0Tjw)(~5b; zUS(_Y#rbhUUtv1|oy4-|7>z`C2o??oE;BOp%w%k*Gu7iq%^KzjHtOKH5U=ft>IQ z#Z*K!k5*V4qL0x3HU2evTHURXoor8|$I=egV8(HSxPSP+_>k~S_$b~MH%kkof|#LR zuvOh)<1-=Nnhmbuf_PZGARH5x!RA(nf4;(8W@^xN=w0@ob{?xJ{PT9Byj}wp(uVAin%Uci+j#Z{AlhhgNA?=vvH!>Ns;2Sd8iS{4Vda4vt zl-bGt!FqU}Z!FXjx`-{rN>WMbv2+vhXgS29Z5)-c2k*l_mz7FLZSZjz-U?J zGazb`)*Qa`uyNR^WL2=v+vn_7;HvI1cbGa{ZEiWgls_Y!5{`*S#R<}QiFa^_u$nkp z07=LRmq<&bhvGx{=eNRX{xm;=8_DsAgC-*$BDI8GRxj(B@eFo!m`>s*8(F&>XoI;T zan*X*1`=n6|{EOT|X`!@KTdGsEsoGQhiQdX=Z9cJ{!j2B5EZU|g!smQ|&mnnE zeX+h+0&{X-dLY#VA2SFb`D!}sXlr1sI941i3>HfACHa5Yf7m8W6Xqm!k}7T&x7V0! z%)CZk_?%PPG;Tq0F&qhgn`mg*!>~ijite)+g)bwF<~{{AwO0uhJKG^h5MRbO*+@AJC$D zbecR3u}mZQ=X&ZWZIpINzob`&&pBzGvYJuNsK?;eIIEX^>6e}LQ1)n)6l#6Og#N>gj#FEX2% z%=P*Py_wcj%ZGfgh*Cu9FZYvQMPJ9_b`rb41qR83;B&r$&ncp|(pn)W+^lCav%=@B zvr18=sFUisW8hp<4+KFY=s8(x2j=F>Y-VKZ!5M72>8R=Kt`Jd(3Jv z9`Y8|lj+4gXP?98)a1ttyJ|4RR)eo}8M zw_`kHZMn95Kl%WcVF#kV^HIX#9tP$pbChN3GW8lb+hRsB<9BnTN$lP+>KIjrsmq*V zPqDf9+gSLX zHn194gggA6{+^C9QDzV~m^;azN7QI6e||52kjn$75%0~z9$X8* z6O4wUq;}B(Iblz=r@Bg8r760ik1|J@jLq09sTEXFrWmt>-N`2LNql>uz3{#GJ#xY( zF|L8+&SLv{l+VZJ&mJZbd(0 z9)YuM%5CI-=Whr%g=^wfagnqLTtjwP(4H|4q_Crq;}2<*^j>@~284h>c!?3*2o6nw z>==3s{nmbKx3XGU*NkgMH@%zg(|lSgct{J`dwt+K){XFLe;}d>1JmH2TPm%TwrU%7 zrZ!W1rN7oYnH|m7)@y4tHHH!xo|(Z;N1hYl$_eF!reYK1Ic1O&K9TAn4jlrJx{i$6 zKu2J*I7u81&bB;Xp1;lBW?M6@k>{MJO4+6C_2xSG=P!+u+DUD)I$0f|3|CglD`hik zB4$`0ogSSL^M!fjJn~ifntV|CQ@I7sHV62n>Be-!X}ORSuC~k4W$Ba5DddC|xrO`! z{+w_QIpKM6zBC{Cb53N={gG1)gSJJ#*@w2~UHa%zH-ptO`*BJR5dwstA9`jyCdUPr%^zmv-=fcmxCN9(N})sN|A z%(CWj>$pX1@(cPU-5Yl226v77Lij=`Czca)qLy@3`bQ!>-#~!O6|rA^fJNdWaVC5~ z3)BchY>*wxjAc@(0M*s*YTp14*~(~T1hhcRKd({ND5vDp@Hjb<=N!QbE<^r&IGO{Q z&k5i+I*gcWwgsG{_lo$`$jqlE{5LO7kBflC0ZqEaI-Uk@t z7>$*z2X5`Qlou$AT-GlnqV{zGc}_d_CVh*pN>!n@SX-@Jgm;CnZK^fX@~U~%d`f<$ zo7@exfCtE(7e*HVgwG11?JmIwHR9J@fsG``>welKyoH9Ow@0ei_1_a9D=%uBQ{s#z!;Hul+<&|0u9B6VsY@0q~7@h`vdZv zG`cI*mAYhIvMQUE&C~j6y|30+E31|TXIlz!UqAU_^kFP!Ao_j|s0BO9fU{A7{8|BR zj6PaVHj<4WtkD+ftXfO2r3=I7tl(C1ANY^FSM-XsL`#1G<-zlP2asAJsi{ttrb&N^ ze~E{LL#TaC)xZN#=>EukiAUktyFUCZWW@-mCS(V^UHk1~HSbzRffY3sDX>LBot zeUv5gQm~K|)^JD6=Ul<~sv&nJwK`%)$%NH{9o=p0Hi&mjOkVxxr!)LyAJpwu!xs>rFvc8X5+AV~ zzM>#}#zy3X5-;%$goeloyP)<}88h`6nZoIzqIp`(zC&&3~S zkFhnF8q7h|z6#j+?G@$`b=uNPGApmXJX$;o>NjT2{!(*d`3B= zJW-#Z_VuMc3v2JOJl0x!ja`~9Lmy|3G3B`O++2Px@|;t`8Po~qNOL5z@A?A7zLx_I zONS*xG)0FfiLdzA{K6QwmX}>gub@dU%P{0Q?~V7yD1DUvC2~Rq52Dj`aMjhrA8345^Eg{3|=`=sDC0|4=q5C)DFA>CYHo3^bC>&*sne&vqi6 zNUvwsGdZ{%+*p1rzgO5N91)L*Go_jE&p9051LGV&JL&?&-e&^xq4q`coSocGt}Kv0A`lFf*j4L+XTsLwX6bxOo6Iq54#P>OOs+CjAK{Cv*vJp|Dt3Bz3p5(iw@YTW>@T%`s;>Sgk%% zUuiM&jXA;`p&j3jS6P*v$V`gWzWUg`?fd3^vxCvW2&3QPPjF_xgIha~S@{y&+6i!L zYoO~VfqeM?CFF{mFjq&^!>XbwS{L+bJTf1d{q6oXwk$OnK1X9UwjJM=pCil`7K=;7 zzPLZAiP##FIujY+S&Y<&@fH#biIN}+$GPJispVazuhCWDb9PuetbArZa}WA0I-&Me z61A_gN;zc+>Zk9)5s_Lw;Tv9nzwIUWlJkLE%c15#>|R$}p|8-Lrqd*~#sX9U>L7iP zuEbUXx3-x}=hJw<=oc-3~WmC~W=)@po~Zuud4l58<(N zdX_y4wJ$SP`y#OksePS})xMs}W#qCkeg6$n!$ELHKGY3&07UN=s0-Dr+EuNjQPS99 z?l3FcmF*kUb*dZFjd{lY%hup)@I;U2qLxean&hV40TPdrUV^8n{eA`15$nYIEuL~u zxuNV(_7nYyZcnwR&RA!xug$N`lllq0x7G)F4!jQLYA|$&^rn!$6jFb_4G>*Rgw7G& zE3cK)rt33w-O!Aw;K;wAvQXRTt#m22G`p5t%O&%l;d4CL{RZahKrDam24<}#^vafO z={sPpxHiVw_T~HXPR_|KMxEG2yXbNDIPj3^<|t#7k*Fu>_tbmpIpv)44xE1-;05y2 z6TmZ|Ds1~R;IMKST*C#`(k$pzXXCbc$LwHtuwPTJsJ={J<{|r#Ed~CkyU-mzr&lZ< zJujVy&B}_*z69bcLz)W^yKe}(@Rona|H1tct3O|%FVl6XI@Ag4ghg!5ef_>ZTbrfz zN9;ZdeIAFwgMKYnKn_h1jFv;yX+PM}@09PAu4-3xy!Nw3a_+)r5pzAbhP>35)Ovb7 zdQ%eFq1;ezC%=O~A)FA_i|fS3Qe!Y4$E8%@1+W-!0QJOrVsoK|@D*Qzf5X0ECoz*5 zH|<9LJkQQzWwCY`JB*H~uN4C4nODuL5>ANdPy@v8`N3;f2T0sZ;t7j%%z&>ft{2zG z8b2D(&F5wtyDjwU26DpMsC{i=1Bl%-p|0!^-C##=i`}K}(q7;!Vy)#sN$AupahAAO z*eh(|xA3F6(Oe?70> zDi1i*pZ1^OxdP{aHL&$CtD2s{EBDh<(1ldh0{ zt()LKumSa2W-W7#wb~-xnd$G7_N>`yKCLGQRu_k4t)d(AM2$%NFAg+jF;)ac3@|7v$@s$YW^3@MOCpH zB8RhL0(uPdNnc6`#nEB+o5%xIgepP7l&s;M18ZpX#_~;gh9gYH@#bogNx z{+2({6V%V@XXQtaUj%jWx7u5c-qx zoR9m6n)q(?Ymi>LoOVw85o%wXjLpVu^mHuJ7HTKelj;}Ht&Q;0y@8IvFW}QYp)YKr zIzg?a)z(U(_FUDdY7kCmqxHM>-hOYBTwnm|kBiwwEU}AA_$7Q7p^E^bTh>>R@pKEEhG)o#^83px%=;f&v%k4v` zLoWwL0Hp8ZGEf`+f2qKE?VNU6Kchc39vd#?^bPC=_H1enb%nk{>x_>2WfqQbGoRph zNWS`o_yw$dPjQU+V{A+a6JosfKm1ibl>^vR_7-!CSx;|>%~cV*NQ|@n+xXi!tRK-Y zXy;>V*g@@}zC&GStFi^!v>p}bD+=k~JPM3Pe`067v);q#VN5h9n)|GMRfZgYG(yO{bT~DG1HLOIG4?qI) z_yUNd zzHdj-Z{|ZkWOgNniO@{i;qH)Z1z8wfpLQbqaX4EY4S-7DkI$Uig=GM9U8x zR*zt|enOT%5FJi45fMI6TWBp%p$}?D;GfnSYmAlVDswCNrqlMB7%!7br_y02#JpwS zvPY344B@}$RbGkp+|Co`35(HR*IyWb>bytzmH(B0g4oyte97iTJvCP>77e0y`N(=? zT{izVFB?~kSNbbGD=mPr$a4Ja#{Ne*2@Jvx@PpQNsMnEMt|i zYT32z4pawf5Iu+enVYSJ1oTc=d7 z=GA5ZMfAe33ZHb+n|sPUX`Z((Shwuk_Dkv|^^yKazXk{LH+z{~%q`|fANOhS8`*{I zShe~>10aWxOSs5igh#5&ujAHpkJ!ho4Bu>{9t#Dc$hp5a)*I`U`N|9!0mBcp)LZC# zF&`DtSNI-%O{5lfO}(xn&C_~ny|j<$nOv$b)q6n(()V2*eOz_yx^@e2qwVPqbX%rv z%r<1_vcqEC;s)>o_X3iKx4g+S@zWsRck1dcuZt!??Zd zUiL0?A00sN=#SI~iulyGm@C2+P$px3Wt4!vkJO)H?+?-jYB{w$nyH$qh+ge)ftBb} z%cbW+N6~qGrtxdcH+QhwS>&ujTf{}J>DF{Z^g4gVe#Ppn!R|tgQVsiT8)Ea%@QP?k z6w;8t?nCcfBg9q5xMQ4~b8$7;nrvsLGt&>fcmt_{*n|CT(my}e9BZydzxxCI9x6>G z^{v`g%uFLKla?7(8;4d*E2@nI-fHi)pY@;hGU)x_Ox8?BU(s{xrA6#9Id5_cJn(Vm zII{pfgiW|6U}rwYV)%pnLH;@LFMj?6dIBF&&u@(PEW~?HFejP&^ga3|^0)V}SE*Kt zMGit_HM5zGjfMuv(@9-{c|i1onlTl2SKK;b~o6o zb` z`2kdaYJ@$?Cb{og^blNyZSbJa|2zFV{WI$03xUo+Gk}a~H;_%w1{Qp?-pXig5II6- z*nEcGmYeo<`z-1m`)G9XFpHR;=o2FPegM5sCD1!Fo}a*P#yW1}w}YLX##aE&gJ&;; z*mwdsuY=41%++1`1ND(2-yOgK+0d6z&8&tTdbDv-zlc){74%E!tDCG%iS4`o(6J@j zQmo%Qt-Ib!HxXF>X&f@9nZKAl(W}t}IZkD&GF2F{jE8YDuYjG<_jX)s?k)CNW4=Bt z=5&4|zm8wT&*3|P8`9A$`V;cNr^vN)z(+MieQ_}C-FWI}ig50~S-)9F%%kRebmlwqGjY~sEHR7A`1Hf_q?%L|g;m+e;;9TlFieAiZ>@GHkoyQ)b{irpGHjQ#)1J)RGmDw&%u5pICJyxu z^rqpA!+i9yJ=SmOJtOTSYXi#y(r4>a!Uz6C%DWHm{(8UvebY~kKTSxToEk>(Tokpa z_0)FiiSSxz;%?*q)wk5wAgN_i%S@d!ZA#jo^u2$S|Ayy*rylCfq)#Q6o!cG&J(!MK z$K%k0(8}Pl;GN+0;7{Q(;m*j;zXCrn&7N*YS%uAx4y|#nNv`vrE1pB%6W)T}GTwsj zvhIiAo+lxvn`lq7>!IhbL8N{}P79{(O4*ch`t#AxJwA8%yd-&Ua+5&)K*vz4P#>kI z;;Gw>hlddLB^w0JCy}7)59Y-7&P!~I6U$Q;A zM|Y!F!WT{mHxD)ozDs|Vem!_O_#yl2MK`b#}K z3MM^K!|mv5?pm3!B;i8h--&B7ZOD|KNy&69>0DAKe|CRyPdQI}shcD-7Bk+QYIeX` zmOv;RT9LLgZ9(dSR4pZxax3*}DwVFL)eqMQw^y1e*HQ1TPJd0;w=WgdN z*A`c2S6kN&$7M%Zv4nUHeM%~Nb+aO7T&gTnE=K;27$Gw>Ff=$+FkC2HBw94u6n*L~ z&=>WbenBr1mI|aedDeT%JI?>3|3l)N#D5bXC${sq^AGS2@-}ofcQ)c%^Ed2Ac3s3x zc_Kw4=hLpG%}!aAa`^L!&;36S{JbuCU2>Jcw*fxHgtp-f(+Tu~-G}|2i5PB}bEvbn zr;g{k_Xarv;{Drm+4G%iu&aQSN2&>3DoGWini>rZLy0Q$apIw7q)McGNpS6*VWhc!SmTuGogM$orH!7uRL!(rCeoQ-O+1(1abFjbEP>- z8L8|I?GGIeoCv&1{**lI^SIBGKhOJ|Go@HczO<5QZNojoJ#ilLx%JuV%njfMq9*x= zXOHKI@09Pm#G#3s6E`Ie^!M>U_1^VXb5(MEL|vyQQfx00Dc;mCQlA7~2AB{Zs)s)K_C`13ANaEhVr{XIyS%%i zuYoUHQsJbznO0}|In&HcZxT}yQxbv+_g(j0st^{=(1+<&sJjHgL=_2V4*!xqG`(_K zfwcB%HPWu9A4wk??i>!I2FDp;y#mh06y>sUW6^W)z;VUlaxpFgg`Mq=osMtCn&M|R z%6d>kV2v+~(&*(5h24>j!4ts==_}HAq+duc7it=!qnV@sA`TjdI>S$hHHV|t8+3== zD}2j+zNCbtyqR)k+MWa};@|1->sANnr(Zox)PbPaOlLG{VOMCi@N5~C05%lm_yf}zy+sUws7 zClCDG_4B*Wk3YXmd5}^%y-@nEktvadu=W4ik8K>;={U%{CbB;=K0H6XC44BH6wMo5g)>nGg0Yu~ zUp}!Z>|SxVc+>fhQ*{U2$)4x1{9`@$Tqj+xQSA?LPq_9}HENjNQQwI={fJd0Q}hx3>R#xs*1>Urr|?>Ojq#f3S=c2TYLK6*=>i)t9|79JOzAEbksgU^EL!BCiui0EIq zh~B~LI16~3-NzOcvx{dP`y6#$rCqaJ!(7vygPko@D_N^a}+XjI)(@uy?=zhW}F1o1~tZ zCS)3(G%v~RFY52-ne4eNy^>bIe^#}cTgAYeT?*d_4^00qy;Yz^;E&YRseJ>T17p$$ zr*8_c2(QEWD%O;Z!E_IL2)LE~=xs@JK6eIP&s{rROI(GV9_Ji!sF;Uixr#V*T@^X& zeAJ{DMt+IR56uZ(3|0PZ;p&N6M%x9O8{X7Gz(rr@d6!>K2d4i1Elnav;Am9Z|a4Z+Gt+?=tU1&kvr`u7a)r*3icZSfdo% zVNk{<^ljveW{>_A-XC5No*mv9*%^uA>}FZilyjmdrVTp?duWd6a}{;n_I&aTOZX+> zXu_3*HQp`WBJPsz8PW`i*jWvIS$EaTDjf-h-=#fDd!BMLrDSscWc73KbHkK6DO?(z z77PVLXO**x-||_*Q5PD9D%KA7HupaX|0FE+ukfe%1O7X{d%l5KyA)@@`6oE6f=m%+ z3pm&fu%X{ahecb3TZMlNjSi)TK8H3$)hnpiaPI%0-EQgYI~#My~g68=tj=X&KT3&u7F zla)z8vGAsF86}re5&AKJ>P+>(dCpVlQ!L{w z;T-4s$u+?>(^b{k%y~yl5yx|DxH*VBdl*xUZpwJ&V_1lE501eXGbN=fX+nC-V3(j4 zrXwenQ%Y;IiP;|KT6*FfJL67v-Ag!;Fe&l-#H&dsl9oc}U-+N3%d6tW24nvLcbEs$4Ou0#(BJ+E@t|{7U3%L<&2?lS5NN^}~(A zt)m^Hqt$Whcjid*U-~WGOBf_9axQl|ye{uZ-w5A)|7?FXe|i77gzpmiyIZ&`p&zLZ zdP#!jZF7$@U-=li9^%r{0hBNPw^_Fa87BE-NjzO{>+ZUS*vT#Kb@sLSv|eHExa|nWxeOzN8KF0grcHQ zN!WuPq08uFOOwO${Lqq+GtHg0FJ*7ak>tb4)l$AmsS@})FgG|gn1b#s)-d#ebWeH* z&MJ0u^>7tPD4ejzf53ku@m}J{#Gewk`gZ$Pdp3GjIMzE9&f*GDC8*grdpZv_t7+jm z;T^$0gN1|TKm&;(F_Jm*g;GFy482c9+?K|M*|FkJVp-_4HXO(4HgJag#H%`=MB41y#J{Es|^QtP@Sv9y+=;K zdIV2d-#5PEiC-t4K-_%W{|x#xJ>iur;A$y$74w7RK4;u8Hp+YC;-Rk*>5tPlrLIan zn7l2yYI2$6hAGuj&IOJI#)L+MzEH9#bz0ec0q102#5d4C!vB+R zvhN#jRqspZ8|Qi9l2C`K$6Q7~{c-SfW257vb;FIrEkhkcdqRgp&5`SgIAc0bU#!oy z7up-x-?86&iX)uE5Hn45clEUQymmivXLtEr`Eh=%3RjLhZXd7(6hda;q~oUG#^CY5 z(LiEqV(RUbJ1MS!C$KerXZqO4_(*B=jtsVk*r&O(+$qN?hwU*v#o&YOL^H8NQoE$` ziRBabBbH?E~XS! zileuA^>7@6%?b{g$>aeQ&xeoHM)*Cx87$E`z7NbfS<&xa_>_Jnud2-R}S0UnQwbQtPDp zNuT{M{CQzhibH3+qvt6for`|1Kh;^BLJbAwAd@Dg^-mp|S}nD1>Xg8&fIpZuxGl0f z5=H;lQfsl56}9(VsChJSR&lm-H+1LrB*KQycK_o%=M0OfVh64b*NSRE)ivrFtI#L8 z4SVTi=xoRvN($`^9SALstd9JKUY5zmJR^;=sHr%=d(-jMG14>9li8QsH_HE$f1rP` zKRF>eAq%dZ8)r0Iqh^uScG*wBe>x*(*nxbrRB9pU)86F2k`E<+llo06lFM`{B1TSu zOTGop@iuCcZBa!wU50C_ce3|D!oGwF2|p*Kdjg({u8OV|;!4=i;ou$e*>3dDuSNe| z!AP0NgV5X1z0m7WZp1hX<=^CprfU%t{!8N=cXhFy*~Zh{bKHB#d&_&pJJmDZ zlj3~qtRj{dPcuiEhv+2@C~uV^;XdJGY5UTOrRGVEAP1|QQZ_|R4W@d7?qJnum1rrw zjQ%qzgL@v>l*w;76H_bD{v&pf^k)O}c_o8}HxAoil zUHP7TCVW2pF!&r6ssU(r2k0;-E)lMevqXi> zQf7CiA2Sj4`8@7|?)wSdnfOD}xFl~voU(X?}E3!L0zFxp)j^68$tZj>`8d?0DnN%Cr?g6Wp7J*3S>SEpi%^bGHGG#uSdZ$YzoReW<(A-Gs=KSW!=7|c zYi|>8TTe4jURO5PC&Zy5`UdW!CU9Cmt{1`gC-jT-i<}Cb3UvV*!bXjX{ute*?o+p! zyG<99$P7irVt{jq^Ec0W&w+#^3FCcJe9sbICOq~$@hk)X(iZ2U2ZLL#V^lL5fmiti zxu+mg=$z6zWmEE+;*2lB(GEJpvuDsXWBpg-+6Y$WUQxEgp{c^mm!`ri6J z`4WAZeF0C3XPJwS)?J+e$mp18_I-Agr-Zp3N>`2P5xX@7(Bo;(q3S>3Qv01|kux^!0bC=?KjiCvw&oMYXS+)X`gJXaCni&(ef==Yz3bLaiQlao5wK=iUSi!_RS z6Dl9-5$ue-^FeSI=5m|-hr9^2t3-T5;d$;1R|Va_nLSxN!Gv(a0{SdnMx&(oi#K1nT`QW{@P!KAcFZINoFX=#6lFNM3K z_o}ni*=ohMW*^{e;%wJkS6=Uz-aZL^6KW;YO}GROE0-&mYdUN~H?|v#wlo`roi+@8 zg0B!GO%6>2+cr3~Df~y6e3!=vZG`r-^|N&qcE`X0pH0p!&LN)R9&bWoLZ^go3AMa+ zy$@WETn+GDKBPAa6sc=`)a%w#Hes zU+vlU3GO5}5#Mz+#52NE$ye34)xQfKZ;QW-?`z+Wo}WF(948#Dz~OD6Hc*+3%tj_9 zQ3;2GVLhk>TLzm3&7c-c1`qQAy*Zn4p87I)(_}W8-HPv9`5k({z`e*_)l!u^|j zn{%gg1#IhfhXHerFHZnHE$lsteAO1aLOK zU#M?L#20h?e>}YfxK#D_|37>7%$#$k4}x?{DAFihO82F^OS-$eq(r()QW^vVK|nx| z5TsiH5zaZ&J$rtyb-w@S&w9M~KKDLX&zaf#^I7Y?-l2EtUHx2rT?IV_Jx0I5e-#Ep zYTOYYql{KWm!Y7$9c>wHIbl6v{efy?X<`wcUNbQF8cGdCI1P_OPeN_|ZT+V`r#;Qx z&D~X~+4Lp3{ki>@;X_o5SC8jm*Bvs2P5mwXEkZDwnL0CdbCxYx>Sn2vWdt)$Q(F^T zR_^4&cmzDto@+maPlogO^Z5I_zj1#^f1mzW+Fxmvz_OBfr#|A&&lb!UJQO_`m0gD2 zXg3OnF=~lgF4!*GzOa8`Z^8^#lv$p2T~cpb#4_SSdRbG=J@mlpUC_%JPPTH2(HNg2O*e(|u54Ze;38-?nxh(@BWxvqJWZIkVs z?f^1Wg6esGSxC&QLZRLWdDl(JB69^pzEM( zX8O$ZlW8Z@`la_zpY59Edh7ky+ZcXg%XrK9_h49C;mkU%sn(f}8ID7#hf{}V8J^{M z>haX?9N#%=SZi2Cw@^c^sdh)heH(pX&>!>{_7?UocQ1E$qvm_&d*1ur`|5=#`nCCZ zV~K{dF06R0mMmMWTdc?!t+Za2t0`AfL_afEKUe<=e2)vVkM{rJ-|E@w`PQ}AbtU6+ z#y75STmw7uw$nu(Ey_@AU=*t(@FRZ`9 z%R0+kA-*do(J(GzM(peE>zuD1bU}H;T%OuqLcMW$9`*r(t!gmvGayfdt51tR6SL{E^c*=V2v$ql7u_a(_ zj)Ws|TfMCg#4kvCkcEy#jzOt|Qs1P$PW{*UuXCn-ru~iijk&X_i>WSsxH)Eyi8kmJ zck=O!6B!TF9;OYaPL8RWQ}Hxb`Eq7wDz>}w9aUqu_$40ggjJ&dhK}aXlrY0`#I(36xs8NXPt0Nn!wE~ z;{U{-$D7C7h5k{58Griz^a-zj3i_^Hc&|KGAFGGKD*iD4VSZtKVLfg;Zu^3g9fo|? zbJ-7z*Zd%G3VHvkdaHVexQ4i1roTu(MHyTM*B;Lv&*;GDfb4+F>&ole8QU3insb`7 z*t6I(oEgp$Sw>`;LVc9_QEDrCo(blO<`?K{-?7ux$JE&OqHAGCvBbT^J=`_Sb;9+N ztF5Q4r+~kJ|7PfBNI2`VYZV@g0hPmi%Y4f-`ka5Lb(VFOf++=44zc|gT~Pga{rJat zNeuB1^~=xYbUWSGUDsXzx&L!_U?1`?8p$THCb8mZPQ}k~9iEUq?LF&sJmS1;`^_dZq{rYfh>m7A906m%7^vZ??%ABNIiq`e_w?_n@~-kO;0mwkW(PzE zL<{K(=|tbK1s(ie%U;WT+k9JAdscgWTYXz)OJ$4b$?7vJiL3V0=+o%O%+@);LP~f) z^G@|l^OOJsm*4vfSe`}ki&>*vtNV;Sx#%f$5PcW%+~0BDaUOCWb{2LNcGRJdZie^F z3U!4#4$q7Mu!!#X?)b91bGYZG&rR=;)*)>t)i{&s;QC;%h1Vc;PCoNLi5r zeb`pbQO%LZna8=@vD|Ugc7#6kkom6Zu4$rvqTY%|Dg$4@+05U0e0hBzJnua=ugyEj zH_0b=#~L)HN6}xX{K=n`pZj>Lxst7tZKHjoeLvOB*3Bk!Zo#AiNk`FM{R7W9XE;~* zJoviYZ}-#hr{4m0@vrty>jv+6QeaYG1^C!M?tk2is3q(JZuoBa_& z@Zp;1n&^bPD0;PzEFW1OSRYvB{h12>(97K0Tpqn&1?H4XaEO|~z$g5$+}GSM=%XTtt}etc#Q)O&rN5MPDX9qa*BZwf$KBMssj{Psr^Zv?I^H^# z)1TB!u9w_R?WQ)=8fwGB!@wM>`gy!OW|!GDI%8BuLsui$P|r}$0sjHNa4>~iwU?d# zdHfc#nzNZZSvy&~+q&CQsj-%^mea85^BeOUBf5z0Q0!1_PiRl5A#SNJJTE-^-22@( z!NZ!e|4IrZ2Yw6x7OsSTOZcSQleQ;avs|+{_)|2sXzCLxFXgxU?BCKymP{&{REGIO z^oe$6*0bKT-l4qnz0-TAUrD>1wk>^I`U}?!S7T--@kZ?&?;NiP=j3P8&!)NNIc9m* zFW4{GUsBt^7)x48TFxY$g+s7gZJB79D2VQAVsJw6nD3Y`EB(hA_H{pdPkY1uu)lV= zcDP}@Vf+Z%ppU^vEM|+j0(EB`mpnn#9pj*V0#U&Tq-snql+U zJiGk6{hz`;Dw8OaXlZC^D3nqtMc$*D&KgdCsz0@ImdaVggmt2QlKr;%wz(7jniG_X z$_BVhB|@Kv=KALPV(zH>XV)3mE7wa`S5H@u)o=3)zxP4xL9B{WMd=NfQ?&T2EvqdK zo5S{{t)k7!pWP{YQiKavL0>^Ho`2#Oa@2p!FMU^|saJeVzK(t! z&4w;U2<>}Q_NJ_}t+P#KmiahK_AFJYcg(a^?N#jk!OAYeIy%S>YHf6FG#%e9xiee1 zTDab@Pkv8zbaissL7&7EQh0o~@jPpXk8dlyhXz{)TjZHH(3m#kdv9%NZK;pX&PY61 zzGM&Ji~2Ip(6BG;d*^xQ$>YiG*-6QFB>o}dVfQa{qHy!m(4FkD?y>fF^mqK@{70nV z&MoXeGw6Hr;axJ(FwyW0*nXQxo5)`OUjI$rppP@MWt>Pmk#?K&scS~pjB1{0o)WkK z-;Laj+=Sb7&~VUT!vkf3b%FJ<{fYga;~sza{tkKWkD8B~#WQB9eyKjMmRIxgLyifI z35b+tuSXE}W1duBs&6Ao{Q{8!kvdu(ZI}KB{Y!TFi_MG8t!%AqAM79OB^@OlR=d?M zcbzran!FFKzGzUQ_zh3@Pxt@f{=;1%qe6x&&7D>#y-@mP`aJpGuAvWI3IFhf?u70V zyszf)B*M0^ZIpAAb7|_5)QYKJrjBupc8s@!$aUV?{8j( zO{(;w(?G-z_(k-Tb}Du%c0;+Th-RaurKN?HfxQ>}hM`%8 ziPSJlA!lKyU=ermUK3yB2wI8!@CYCKpZFJf7I{XyM!U{toXr^F8sQr6nc&&#-|F88 zzt^tWwT1dc`n{&TCWqN+9$+0{oo$2_ z+7{Xs+ZD^j8MfNE+ITqSaEh5mwuPgGqoK2*^P%IRL*A!!b2@kYUncRoFvgAX!f4n3 z^#17`&S%&(y=nS#_%r`YZ<#*HHOckL`^sA-R28hTSiBlKXB+yr@|NK1v@&e334IB@Xuw^OyIQ_g3{(^=zP;aChX#$3t{J$aNCk zxfh4B*S=@IXRc+dX&Y)EYOhC~x1O`g{8-sk*>p*{sHpHTyW@}bweM@6)opc)=|j)- zp6TT>%4K}ReEZ1v$S1t>idsdjv)Wm$o?Jb7ly#(ahhv9hG2E-O&Be`sn(mm+>(A-`2iN<3_gqGZKaG# z88YAf;Qzs2E>bR%51t;9a8>+~WQHAKA8D7_xCyn_w#W969TuDPq(Ak4>N|sX38#4( zz6xIc%wsklNgZKl@j1TiqT%{I{(I*0xy-c8)XUt-7 zXKgiXHQY+vO1yy!*%UtGAkQGrIxz6;aGQ{frT5S1pYaKMKn)yjdt^uC7@lb74Cf4@ zi7jd?YP;#U=_r_5P%Puw{Y`WnwjQzmm;63?0(;>rXj^JVYeq%SDYIdHPkqlp@bJ-| z(VnTkslE-tjX}|H$Unb;p@2cYqjJ1Uawg@48~DBLd)rCNNy`B=iD%&USH?$P{31SO z$2ZtJ*n5N>f3=Ki>{Cl+EO9M$)$`W#ieCF?aP7;w%eq^}TgGq91I%T>FJxB8nI&hI ze^dWWt?R7ol+Qzc2f4R?N}No*jJ%A<_f*D zAMtwZ^oHO=`zGaeiu9o?ZL8R-Otv|#POErR2tWL|a$IQ&|Ilk^VoMdcQ_xUK1f|j{q6YM@zVOzdJBKJ zBm{o%;lM%c2#@rS^2@U`BV$I!tn^vwQR=?yzUzZGP1a&T(J;19S}4MyKbCSlWxaL1 zwUNCMQ^-d93h?ko;0}Ue$-T5Pu`(fZ&;$-XJRjhsnI7=`^oJ@q~HSwfbO1J3he z-C|uqV?m>M;y<@Ox3+e)aZIDnsZFi5ueI-mm2)uZU{XvU*GqpX`nS!#Exx?&yzZ;% zSJNM*JxY`Fsg0|xYXSVr6TG`KW3ytjmD!4DUMHC+nGe|x+4eg2I_mKKjApKH4c45) zoWm^IjTOoYMf5d-Rjl=|^~-Ej$y13*ahfN)FT3v^&VZBP7a!IRYr^@ig6GpY^Eq=% zTT9yk`vLn=s*|mg?Tq=XS#(h16CxNz1(Z3^2z<-j%iMAw4^AJP`FRR9Qi8ow&rr`$ z^?0>-EBtCIB~?nAVVPn1%l?=BgY$!PUFy2jht3DiKF%4G&{X$jntZ{I!D63(6TUduBof9qpudP8lQ@v@OU5Pp5Xp9#p}-N&JL*^Q>7>S zoW1`6^8s@s{4m-n?Ub+J28_eQUGUYGobOB07pGUDI%IUn_>g4U@J;DAXXEm^}&O6V+X#CCD!_m|66S%kuN~35nMX)kBIyfqx-t~R;eNEW`$miMK)85n8*VZQ* z{-)8U@S-;-#8*N5*<@!t&^Ex<+1|Sc3a}2R1UyHq0jd&5qO^Fy(fpe(C(uIo3AT_Cw09 zlsv{fMmd`Yf{n@fyWP9p+nO1vgR28i>IK(KxHv=nL;TgkRm02T%h)NJ^)*a2O;^Ba z+gsaPkJ^sfPT5Y{23QAL|4I2LrKhPUd%sG0$>|t_x8*+e@)tZ8JO=m(t6i&I@~%Ds z9~Up@XZAAtus9=>HMXDR23)D6mCOhQb%@h!b=>Ydh;F_QLknl$=wuEwe2R z+50vlOCf{g#qaTh6D_{rsnb2vJ!jl!_>S6nq(5tm_j(h~*xwV^5`ztc4dQ`6l3pyY zBd=qYbCz>9m6NBmv$b<3ukStHvy8;>z#>4pkSn6q`lT&yP&_I7jJ37u;i{3%oYiE=3b$lrJdyh zJI{ge@ONpuwb$X-;l=(Xenc9c6&c@WOi7=@M)6_#Cf6p{KA050g0qTG*LQf>PR6hA zf%$>Cp}nD9e)rC)om0;{&pR*LFWO}mpN=2$3;j!dJ}sZNJ-j1)&;OSn16S_|_Xu}o zFfy6t1#>RS-nuF~N7<8!)>kkfIYXtd6P&T0t)A_3%jXu!W#GqBN1@{p9h$uFHN7>x zkHAAt!|TCv(RIXq*!=^0%5BUG|3honRNquz1m6+aQ9ZRkwWspuB~^_o<0#|!&+=d9 zT_<{(xAC{}&%-6df?eu8de3LB&s;|`j%Ms|?Qp&Jyzx|nKOq{S7upN0m)c96jDP(d zcD^~753}2|+kdv5v1PGl0Sm95GQ&8-SXHU2T#sFkZ9%)8mtEB|&oWOfcTIN#cYXJM zdQ#bm0ndlUL#VR8vi^(AUtH zh8rP!rDDF~KDpZ@>~##)J)?WZ4)+ds7JnAM=%90GIkeaM*ZMYiGGUHp*#+m!;4pA= zBr^8^^52caYqh>wUww#X@;mZ89^%~to!uw%f{ucc>JhBy`_T6x@#ZV3lvKn&;u!BI z@(ybu&QJ{$Yc#dcw$Szs*hmX{fR$jJJ7U{oZ}9-R?7i&W?Aq))o_;*N0#!Vtc*bP+ z6t~W=^Y?-;CtiZ$5tBKH3>{>!LHUvkuc6h3^m2)5#y4!*^)^_ev#}q&QrK?g_r8KZMuwJ%Zw)v>5)~nVo<}POOR1`gTU9GP6fIIhJ zvYO;+9+3nd+YE z4pM@@{EBbY{>c7F$wbM_T}@M*Kyq7iTfN{Ti=2y4gPe8Fa?EmgtzN76Z2m&#$MwYZ z#GiOp*9g=I4EGH8NPp8WymBPAtbQ~#j_3b`??fivq=yUB4Nl))!(PJ-vMT0S=2}MCM%rW+ zkvo5aWxPc^hb9=t8zggfPIOLGGJY<3FL`UYYq$d$feZ_{{S5aEcXjx@$jCx7V$);N zx8+8;+t=LJ`~+S{S!Y>inbb0=mz|fLKv8z2_!bMkeiPIQ>R~(;@}P#z6UY-_P3o1I zVV-NAOZNW4NtzHCACUf6JfC!`P7RqtrZ3E2n1@@3TgTCZl&5xEb`#H*NESV(?A!Cj z^To50ueHs;&7T*Z{#o}~bTE6}?>+x{diZ!Ry!sy0;x7b|5hW$tC|WgU$Mq9OId^1{*yzuEVwm7gk4m2czU#yf^P zhPV5-`_FsMdtChKLFIGjbLaBr@|Fse4rGsHk4#4g%4Q|pYEp!_wWrz5B4J-3?t(s;=PpK zN-?}BdM5Ww{@wh$xiFfA=2T~{bcr@ac*dAXq1a` zIeV2wc=vwk{}R5~JByy9_qp6xI-hZ-BmYtRKqsJ`A z;7Nv48sRn~J!5G!1_Stxf}vojSfE%yde5?^3nw#BwymR=UYvj-TyF?edunvTcubuT^$m;zvFY?v5|bS@o=Xl)ipFnG}Bp{|xT(?ecvC=k6=_*Y2j&0?z`E>?p-wU3O%jgV~Fp zE>`Ku($8eIWwohxgZ)?AuQr)S-le=tIc7R$QdGTK7+=K^Zm{gn1#?XIqQBhhBwt;$Ped4r0g`@*Vdd_m2*a4w@t8i0I_y z4DE(5*JgZ`>YMAEbFi0uMSTzVQl8IiX!N$@mlGyqP5R*0k=7B`l|kw8PI!*PW-G+D zYOklEuc7ZgzP7S=d4RX!0p)-q+_iyVw`akZveM^tq!zP7zL;_`<#V*YSYaCG!TZdC zyMaEUM3$1@=jTsbe{26)s%WrS@EbS_&B+-19*r{;I=%Qz>`UI4Jl#Cq+}qOIQjM~* z2mTk2XSoYjDXSC@4g?daxC5EHkC=~`^P%&7Z+LI$%f8}q{84-<{sxbOkArT%N1~&B zcE8T0A{ok<6k_hK>d^8cYL!-@IguR-*)4U5sBLwlan%$`fU( zHdQMdEfcK>zW&Ppx4%E<=3DPu?-<`0A6H~x8vEsa(f!eS+#fM^^WrHpFJ)fJZDhv zmt&V>UBlhN(*x52gM5R0ExgV7rYd{O`pWro2XY54!;wTj9UYb!mUu+&;D7je^uW_z zb_udiUua%nmi)EmN&idQO(xG4Jguf`)3k+netkrCM5AD%pzx=91bUJs( zqCaZ;wa0w^euLle1NlfNQck4!%sz7sOAYj%bIi|injL5wWNHO}R{Tl^!9kP%uk2?h z`X>5@d53y?Q(b*seDe4HG*UeB1P^z~^!!?KQJJ$ob9~A^t+7)Kvb)0}S^&m)3a{bv zYI#-mKjP`*^gI21-F@8G(aDd5l`t`FQrds%|D|tmZ*cblBZu-3&H(cWv3uQ#C+{}& zWV;-@9TU-5AahDBP6=Lu4U|v}c*rj%McXA8o=^x)e zzTeTC<$#a1KwF^QSMDok>1B|0lN0rAa$P)GOH+ev2oWVEnuBfU2xk#-XZ#`Wv|*`@ssckl&hB%c?y^r?NFn zp|Q^r_$crR{4?Rg{_el(9~K-I6kmTi3x3o622X0gVLIm-P&?ZGU+tTmo18sTd#0v4 z)19>)wH&gyJCu9~4N!H1c(=$NO7=0b<1dv_I%9C!AULAI4|mhGB zMg6(aR;Bu~NK54tKTh$Td>?%mmD&FX8d4FBSq&Yyx7KO<{M|n)2Ol9 zNNuaMRfZ>qC$6J|T1KY96FwL5M=y!jXi4>6e|Wri=2$yx7ejzikI zX1{J<$=<6vb;fqqR@_qDA|9@N)IRD3w3gx>xDg%MP4swg(Tx{QE0nhL!;TMA(k7>E z%-ERm)brGXF&BHKGtr;m5XdfB=C2=Z`)zHUZJf7LZ>6SWF=xSgBK3v+h5eT0mL*&A z$I0T+^B4M950B=W(CUzaxmR;vbKhEe(r1+HSRau~D*lrX$y}RG{;!XF7poxs1UMM2 z$t0eQ7fep71g=M~z{S2%zEJ`Re?s`Gx8gT(I_wnxCf*;XbALR*L(x#zPPF*KvRySy8EmG1^V{-2>I`%`yYH^?~1DB7Viw$ips zj?0c3snt^_QG$z(vX8P4w+y$OPCAVie}gK#luZAf;0H8NMf_iTzw!$1G}1H5Gs-*4 zTisvXzdpD=*a2+6EdHWtTMU+pJ z&+xbSHn9jt+4hO=D0!ChD+TZos-$m$_i$}PZCr6)KpC(Z4;T&@r0=Yb*F+tBV`b+h zyUcue-(!~;9PA(D7w%0@{40dVC_Iu9;Syo-Ts)gNn;3!)I~mXH+UDBkyXYwv*caHV zIjTDD*zee7XLTK&?}(%kNs{#{UVP%em!JHDXWpk?!9_&3lAS8%F6M6KZRH(IvaNVX z4b_HdC-gt*&za7ds>3&aXZ_c@5*>O`bgwJz-`o9GzqP-)zxmUoPm{*0rPD(0PyZE}<6q7Wf(k8V9zZXKI6APARRF_Fng1*O9Ct>34RMFV-2q@_y7K zyesc;hfXp~B6A|4U!cs-^wX7mn~T~-Z9AE)a=uFz%m6&7I+5Q|g?>alUyG~7MUunB z+)Q79&s*>inGJ`NBh`uda7J)OFgIHHR_Kl!)7uGW;Ab*ci$;n@D#R+Wud za&T3)RI%K*-Lq|QY;bgSc6DNx>0HQXt6B}#wcsuD4D$>h>$2&@kF0I5U2v~=kN3Xo zfyyB%)ceA%T*&IEhJ)*xPeo3eXgF$?Q9X#}csmmVV7yDWJpSC}3 zE(W3oc?f$~_PTj~Z6KxS{=jd&;)}>??0dMAS zZ}`Iah4JS9S9S1T6Mn3m1=0r>#s5Qg0$5OM^WyVx?wUY{_9(s{PuQ)AZHX&nvHh$3 ztK7$PXgFHI^^|b=hm!4-U&*fwK@U2eyKH`Re)I(1+%?EBY#eM%7q5_LI4;v$`6zv2 z3-Ismx^B9?>RuHn#^g?Mr^pO1n7Zse7umnH3lH%j^TK8_Y|f}>)G>*%3E@0r3lr$( z?dp|XyzqMRQTx;PrT205aTWI#_g*5i2CK%%=){=BJF*niWPS2v%VbM#dv5zN$5F?Z zXkgYm);o0egl&#xj-?;Izi-HKt*6veu5o{yh@6O2$6s}NV0u92#OZi>lmR1<=c9SJ zdALusPjpFqNnGykE=m{WsQ##ak@_vE$FI~=lsspW3)WC+sMOQd!!z!igm}I!*Ork4 z^phqz=ecw_b)}TjN>_as{d9G@I>InK(>JWVvAprV;eo86)CKy5dconuH&whYTSr<& zrsHK=f-EEHn}m1UgwOVQ=tZb-v~VWobJufZ2^KbL9bA|2nX2fk=$js#9_$zG7u}NB zl6axMQ2!!3Rk&EU;GYdb*B=Co{00u*J=+7D%nx3dvhU^gWudIMa{y4Hw<}ka+`zl_@UmCtNjHMbH8X105FCo9M zsuams9cKUYuifTo%<%bcz59>0W@hzT}t*Gj1b#O{Lzu+b;4lNG-0C(OU^TevKPye6tzf5m%$yG0BEXM|U zD(-4+j8_a-4blVaRYlg<`YK9gWs`0bX;o59NsL&f%cbN}exdr~)$6C^uCGR2Ay@bn z`o2Z2tC(M_5K!?ppt{)<&y#3U7y2mR1(Y z-k6R5@;r5}I+ne`Qr=|)S*93zhK~i0;c)&5E=x_w$;=ZP#a_4!^JIZ|0rC~ICSKto z*o#~+xi1SF3K?2Zb{1E17Op_wE;z633a_z)El<6JBk!eJBw7fJnK-9Ahac>Q%+FNE zXWt0?yfn2{zfHe`eNSCoUEOMJjrJ?PUTKl^NIkOn!hn7f&O6m!kwcGIcI*?=8 z6mI=E-jxle^`g5aR{^pOi8^WuRqgY3}0DwHm(ZAp9p9*qhqFuvN3Qu(Y+DPrj0TmTawQX!X8kU-&g= z(P1(%j*t(~8-4N({|*0p|9}2H{0?dOx-ShcZsYLQ`uA#O0j8Y*IZ z#0*~8@R=b<@6-d#W)%0Z+~4ANoXq08I{bil{x_(}O8852=B4qU2L*cv*OGVAHr6yY zocr&D{-FLHdgJTl6Mur<^Ec}S>wNY~UBFvv!r!fBu4A47r~gZ4&o#V1X*4rq!&Ad! z!7)DdmGvD#2Ti4#f_}YUrx#eo~LA&*=@vk+9Ro(#+D) z+7g!aFza#4emtD=nbXP0tB%)YV|*lA;zv0rHZzttlAC+Jx>&+aOn3EpZ ze#O_~C-yYQ@U6ROIb$)TXvsT_8;sA4xb` zLuJD(WsdSj`&U~^*6;4f&PX#nv6qAvl6de<=x@%dd${y|63r9c8`~DEqgBdW)K@M)hI+7Ah6{O14IXd;WazWH2e1ATRn=U?RDT zXYmo-8QC1kLr!#%b2%BVRu1$p|KYn(&(gpWwZ_r)zs6bZAKQDY%j$sp&<{VWy!cM^ zQ?Bg zl5;ekSt~zWL)99y*x9F5vX!&Vwa&0+g@|lmcRkZI!*p4_tcthx5HgKQfP~7mT!OA}DTV;uI z9!=gAc&S&TH_0dVg?ohhg&GB$2QLS%qr`IuE`fhFB-gz+ePSRUjNj7T(w&3Lx0tM- z1bHa0@Kkf4d+A4y{|sIG81r!R*W^PE!h^YhKDU0Ywo=Q*o$!+Ul@gpGCA^<{O&*iy zPxl@7_nuXrTI`sPkvn%ed@Wp)jEblDO!qMKF)T`2n)JE3v^fm>q$t;)@eieBh zX&-AFyBPm9&Q+Jlqss$3>z!_xGJ<6CQ=|gjRDM-1;eNkQS<5}XRoQ{7>>bV?tOqD=5S~W@zh0S1 zChI5ZCz0cAOg1D#AWz9{$;DQFytJj3XDQE8B#Y#R@rJP``svl=SYiR8U5Q@ddB_M$ zKH#(9bJ(^gf`Z$N2BRV_%KO3EtHS?0&+{o+HFe0l&dZtj1NB<}hQD6ZF&xtmrV3KB zv%3PWbQgb1D>v0Q_VySkJN{N88k{?M*x_Mv`2+PvK5 zk}KIZ&@OPq|9{mx&?j&?cqMp?_ohdzN31no*AvJ)Tm{B9K6zZSa5nex-0ZdO#mV8S zO-FUKbhKdolPr7W>15=(AVVjG#Nukec%KjmvY z>+`7J@Whln=F#Nx9pt{lA}BM5p&#dAQ!wQBR8?lC+LUk}1ureBlv0k7*Vc;4NeN#3 zmF{cZPDJLZsFYY7h_az795i|Qo^Mb%?ySY@eh2zKQSLR)-^%}ycVVWUQWsRd}?3ops_LiZXt1c7#-*U zro#0Jj%%Ih=_k@Z^&s<2cw($~afsdwn()SOovLrBM}}oPHA$bOm)S?|`k!N`W1?#x z9v&WUj-SwB5}t$$+K@b+IpI0s7Wmu?z98S*FXW8MJ1>~%KoV;=m^YfUS+ZF!;4QTa zPVAkeJ4uoWGD|;8-xtijUaW3RxDLXV^P^?|1Ajf?3kmnQH9NqrcyAD75e~!xnfv~- z^m{6}diUh+$py>>&9a{yL-8PGzVpSCizgE-VA`Z^Qj03Zl*{Bw?uqS=r8ArCV}?x+ zrG<`CGE1)yuMaPeERRU$iFo$s*79gY6GanIY6W@nSb*qK5toUk=dJFo?iXsOZijA{ zZa41k_jO;gRorx9*)E@Lhn!s~-h=P*t;%rMNrQ??-dD8cLJYIC)P zu?4Y>WP-fM<5lJ(!9WGOc}saA-LDO=4PV5^t+Ccv6aDIW^}O1Itdfz*qcZniv{mL$ zET3fVsXir#tw>Ulr1ggNhI8bC3vT~B`aIeIp1ojfKl^{iQ7Z{|kX-%%H3!Y(?(h%c ziufbO2n@T7W~v)|?KP&ArY7VgNpAI7_R@o?vB_hTv3fKm8Iz3<*u8zvjNKRixH0&8 zzCsssk@vh9*sV3}Km{@+T#j6{y3zX4`TTxQ%kr~g|&QXPb&`fXJ;L`f=qfIECAbv83X zQ?M%0(KxhJt-A2wBU2)O^LcKEH}QM}h3m%t8NvC*3c12HZfL4?&9}j$l zmE`0+Cu3}zd5ih1<+SBvdeZIq91ns!FdbiNgDGw-h>v@UPOl5XX)F-Q5jlom-{15| zSA4&s7#`|-%N{Kkm}>_4nzbUeBhS(3txIf5)I>wDf%|kJ9uM!(9PCW~kyNt_$z{l7 z%!$T*nQ@izEbseO<+}2aonbaI%r?ZM5)Tp^dH2`x&fi2UTZMV@ z2L4x~1r}}MCH+NxIsCIafmh4F|41irlTKlyZaulfB@^r5@zD~*7DX0D+QNOE9h!qv zY*>5w@|sG5>8ofezpi z@B9#BALCkdu1gcMnPn!%4uyAy>jWzY`}@23Yk}E4_1^Q=@zwMVWQM33tQuT~r$uf2 zOmdQ)`bKdp;|#M6TS<7So7^V30a@nTQjVl_An$ezy437&Jvtlv83(E()uGBLWntpm z#H;wr_!6GOEoh1haUVFyr|cMQ$j0eK^jvID><9LiiygB22~Ta5^>F(c&}+VOMb>ozZ5s&5^QIDy2CuxYxF1egVhCU7Uru_VCd7y zd@4aY!3gH8&g3A4bZNS7VEqT<8{_s^m@Kimkx69dT_f{t3x1-eus;+fC1@0VXvcW7 z_@c!0#7pIYQqoYw@D<#2KYn}#$;;f&**Py|cFG|%U*++sD~jjCLH!ARB$1@6j2?a? zPfaJuhbGT-f`2)z<__!{~I28{LUByaiZKd30DM5@i#e;(g-JqaUKzBag_xs2qvnS^Gt#X5vpRY~SIy0~8xPb=3FWwA4ZYvtX>FmFn@ww(e6CR+e_b0SOAzf)c z@nzs51$pBiD9f2Ud-EL@FqAYLMw6hUb&43mO!i9*S2+VW!)f^hjBhCUFB{_D$8Y16 zS2|KM@`#zu9Sq_)yprw5Z^3C`ig(HC-AXTa6TWF#bl{Rj`hkp%|4c7UBj9cJCAa)A z-lk3AomEdRk-P$4#Yp<|gyL8FCweBH$DYKN!{Oc!udfZh+gs2%Zs1g@565!}9HlN` zMUoAhMm9%VrM0q3U8&B)OH{J9f^h4bCAUqsvFof#Qdv5~Q9aIB9QgEObW6a?4rm_2 zVKc9hT$G+etSCWNoBwux_R9JpF$yIDF5PxH3<_N&hLk_}%P&eX5tgJ}}cS zRo`=-KPB67mTs8Ntv%Ih#Y@GPMW?eWiiR(Seh!I`)*`Y1&)`Qela#av;YZh`ZYbq8qSpuq*x4O zZ&e4L$Od-*%kcRw6Q~fF0$w7ygW?JG3LSW^c=q^UvXFjcYCcBK+|Ag@xR?Z`a!FUf*sb3e;F^Q zeWsO!50!%*m*~p|liPHbQ}m|tNZAhV)KKZH+|>O|C)HJVBk_{0&{WXqdWlNB|HHxY zWJVtam#v7BU3tvsHkD34N@h?MvZX#(KURNdD#)VO>&<*mm%t0!Y3;P<=*1^8zcr0? zjEsVBV+wyv{#;SAu6_<*hU?WK);rb!F2yL$oKxfq3&-dsSzjZ_Qk|SK9_RgkIpq$d z+=74Ag3QOpWNgd)QI9)yBiZn|$;5e2Kl4SfLNIF}YhVMuocH{9{3pQmN{32>@W zCiPClw77PJT1ov#sVqVlQw{k&3iIxpAhSKwKhZBym#9ew6Q^fcgPxL|isYj9BG)mR zh$Y6dZ((H^TSfkjXd2Ivt2rh-macAZxDT1(E2FETW$2v+_m+KWN%DZQkU}K;*qcc= zlLq2fB-yLCl5Qn!G;J{b3wm%%e@ic1eDMJgee9v|;jrYqMrk-D2mNs1NMI&C(_3=z z&XMUY`Udgz*uflqU%jXPWcUW z0Jdvx-Lu3qwwl`#Q>aN~#fnE$GJXA8=G&I^PDS)ZK$#L`SzT89<3}q!y>OD&!a)#S zE0T4+_#lbDP=|wx=7pz3|q}GTfGoNZ)d|Z45d;bfZ(vR>L zko+R~oePm%DZUU*&>T#}?>R3SS0>3Q>?sL&!kx)R4MA7jk(3<|sCg?gv9@ue z=n_g|etdpr{<3&gB}Gk9cf=j36s^dua6P&@wl+3DJ~uuS?#NKy;A(u1!uhEU&M=f3 zpbS*1p(*llk8h(o={myb{T!sJ5KnSFPSKV0qYhB#ACyM)tpDlX=|$Hi+=d&}Qc8Bv z*{L_o29pz$6FxYHva4`M$Ymq5?Ox~}D%qZ)A(U`e9TCU>|9P%WtV!IVCl+nH7q7ZS zc!-I|TE&!#DaELX_@C7vBXkx#m!WVX3M++`Yj9MT!xh>@=KIH-CD6(;=i75+kqY-m z-h=w|-=D;b#0%0l5vQX(=Dlizw|js3BbkeYyDj=}Czx4`d1XHs(AUb>nHhpB$()_X zXZl<0Hyp3q(^Y?sVqvOCm*YRhPsA5$i?qJ*`^xFc@<~3{wdUSifp%>zl{tfh->uWF zBW)wEPWTf|sl1#Ic`3>2Iz!2}EtcAV>Z{JOQb~Oi`c24ygcy$S?7T-}0I)&fp zFZ;#&#e*1qOvln+<3Cu#8%J({BXf&A@iNIq!t-ge2>( zGg;juv=Q1u-9mD@r|Zk(IW3&}-lje%1g?@gc*s=DRNPdmu^bz*!O}LwVbUE@n z+@lAPbMy)Mop-5^$gh}7<=67_zw$dW2WKQ)3Bf+*Q1htHlm%Uhyz3R%%gH`|J~fD% zMctv=(HqciGmAdV%<7({pRNA_U#f%L^>5jVTqj4T6SZ2uO20^1q%`KRxP+J+bxib@3)-_oljMaZ_PYhG+~GD@SfA;d&A1iO!a5n_mbyao?4D4 z#YhlX`DYX$U-?sbR~5AKn&5wORvzYVGO@pU1)sYve}D117)DQJi(BKe*FK^-cck*Zcg63p7IlzJxAS<+&Qa&6dGH67-MMJS{*M10&wM6hS!1GASV`TX+Qiz# zQsOB%EI*DP(~fB~@RTX5D+fY%T$ijQ;f`0F4QNi~jqZ(Z1J#`O+RPIx-k%RC`O}i; z`35EVdg37??}cEon<>G&*1^Ro!k($KzO%kDxpX@IEQ58D6aMGn=#k94SMfHqfG~u( zk-CPvhO6_OE+RXvJkMzEMDEOcK0n(OkHKpYU6Ew*mV(DzgF1_+*h$k#Q!V^hhN;6; zIivoEzgUZSi}<|gyl5`=Y5C!$?F{YA#DwHCZA8wWV8G4e&Es}FC9mtQ>jW!1t{zv# z6XR=R9Zu4|I6f3K%6@t-pJz9HH+^0_*q_lQp3+Wff@9~7=Zc?XuU)#Wl31+MJqCqt_0)Htvf^Y zSNbdBO|y`CN(ndqB=sdF_gimWZ(X@WxkMVfv>&^lIqd zPm@hIE-^0A76eAl5YZ0zF!eAEPa002m_&MZj^y>|ch<1OE5eSomD*Zu2zDdyPb%kG z`DnT5?(iP=XiGw2gf{;L-v@h#`h+@%JB3e0PDXms>sG{HE-Rjv_uw0MSG%ig=t%~V zOL`Z6+#ggAYNKJJL7s~d`Vso7_>l6{|G^YbWVwTW%8?OJQCVC$9As%zEg3}!IZYv3xo>Fq~>t29#z z>p$U>d`3oTe;fmk@z+tcCndP%UG8h))D2}iD4-SmKOPCZ-5iu?MSrAnu^&l~W<>MH z^T$_dt2OE01nZg$cO%`9W)N(BH<=p`s5#UL;|ZRl@o-rG*2~#YAW>rnUzxasWFA>Fq>of=!dLI~l62OszAsLCr=peUn=i zpFq*0@Q>FCNBJfANQwC8@pG~BvCXlK{OftLZF6yYu8o%_Cth&V=A4WtsW`KGc3pN7 z1Cw=fo=PuUBT+LE)B-pl{>Br3QhP*|BFjX41mw9Z4<2QMr}K(h$D3Z*@Cj+517P*^ zqQf^C+VK3erI(X4EYK$Hjw`r3twWBAkBjKjh*ETEkYKe+?TVN zFlxd{xC8D~$XJNn(JY*t%gD4{K{9F%Qwgw<$Lf>Jyvpey4=4HgES!<+qU)m5$uztZ zz7yU+y#ymzMYiaX=;5ev&JU2GEE$;}lr%+tzR`x!hAQOLt)af9@=&eGMyRXSQ*H1) z&VdI{NK8ny(b{Oe;=SU>W5;5WZz-PNgDA=C9*&-_s8$4(`%CRxW}ZUql)l9?M$X0O z+%;FJ@0gn!GI_@Mq-CeFg13A*b&9gnrwebX7+CflN_2N0sULwTPghS+yQs!$6Lkyt zhUjhN_brk5JaIXGIW9j#WiprRMCwL%k%~K#jQSs`PU!AOM2AOTf>$mBSL{n(y6|=V zs$U(7KkT=rZ^@^xhGYB?NhwNd&9fxGyUb_TlxvD;MheioOpZ;C6$P&-6DbqfOYbRp z$w}3+_<)HbOd=#Vj~3SMOjI;9ct0E9zz4!q!5{5gN`qOoI<;}P+xf-Dez9C{oo ziHAZ)*cEn?!!kZLK4!sdbx&eXqB8t9;nd0*CBB5ONyJXaGk6mv8%N=2Rm5|%9J{kh z;9nilXNXStOYI9yvSj5?Ijx+wR9m7M6Q;yW?)MD;5xyM`XEvr!NFHGF~0W$v2m0v@sl# zUrD12C~lowcNI7(- zWhY(BSlj5KD)Bi2HJfBV*OQY4%8=TRUSn@!Z^9LKXU>L+h{jnG#|5Y_squBftEo=l zF%!`QzK*?#O#-i!ck%?8gN5K^G=RM+dz*Q939m4IZ~TgX)>^Qpqv{cL6YrR4L0XeJ zEEvEb@=!0~#nLt2EnbD^v>83a_Y`nPe7rV63u!^EKU^Z=wF{R{`WxwC<-8j}}LLbVoI(EDLN{RO6fkt~db=pAa)bBLe& z-RRxu8?u7yP;ws?h!l+M<-M0)`LEdhn4JF+Fm1sKgtsd_%wgkUV=q&0Tn=`aMpCzp zw~fEUVI2v+{hA!?nsC52@VyI9^KWvquodEa8pX-ni8Ez48Qkrnt>FVLj4zD8z@xts zo1F>D1Z5FkmEv3YluCv-{8D|%hHQ{}8vO7Hthl$Fhq64Co>4H!TjJG9uJL$kCuP!1 zOz{h~BAkjBD0$zd$IVBsUmb9O>YyT4_Hd{1ZIXHPpTujBjmg|7CBX4wJkbG7=J^p| zDl&6V1;H->)^?hbJ9#~If!a$or;dQFKGr?aJz^&KMf*kD65kSE9a|j}tgR6BkbQ#e zW_!a?uf!SJ3Ej?F?JRno2D)b;*wT9)Hyk(oO8(U_)6mRWd%9_w={eci58$0oA{R|^ z#mj<8$o^m6=>^dR-19RcPr^^a+o%WO`{Ci_SM(tRay@%CIsXQ;6~D=|=b%TC`}79h z>6PGbHzI{wX86TC84vXj^g6wg+1uA5mvaiA!z=A?-t6%p^Yyhx)I{ng?{L*b6%fH+-$y#}r?*iI6?obYvT^Bq5g7oUw_j_!mfXQdwV znP$Vktb#1F>LQqU{n&B4WgqU79}PRV^CzFTrfJ*KuNb|gB% z;jmJd=t7rM(sq7r^+%#iWdV}n@zc^Eb)BjK8pGb@v9UT>|9jhG^ zp6X)lTkRP*@2BLxNsrtVj+Vkq--{Yfm7=ziizYnIGlf=^qD}EK)BkAPpNU&~FySh~Qc+1VBts?2SecWtWGF*PhLD8JO%#%$BGN!9^DN|? zJ8=SAwk1XME=)AtoG zqCUuP{BLOvTui8Ty)FagiM@g9sR882R)dW`)C&6Z_4(`Hq1yZ&w&W|OM*AC;pH>7l z3u+crEUQ>%C^eL3`MLp&&Wz5~Krj6UFd{QNb2Is=-cRk19>UA2BlA`}_+Ad~iVEy) zXpia^*vbmbj(%ibY~GC*o_d!Jjg5>e=-yNyw_boZX^79P z#&ZzozW^)&zmy&x9K0^5j;`}j`q_i% z#-_;U-pjq8>z?hN?aR*GHu}A_$IV_FS3xg$v9SUWFsv zNSv<69D5hglDp{-YNh5tyKD34086*~3g`X~?w&8v_v`_hgI3Het6urPURz;VH=yVK z4^Zuqq`~$+x{tj;d+-eS2xy*kIp|6s|0XmA^mnf@er9}tp04f?zo)x7zoA&}SyD^bum-bESPt=TJlM zrWQM9IBM8y+-n?7HF6#l(px-2?@oKp-xy4U+|pklM5{-uhi~TE6%riM|wsr$rCi(y$ptd%Iu#%51-w?@WsOB#umnN z%q35Uk5rD(AlD$LoKrKh(vMU;t%0V)U-T@tlY?uvOtskGbR4!Dw&!yR@jK-T%ab)2 z3Uwbe0Fw<<4BFqPrCjhNogd|Wo#5Rn0nOkxqwbstG&`X>NZK#Df40GCrkI%b(MK{G z42ECH&y*)rE2v%|E#mIH$Kqr!lwKesK2^%X99^Z(`TnzVtUy6Y!Bp;X4>{dyU=2Cw zXU5gMIWKWfmT=lz8T45_Th^1@xNB)owAv@LS8)OkPjR##SOxBa!MPp=_YO{y&d4e5 z?iM^N?cEPGy<)o6d@E{iv#1Z>$JO(8^Ayt*(`5F?A2PN#N=I}u)wJ@u6c@XC6Vkf2 z00($J^IXP~wPcm2N+$$quCf{hH41Lzd`Vwrp>ZKwD_P?W)Me`9>TjsWoiLl6Ou4=K z?3-cP9)uUxeSZ>MF8#N(68A#yvR-+L_M{<9qDUCNTz&EWIa|Nc5W zgOrEX!V60E{5{-j?-2=nWj=D*jb(ic`V?HxyvLB z(vciT{yjhUVeUBd0Z)TU*~%~)H}ixiXK#gTELU1odP`Z|vhI8a@ACI-p!c|ErKZwb zsZ^eZ_Z?^$Wawe+kF zgZx$cXQ}e_9zZeeB%mP3_c>zZ65^o7=J};sW&6ovRTs1dx|13JY0D_T)xSqlg$qL?qjF|Qz3)~sq5p#G-?lsA+&m}%l%<9vvxO=c5hhWBQr1E{?IFYq{% z7~)4Xx6lw@^xkOI=^p-oUY~j$;#fO^d%<~fsg{Me7d}S6RrQ@}|6;hX2*;7cGKP2C~lx<@mg@+xz65A%LsGZq`gjgBFf_5?JU3SVbS>mc)k;(pXS zpGln4PWEf1!?{)K5V~<4`zb^=)_FidY~M!PC=b~p470QAy3JX&zJN)9%hfM z2t@D_jIxs`?oRqLe*xv{w0hZUSZ7eI)Er0S|IIW$%nW-P0!`;$_5LO@i6zWss&6_1 zeq?HPYIc8Sf2I?-8A#`Ff97Xq*k)&yD~tQqJb5>EqSXHs@7c-p1h>)N{G9X#(+1e= z+NRDt2kqwHY`B?TZ?x>!(qHqvA65yn(u7k_us(Plu%5#<%CB(D8%vikojC;#`$=|P zlbrdNm?iqyxZL;==nLX3pG(hTFDJJ;u|e@feG2tgpQk2Mz4cn@t2ios#Z00$i5)Y^T)C%&6&&apF%6&y&`#7p44YS`f*P{A!7q}Bm zlKdC7c0J}M2Nw)3kT&N9=9jJ%UM`fbVhwW*^IdpM@hi|-9b}r#a~=tAs=Q2p&nh^f z$?WFO$$=c>F&`7{(EcS#|xI*qxtN1~2-psZ#=EjmK4l7VjG7WxCn zv_E*38~G~+^JWwktSnne*QrIBW-^9@yXjvvpl|Xp`I9(x&8NIa{vqB*^C8;zzRq}^ zaWdEnzM)Syj&q~)E?vgiaIS0Nb=4odgm$j(;+5Hz*=Mso$sBvIiMBl3h$(^$h;bTR zEPON|AJTq#1M==mKyh@UX+nN~T=`8ATH@u5<&3%)zhzHAv**Lu;hupG{sn5=w=+{= zLC3BQHC(%m;-Rfo3Td12?#j z%}Lc%_p$A#-1&Cu?cTXQ`94~2c0R<9jsV&**NmJv6rHbo;g6)HlJ5oLzgP?^Q+3)3 zt%bXcyHHEGZ_fIL#E@>0z^G=?+#jXUWzc7n^Z$*4MsRI%_*a0hx%lqayu z6Nv4<8cKMFLhvt__)Il3kj|!fl5O(&_Y`IvKLprpXI7w7Je~OxahnJ5qt8H?R)Q<= zFspfxiIn?I_jA$*<@Zbu7yb#ORXyLQkhVk>7+l@K+QaCMf{%FMcfc%g2uOpPlqV;i zdl~QAE1XaLJLM-0*(vC2e2z|hFY={&#(mQC2464}aUD>OD^7F^Z$ zr1>*FJB=HuR@Mv}5wAZ0n)ON2AURa}N9jg#zBkCXo6|Ge0j`5%(ffV}xe~|0xW@1q zRm&ZQ@2J1~V&gC3_k7v&GyXv$Oj_+g#gx43+P#I5zbUFSA4Ov+-x+ zSn97}VW6;@sTyosS>XbpnTm3JX3{AU_jm#R_X7Te9xy07B3~{G!Y&{|a+9neKa|vLj@zZ-MscfZt5+RS%9?GY_jl zO}H}M^Do0s*MPGZFEh|MkQ@1ev0-6DdLZ|}f>ol9`+^f&$tbUsm*}(TGku%5BYu_- zh0TvC+4kTm@RTr033~GDlejru!(xGExq!^^#9j@VIayr+})rLd4%=> zU!p%Y77l%VZhiilu4Okv@9Em?x_r*0+FP~!oy4r`=_^SecB5f~;eK{(RNMUx4uUyA z=YBc*f8ya@B6`REW>Ud_Q7Xfk)>P#)z+oW1Px_~MZ7ZUvdMICm z!9YBhddEMJ7k*D~LbF!ltHuM>1B>CB?#3TX{R%zLW5%P#>zNS~pCOV*z0ep2rs8w8 z`+qMxClAp-=u3ZG@$x!wn7O+@_>cJI)j;=je|D`jU!YyIPuSem-zbjtS0br;yvRA` z?71>$ymcY) zhT#nq70$tpR^-%IF$SoYrTZbyMKdOP*Os$W)SR5>JZIoba!>U!l&{2ze-FSDE3XwN z(h;^!9EW%vo%wGHzRk}tJjBmZp1cHp`BC5?hF&N=S9%=2UcEit)#9G3utz8^vMDnp zU(=V>?%V*N+)4kh;*xg9RBJ1jQ10+7dBQC2+w*9*y}-_t>dsrhFrcrUxm`KUpzr3s zRDP_U(GfJE-oqEQ5?Yi`;-{#)=^FbHPXhfcQU(|#Z>M%>x=;1%``6ib%TyVSd;cW*lHU{87( z9l2Sa1=GlteqvJ5M-JAVSh*M+0O|*8?p877Rd5~8>5H;2$gUnNI|Uyie*baM3UmN( zgUj@X#6277D`_rDd)5c|omwy>HUhi_bZ2Vdel&4Pe1T%~t;`1Y<=lPFnZKD`6!k;C z$@gT>WZU7Pdl`rWUqL5EeOS!_4>b-mYPR-cAZ}2z9g~1&&Kt0AuAeQwRXL*G|KYje zxx;Wv1G9t3J|84|>YeZVK7g(yE&JR)&f601`6290)@S$s2hfDs@}WR?YEK|8U%q&% zYj;!2cVG_j3Jm9B@G>*>;*9!&Nkr96-~#g{nyu4ZRtL}ysQwf$sv5st*+XUj;U}d$ z^iiJSP1N$&0p)oU&}vofsy?9Z`6FNoK20~W2d@31D5!|Xk}iPt;1)2_Fw(G+od|IS zx;u(W%av-DRXUZ z|C@|8iO!BM?j&)Sx<~YR zU*VKq&wZlz^h>5gYz5YQ&scLfUy;9l2NZ)}2kIw@FMS_~1GF-`^M85hKY87zCiF7& zY&7R5J=V(XD`}3&Y&0960K-6EW}T{owQwgMqLJeD>%7w|`D9MP2{i@U+wTXIgT4z4 zIU_gp`rMo37O&H%8PC4i*!&)O?>tv29)9VAXZjEfWhUWydMMIeT2!_$f3H`frszq=seX`hth3-G*ugVZY;OwGyB-K^;A`|l zM}ud;bFeMSL(c)}f*u2d;W`PWFx*pMCj-RM7Wp{`@rgl0kS8+MaE6~D{lY=?d!_4b zEwz`S1ph<^TrFXDJ@e1=2zvcV$=ZVGIb!foM-d^w!v2F!841NXkfO5L`xLb~~ zy`%c44R^hC_kM*P+Qy)8|K zb@1xyRcQ8l5AzmL@;&VX45bb^igx+n+#tGvx1plhobUP~DvJkl;w4n;Y3EA)9t{Jj zmiw1nLUBcRQx!7jWAwqs6GNqEqxVj^`gc4_=_)n?dN%6+N^3wpMe%#8*RK&p#XG9c ztDb<)u<8NzniNCz?^MT&LzHfu_&?q6>QjFSTB9*`1a17m>^C8$ZV+epJzk^d>CyZJ z<{0PliQiy+ojp?JWasF%ihNT)W^8V3{?1UXJs8Y{8_^x5`$Yde(vwuj33?$X*?a!n z(1$2;f$yxkp*0$Niqo1g7RS}!@S;KehGX>Vs)2Fz1=O?t60Yz=uz^XB2}hXo4?yhNlIfHd5d^J*@m19RC)1m`u=t-D&BM}JToh!6-9`7Hb;jo~_^cd?Z& zh@PG5&ncXhmDGiK4w&Ap=DcqMs=XHi?S6RjeCQ>j`SJYyuFqvGF;4TNs+FYOIE1`S z`Mr1s)!$DVJLhAl`d|%#bd2;Fhxlz81I=8C>{<)ND{IEVopa}w0p+Ut%o-3Q)L%(3 z2e*kEPrQrf5fn?+^VCejB>ICo8xitJ-LIO-5Pu z&ygsHQyjg;SjTwPaK$juFp0gqNdEKFtcvOl&0K6@2dx`WFX=Y^>e1{aYPaECzQ1zk z8|mN1nIYC^($Cm0Kkw5Ng@gOyEvpt@&y3twvZi`Q@d%%y<8iR;AiR1RPEZe0+ioQ5 ze1K0VZ^6SP<6Sw;!dIh5{S8o_qFQ?qxQ@?EHNEb4@l0F6OuTp7!udp~Po>48x=LT- zk~J5mm?2J2ca^@6W@(<~X40MhHuu;YK)p%LajM5UhIv}`jx`sin0XgH{aTiGN^WL!Mm^d=Wn<>#0$O8 zY|K4Wi8XUKp~TlZHxoGU^HGe^4r+7$h0dO48=Jw4iuc{g9Pbt|3fQ?vROkFa47HHA zXzuD0Vv~Bk>YtATqxhsgC5IAsEv{Vm>?(5B2gu39$3IRF@iTU=biTxoY6kNo@F;Jp zYP^Z;bld>;kVC&g&HV)Y+g;S|_wqjJJr@V1XRCQcoe}+wcZ23Yy*=?f3yGoncUG{M zedxt_Kxv;&^F7)rs7yyx9JTHk@qMk}*?#7;y%&ul^+5KbW3Rk>7EGRIbo4y+yV1EV z(DxNDdkBA{`@m@?SHFU5{yw`iYsp!16M%LAu2NU*EZbQ&9~~9tncCfvX0CG22+$tg z6mlkM?})$qmKd$Ul`iyb^d39}t3y(s*EhbDyO^sAPdb9@tOZGXVPqtIHQMv;+^IOw7;Qy=3OQgbkA$|Msqjgf!=$~G|mKl3i{?_ zhGsD|)1VnK3pfp@c9KW?G3d(STxz+_hb)?R;a-R=?a*uI9{HEq?bP?Q3zd${|9qf!K zeyYAwtU5$I{gC%Tb?7B}SmKn#?dzR<6G-1*b@){BZuJ*i@N7P(j%~%?p_)VbIbQ-^ z6k~0m`~5OKo9Wb!tQZ(H_xvq4q7$~|CHSOsaQ72(6PZ=-z_j{f+){7mW9S5`Tg{oI zzz_VblgVpTzpf^dNO00mH%ayF3Ups@0^{I|b}?I{IZ<(xI!mhA#lds|syknS!`cP3 zXRr-CPK-WB1ujpZv+TZT21dKs%B2-gpQN_a+~8rJit@tyfHbSll${}p9-uGx3l-&Q zxaER;joAgR>kVo(ou?&W7JD_~6zhW%yqkKK)!@H>;65Bd52X!I46R>!E2^el;jca` zt-^GUcrDdcy4(6OOMij7Sp4ER^yS{BS0lc;JS^~H&b*PHvv!2U6-3B8x-vg;0)BoP z=m*4Us3)rZm`%jcr(thhOcRO&SMOB3(}Psn;$B9g=hhDVhaQ^t^)w4#7fdAMzQ`Hs z%MDrxm;7_?=iK((HnP%V`JG|$yM^>C)w2*+rn4zy72WUegH`BwF5o;2<=Lt~qPtel zvl+FH-ZAY*DCd;7;Rw1!>WypwM>wnEerj?DwFEjVdX`q8c%gYJ_2i+({})3)%FmL| zCyMGBd#Le8kpqY)S8Y|!P>v_Ikljx|9oPZJMa;G=1G+bqFMmRY$6%}BQTCEGlX4Ia zqdN8Bd%3y!*;NgDsK?us9>pTgsJLw95!#(sKc)gX%vV5l(L|u{t=Z8>!Fjk$Y3XZ6 zOLg~Tq8+k z&9|-8Uz%HdpZUYv$(U@wg+|K#K>L%eIS=BqR6B_CxEqf+Y2}Mw(=1AYy=(O;zn~sf zZ2bZKhns+MX!UZ%Cuyfry>FyC$w;r{`^SyQQWQ@v0?lXbAqMI>j3d|C3QqDq{!3R} zcmJ2nJ1Tcp{8RmSoElra`^R}KgAMtbjOi%zGj<~AeK0?x;X>BXwLHizcRD}opnlY} z|HX@9YAA6dn#b4tjOuUAoV>%Ex`y+vS%KEnkm6xfmnjdt-f%tj+IXJeJ}P)k9R>0= z@^E+u#@Y;{3P$Gh+cxCviWzlFZ(+{kXC?#ZvY|GWdS-pDfOD!{qKf1Z`n;5P>z&z) z_U3)Wk_F)Z&Gbsgu>uiAJNZ}fjZjZu4yP+bPePo(Y9(<@pXFAwmAeh4zi{p$ZvV~X ze415NUasdUy_E}~s-Y@fxjXW`xf=~P8nj2Jcr)pL&sDw->Srj9p5{M6?le7X@z3Iy zm3!(AQg3b^7!K~HU#+`9HNUueP2gxAV-R>0JPZbaHNeh$I{_$8ybo?*{#o@K77BTu zS-W(%v5ThpHpM4D7|AnLo~yrSDLcI4e*Vb)k>64IjK5qpxcdLfL)*f0sa|`RbE8?C zl|X#8G$bDY%5RU5Gb(l~)@cSwIk)c7rEFK-&19RY)La_kIci2s_r7L4jm&7g4l?vC zhLJa^FQCutS>mX2+Cgx4|5q!OGl)CUd#Zd`dkE^IiG$HDx6ZG6zxv$u{z+>uwdDQ$yWc=pLs!G^^y;La zH-vuY6rf(R^3Yv|okXZ+XxqO74|XhH6OSu>qcp&5;S_i_)imNT#1XB`t;*j^nx}XU zrmPab=N>YfUi`)4EE*ddGx5_Mb+D(Y#OfFiv2Xe;&|Hmv7sUzji~Go*$APElEOr8~ z0rgfK{Ui1mXgN*_S>K$=fTj*oE;621)U1la{BAL?zaKPFF)qKKQV(2aO zSXFNi=QnNyC#LhL-5u#2Xop?-lQdSQl1Zq>-9;X%&r5o=TH@}H_J=r}x5)LRVRZ}9 zr3vWHEVtfW@lBdj+5t4jpu1-|=X5upoO(jq(^3xFpLx$FK<~10CF#7)=lvANv5~W& zv!?TT4^eb1QFJ{$0OjQWf{Wl6zSkn^R^?O(uNAD}O;uf^`GlQ7v-*mo@~b(@)2+{R z${Z$~w1YGODCRuFjjK9NXYn-Hg*xUN@U@kIJ~I=wjCwNSS)So9)U44qpxST;^To<_ zhM*x`P*yr&$Z#A#GSuFe@b%>YtdHKbCpKubnc_4iLO=n%=S^Y4&wb*ek3kI z{Bjr0PFJ!}?GY_5UC1pQgtO@ZBYKWl^eS&)yx=9x00J}bXiakan#8&P;78t}&cA_} z|2}6yf5Sk&_X*~J2f(!yfy3-l{lvD)72es#D zi}`-`zXmY*I0d~dB#^>212+X)Uc3F;u&cwaim(b_4P9+s+`M>G@QYx5wD+G+_f320 z6#Z^KWPaG$-dW98)fX%mE;qH})QamXt*_LrQrAkeD$K6Xzo>svMSL?);@MCUt+mSZ z4%#OkO4!1V@TTGo#gng2y1MT2hReOc`&Zt((&$>FYZZbOgV4OO_t{fb+#6&F{WQGR;)TmAL@n_XL6`97G`I}XT&#$ zz7G9Te6YC6f0h5+apn6fe_lC!<;nk^{O|gb>r2w1RA?hQqs1sbbm!e)Vp(MA?|j+$ zqW4AbGetd$ZYW>9{Cx0ZxgW}X<^Re*3xDsqjyaAP{^Xinbu&BiN@7@IG#=DlgFS+e zmONb2y|`QP^x_%C=St3&+!wkxG%-3cIxP80@*wrEYQ2@_mFAD^AKB$sHQ77KThU+H zzsSGPk5#Gv74K`_5?3*w#|rxaK95CkD81QEej?Q=^?7VlO#YX{gCl}912qHk8yp)L z6Q~uc71|ux9C0R`2|lv4W+1hPFc*!V#?GeB8lD;+9IAb7{q6i6L0cd2wDpX1j&#Z= zR&xl;IIEha?Ud-0I2Sn=X%cE08WvHyoE_$%IFUirjL0vCMeeT}`1y^~#2T*&t4z3SiLeyhwp`N_n|#7)tg zqIE-cLpKI)3^XZeQt|@W8Q2wQ5WY1mU!Ym3St&bvc59iQuZ1?~EzUa5p`M|hoxYvE zfIr~>7i{!x^gZu+-qXn0$oY`9y)|eI7+*pkwg6H;9ZScg=UgsWKKOpg`y~y)dGJ|q zb+BLLg-AFaj#tf8&1eR;jp=UFBHKdSi&BdBKIiS>@8NG;)Trnm|3ChxeO-J%xqos$ z>FDHWVQFF6f+Bm}T;1Febit6-jYUF{(Eh;Bfi)#-N#z zJQUr%ZA5tO!5y(3vDI?ba;@^L_O$Y~^6dt9fOVdAo))eaE`p%_0kml}A9gbx`?e?$ z9mO-Ze58EdH{2KW1(7%ooC%%@evT`}Q?aLF%TXYGF55RN-tiIkUQ^bT^;YMt&ad5H z=Y5h|;5)_f^!@7j)$=*t@B8ih?GITVvOLF}o#qj{vq!%!zAipFGC5K%R4(*Z;H?01 z)g>bXBPCf7>>ueL`8fV@d^r2($`ci=nxNyDc4QpYJ=Hxg`(E~K^KbJf{V9KSaJ%<* zZ!cFb*ACkb+f3%#9Ly}gfwr4;jODf2IoLVatfW~Rk6cY*Qv)t?BS2sXxVLz;4$ z{n*01$Y{%G%L&H`hrGxJ`3L*!m#bgyOOPr`6*>G4zlIU9C3K83k1{Lw9m!78H)!?0 z7k)4NXyDO6mEtPJ)vwjKHVB9u`8xP@us^=6|0MrO>b}yv<~-{>>lGX(MtDbf5q~Xu zx!lX;=79-C6N*~Pb%3=GezZ$GOFRKzz}KXxNm1vbCySo;Kkb)a zrMz@Mvwdb8VH#o59Fn}-M&b={C2~1ZGgLFwG0-tErDRIUK~OVTGdL(bDEwyZ%~;D+ z%T&AEL%9)jRwtP!nH$<0+V6MW?|RSko(G{^Z+~BZ-x2Q-?_-|FJlCApoQG|PZ7uL% zlcw2IxuYAF~HRRXj$IhmVKlsl7P4IH{Qq*Hco==)obNn>X6GX27Syl&fqmMqjzhcSBB+pbsTRbabMcU+-uouS>#yc*pF|3{*JN!vHl-H+L!j#!4GkO zYk=!Nd_~UTv8@?|=Go@i3dst|VbNjH384w0A^27HF6mwJ92gxK9he=O6`F!a^)1O; zlJ}!4r(Ex}>9py%?YOO@tD{R~=|SH?-#q_3|6|-CId9IZ7&G57-*Ff{*X7J{YDPPe zN~BD2Q(V7ud1CLVl2Iksim&C*dEH>$;9udt!rkND;}g;o(q{U7%g_ z+8yd2>i?wZlcKd?s(-4#t+%Z#JX{W&!#0sVx^ge+3N4H+jOiUhwi{2=n#FHid*fR9 z;_}6(OHP;U3GE5ZML*etce3`=&Z4g{-!|X22mc>Et5HRxidL5UwA=^ap`!LhhrEaK z=kPk)b+)eT6N|6a`H-*e;LzZZJ_i~T*Jgp9#m^LX3v>4AI_5s+e%m|E+sb#R z?~3=Tcd=)&=Ox!muF+`D#_@U5{9kpLxVGp9?T_z|pN*W2Yz=J<4G#_v-VFW#@{vCh zJrWHiLWvpZu?=L}O1=SJtJm7i(G5E+gZq@{l;=IZoq7CTV|B* zLC@|K{vMZHmt3{IwY|fA!+kq|eEn|q)X(Q84A$GMCaY;T+|wv_`-YKcl|)J+^+NSR zPX?Y0OfQ*Uatd?^b_nhc?+#argLI|z1b8b4e%CKqU$S;}c6HA2%<-J|o%U5Js!~)B zc>Er}{2o7Xe&SqXU1Qbm#RzmH|HPv~?+w;6q1J)cfw{$Vd7~;6{{q$r)&~}n|Ga>w zhcp)7qi*VJ>SOxP_Mh#d>!Qo!^Z1$-H7jaTu1Wrmde{H1-{!S>XFF#*pS3<~Rj=(| za{0SbccvJwjg1VA3>_^wTJm`D<|HKFv1G z*4x#`HOM>2JKjIuKcZ+v(F1^Vz&F=3*VD<_$=T1^&#K)9&BoTlXQDy8LHzgdAK~`F z_QCBX+e_{N$H4gD_+Yt6xyV2~RiDOhY915x{~G@_I;;-scX%xAb?4KJUofkvYOn zneNfwZNJ+-a((1l>Rswx;a}mOQ8Xj}y#Dh2>3hQSgy(|eg5w9v4;E=Fy$$Ne!z`wLjGsy zy_)Qw?Elug)mu#d-T_teN^I(ChSr+3W_KrcC$J}pRt{AO)gb4+o6ln+I2AY@xF>v1 zSU&81Q_rO|pCw&}XDrWHbl3HE_jZ5b{UV=NKj44BKg2i0r#oIg%$;qWZQ3iB&g#j` z$;^M~^-aK+_b~oNo}efANZ^sc``~==e6U8OMx=JUc6=9l%ip2|`z!k(JMjtbWbb5u z#Px`4tY@rew|9@%>+|}a^*-y}?%wXc-+90DdfWB3*U(TC=dvKXAbTo#I{88DgIJia zYIu1y4>k`z06OA7b$8_Mi2Pu?rMjgwCso~0-QYEQ&0pKTw*BM$Cx0LQ<^9V$kepHX z$2<6~HgPp^dF&qhljbM$d9NvF%7v5RWZPKV*j?ef!dT%1mHT`G-VMAPm>8NE>K*MJ zEnpd}ZniESR|^YVW|z4Y8t|uGr(NHBcY4?Q*ZRj7jW4atAT)Z5_ zUrLW?X>w_DM09wRvEGpGC|j{DpUZt${9WEO>m=kJXZh+7DM*DpC zeD@093g4$ipB9ZSH@aN8az*7v_(%G8;Fl|ply5BGSTrYW&Y5!^(MzoytsGq$Tp4Us z(zxWrwG-ENf|JE3i)#dH1eFiJhToDq>&l*`o3`A%+)TT|vDN*pd$w=3uUk>KqGVB` z=sB>;x5{_ceb#-q<8B8usQEd=a|X@wK9qbY*)7^Fs+cIx`R&Eqi#LHE@Tk2MycCS^ z^$iY5Y4&==37n{v!!^Uz!P~)G)nCtmjpyi-Nd(4`v zAf-qvkE4W%d>H&NSS?U3U+>%>xIb_zcq-T{(kma|2d4+8)tmW&F8hAVeoH^c3yz++ z?M?Ph_HOZQ_FV*SaHr=^&rIhGXI)!eTU)$ps?+U=;ObyWT9WTa=SBYs{S!heIB*?! z2qhqL#Pd1|= zR|Bt)%FfEpXFSh%w)nRAph1gj1Jyc=8F*Dccx)cq`oax`+T)y(o|1kd{zQCxczYP) z3qIh{lC8ztio29_DJd5$m(PC&$A`pMpzGBDrfV0T2!ue}G3PPo3C{`7zrKHc$Nb0q zt3hX9XJ5=6bARRd%JGxsCyVxE)JOOT-NP-hEwS<8H^R3B>jeKU`G?wbS;leI|#5Y_pUoig+ zZz8>f$!Oi5#3$wN@IT>Cf}aHY1o{MOfe`pM^lhjQxykp5?-NThOEQ`VDrR!@xb?X8 z3Fi~e%AU#|i_hZAfnspP`?pu`mHe(cTc5H%&fb&y{-@HX)6sY|K07ieay580sMz~T z$txv4gNDI|!5QHh;T^FZv3aR^Dd{h_VWxOGJ_5t>vfAz5wW3#xrunA%X1iy*H`_Pc??hKp+9}eZ z4a9@-f5Vr;p9eMtCKXRA9)E58wQoWFlKLe(@Hc%p`f&99Fc3a)nzRtc* zEq|}{uk<%9*R zgy)23#@>n5!7=C-^l7wP)YIJ4?6rIC4O|UeZ+YJGByeVa$@h})nD=PD_Ppr4h_C1_ zn{;c`<0@j`{kGI?sh?s$#bRNukzhEec)KgGJFqIaDmadJx?ZeqY!aS>+G&4*xs6xQ zYiNTO@J#1S=gpp*Jr}$eysLeyeb0j%yf=6+xGuO(*iYD-Tbf&H8EY9ePbPiP3h@eY z-BXK#i-NZYZV#M=k6RL05_m4uH&iiNF**}>jCV8dW;8b^zk-Ks?QAFD7r*d);aTik zEgC{m-p~}U^M_*XVh(Yb@II=in!{~02s8-j z^JpJ!AFY(ElpM%*gn=*V5q@L;#@^oD-pyF4Z_qxYNfb#wI?Ed>WZg+?`r7wdDQcdBwjK|61H6&@`|*v^peTs4A)JQj6%WYaT~& z;vdIR$6dr&#j9FHwTcFVS^io654|6H*SOZW!nUw&qiLh5Hv12YGmA65@aNhT*%bLX zxSv?^cM0Z-#m)FjrUj-2&V0k08b7?-}p;-S@lC zTjVXOQ*=vFWq4o8CC_o*IqbP?n^5GbRaUEPEn2y=>6scRAif?S8y^)J9cdeC7qSGc!To^)f%k*&2cHT*6)uhzN1G;_CW|x0 z8TB&`p<5|leT`#{qYj>zzj=Q1O!L0&eFRkHXZl=z*CX~vs67*A^@_E-_80yr6Yz20 z9NipUPL10q)F)&Q*~qdNgj^9J)h)R8N#iZ!E#=Vr8%}@m3|>$(@O@nyTN@i185+SpBJ_OdxzH9+ z5-tg28yek$e{q&Z)q>IwOQmOc34P33_F8t;H2d89+-E&!Jr1wad#~qS&n(w0m)qfX zoVT2}+=s5*3uskL%S_7@CyEol;I-Hz{7iUHa8Iy0cs)2S_;={<&~?%4qqP&Y6F=gl zw3|-iakhO9;#1qr(baLU`#yI!Z+Gt)-x%L}zPY}|-o;-1Er%S391r1!b3Z?$jBeS! z^uF{td}3!uW<{_Y3%!Cf_7y&FaWfV0abJOlyF3jp;@MWCtVWr%e}?0eYjIkg=iKMr z$GpeAzxjUieF>&|r+WLi`?#NXJnz_T*<<+zr2@@1zKUkmj`;U+eXplOPlpht4J->R z4Rj1X7EI9xnH-%I-9?=;J~KWufms0UeYLZ;wa%g6(ZJon9rZ*#;`=@UZxZV#;vu`u zzRljt(ksvZXpb}~9qoR^$`y8m<+d#-t^d8>K*dHQ+8$BlN3c1*BNuvRoxG!3Gcx09L7 z2jRw><2|%BvMoY057zSfP<84NYuFmz7ugqS8*dx$fo{3GA2?@i!Y6eIq&szs<)(kMmdf zLqEVT^@uzZ*&W*z`wj2pC#2)ToaLYF!gsZHwf1-PcN}ybbg4Jt2Sr#^_!kDrg6kHjHjbRS*-zftch?zfG%i@%K@r*@J(%+(*k zk49cCt( z-5%}OuEQm$Qle6VwpnaLWIf;Ag9GXvkp|HQ(c`h>v3kjRN$CcbXBYozLl?tacuDJw zPb98fcbDeOXa4TNj11h^K zyRUa%?|jkrV*WGN4$P_Csa*SX`!qCKqG$Bk=u2>LokE>Lw*Y-Di!6&&jb9&cm1>pR z&#t@pgHG(V{)!jZLB~NyRd-eQ2k`ARy*GI`d$xFbxVyV+I%_(c+nU>U;=xf$5?e1< zFZULno)6>Uy`JZEEOab%EqE;$1xnz5#h-Ind}w?v&r{lxn&sJJ`oUD&R?Ehamh)!! z&F+z&QJyoPI|$-Mz0I-BamISuI>R)>6sNDP{$B|JMBK|8oR43^2f`(x5|sy`U&FtK z$3(|O|BnA1*FDI%b5`?s((3%(^1Ef2eVBa|9=|_v4j*tA8hY%sg4OHn>=jt5t# z*b}izN9La15Y!snv1xC@6>ARYAY9-eTj34bB=3{>pM`@ zb-in|V~gVx+b1?!{+1j?nCheHY{cs`kw571=<(>p$izrE9182Kbcl9{){NJTFG?;- zDjz+7Hi-7R9>eGB7HZ@-9B(*ocGY&7d2hXLkNa-d-L6j^pE`Qjp0Q2EuTHvN9Fwx| z(9zqK+?i}0ZykS@ck7{bk1_l($3z_ULJm=F`vZS)E!mu=Kas{pTlqW z+t*swT28TR{5P|NdzpGTiAQeRWZUGe@mu43;?Xm3*M9(UTW4ZtV*2?{rJqWRW0IbL zx6o7gJAO#F*>1B{bzJXw-uXOPTL#AIA4aB29b@fd?Jrngu%1NcQSHgoP9I( zW~z0fbz)p>T&!2LS2PhxM3l34CQmgdEQxm9F;VhSX%AdsW<#-e4Bk2G?Cb0gJ0Eej zbhUK702E8cIL120+s50J|2WX6)XvRL{22D)uUaorFHxQx`m@LyjeJIKiPVYQ5UmvoR>geF8M>K5fZs(o_B&4vwxzH(o|9i{#mJiUi z(X7zE?7r-r)ST4L_%34aTTwH)ukyFa;VI!6kr|O^@b>;E@lWDN`bb*yva=1d4SEj$ zSpT*@=6KAZ_w^?CjqWGhkGWU5R=OI~OSjl9_Kubg7R}yk7H)lZeReJ002PV7m19+6 zzef&5Iz^t0d_o@aUG%%?^!Utp2@df)(2mj$v;0htn~s}CSw~st+voGSmv^eJI_Eq~ z7r%~kyM4QTi*<|jE|jA*UnOskb<&E!&*YE9ZwbXe8+Fa6(NCZUa1`eM%udWotS4TH z^E=6$%ty@6-h(dMVm#nx+TOLr>~Z_|j@^!PaJxMm&p4XH0gSg!w01LhGoNF3?jEM5 zK0^DvCVJH|{Ks!gv|u#W5FbFF^EFUAUMoI0F*wmWbr(LK!!w#UlD9w|cC}}kXP6gQ z7g!t7W4+DM+_BKH!11)Bi(`m=u$@%Rs-EY2Xb_|dQU%&K-;((@(=YX6YD{8WqH?@S zyffbFcg5Po{scvda)}Gc3(1Cf$L(kSR5M3Uz=xbQpD|aoRj~bR-)leZIO$NmP|W!_ zYd>pmVrycH;V;&y@QFh0hDiTmI~t@9Bp*n&BR{wty&P==o`Uyj7;6~Y9^V$ffKRrx zp+>N0`6jbh<4ogCjp^GDA@-K1H)(NMVP2cN=Fy96<+#()5?|Z3=5=P};L@;Kh`#st zsU4{fiAV5v?H6krZ4})e*&6YX2-J$*6jL0#JJlv-fMYTcd!*M$+s`!3I^DVqPtHot zN}Rr6DH`q7WKec{}=jqMnuEuUg?PbhhL-BIzN@^W`zo}Rzb~XB6bS8D+ zCGOrJ{mu{Zof2RDaQ5M>of*Kx>}0==&&n};SAMqbwbggjbLbfvoCVI89WObW+MC)3 zS_fL2nVXr{F|n6p5?)-$uk>q{!1tbwpN(&deIBb0ZUZ3*i1vy0iQ4oS24x0iG|RS{ z9qkV6o$NI4GN0tWn`ED2|IqQF11iz^r{gb2(w?+WvQ4zTWqH$bGrgG!%pC6_@2!9y z>T>RocM>xaX_So7$V% zKXNQ_^kzg0hc48lXD}%BxXFIT=emfJpWf1DG;{Wrq{U!U)j(v{ToUigzdOPPh<~qvTE7%KI zR2q%<#2UOhcT&6jN4@uqJem@166<3dVybzTa}Ha?TEs@jN5#7)yCuI$f0ceA_k8Xy zJc*?V^_lrI^9Ab#>mvIi`uQ;NjyN@9l<=u)!en*DCQiK#*|U|yp71SR@gqZ z>0UYt-Uc6&CpNP-wLXPjcRiF9erM`$C=+=NvkkHh@s)iS-<<)t$Nv)lCH_NvPrO5- zLqh(DS9$N$SIzL5O9yN+JDTE2U$(qtIgHn_I4jkN3HY(QY^`mjEJrQsNmo};)mGK^3|?RAC5wlY=H4Q-?pvo@r*BK%mRuQM9ao+EB%bP; z!&)ByB;FEV;78LP(?4W?$SRj<$o%g?)32r*tv6Z=?IwE{;uMmO&a@*1d)3-;oOzZD z)V5>sz50o{_AtAyxALr3;&b+9;>|=L7DSq^EV>7O?0aJO#>7?MnY=UkcKYpfBQ`oT zL#bW23FZmr1J(o9dG>jB`NFqx-t9EG-Mm*5tQI>47RncVli*{afWWYpkDHAEVxQ*72<4XD|(X zYX8(;AHQGmeP`(HKZPgKR;EJlKr27a{DC;P&GE0}mtz0Mz6LkNZ;IDR)Jbf@2Y6L_ zbsE|fbZ3I zws@w&_lkqBn5>v|Bpiw9_%koTS@?m({fVLYH%nW;LbhV|N#;Y>GfkQy2dv6DF0qtY zI@vnensMGIg4^+l>~8CBi(BHB8}UF&8`DP3t11^D9A>VjuBPrvw$A^Ie(@LMJ>t*s zZe5FelfLBFsm-Z9_{+;bOLqvvpM~x4|7c~s!@AYB)wYp%Yjs#0-*MM!_NO~uiqGSD zCYQz!m|M29AG$E}QRbD@@YH7F$#}f$FY>&gWMd!4m&c3gA8bo)O@-0X9>7L}G<`>- z*}fe=;HB2ZRwF&6-|Pp8hH?Ar%lNNuqPV7}nSN|F27R%vHc4Mkm>eIxk z#MjJc^`(FQIgYFg5{nYPifOkWj6I1J5&wvjjm;>Y5B_f1!wSkTPyn=_Nw;l z>@V70u+_EJv5rJResJNS!ba>wone#tRHQP7pD!QPhS5ZT*>W`G?cK-FAbmiY;qNS%%_gHk&Q( z(T33m?IbrqU+@lG1l~=(mui>nm>iXOBT+xmB+)N1Fi{(i-e*&NQkisF`f~P4*1~30 zGk&*@h3yOPFgG>-X*poA*h;NC=z#`o7j5s`X4<~AZm{;Sbg?YNJ8dqzxX&=BUX8h) zbjFbN<7YRSnAM-Y;9v1G@!#Vo;=L0C5~Gt7lb&=@+DtE5o+ckLFCIh3w-$ADp*3k4 zg)eSDV#p5q(qqU=7TIRo8uGjzF}F24IZN~T%!`Pd0+uc1>nOMp_S29qx_yIv>@TtO2%uDc3eG4Dzi0u!!WxK=V_?WrUCALMj3f6MmgVoGO;njvPS8YOz zV^?NxW^d|XswL;6UZPQA4KuvE<9p+S5Lh#f5O(o+uGPksYjAe zB)?1inD{*LEuVR#WKrsd)XR9iRLYYQ&5q3PJ%LwP4fFNpW%&4Qv2L<G)|HzZr9?@2e#HqA;+K#l-WHd3wh?e|%Ju~g>XJ7@dXcD=oteFvY) z?|3`+we+>T3)e6Ney|?1ffw=C+CzPNC3P!$Hg_w00_uc`#j*lnKBnA>ohNZ@&PQbs;gHxNtHrf>Cncu*#wIhCV$IYkA zE_!-@z|&mM=Y83F)_Ny-NmX*6kMT}Aj;F?DcHJ(b@fAifr#{{ms%K{5S$j5dDX}TB zB~g&H@do^vw59#&75KEj1s^q+4Uo^!_*sMQ^=M{YW0tVRW-~EqwwQ>r(RLr%$)j+z z=gcR~*TIjvNhq{8tGzRMY5z$5*(up2*(K3EaW;M_o{JmupZk&IvE*ocO-E+OWaXL1 zx<9}*^Vl`_OK4X?x1==y7?wk~@UhuQU7iZ}Gv zsjpMbl1-AD@!b*M5x)RFPJEouyYLab;s$hxr2pKO+4sqKZB917Wv*kb%X{0IPE;K0 zYomRXZIrDaHTrS$al8(Lc+~APOy^GM%#3FTyxKk__I6;_VKRBvgWR(pB;HR9OAbl? zkoqAt8vWbhXkCB6PU$!3MrZJBi`{;YE?)wzp% z5!VKxH~BK&1tW8>=04|nH^&37a;kjlrDXqP3os6}goo>qel~qL^LJ)i?wwpO`T?!b z3Cy7`I}`uAKk&WWV%chGj`wS8aK!Q#BlRZBag@+sDC|?X16_$y_Id6l)_sgln7sUM zNLNkwO7%+FQ;yV)shX*k`1-w@o}E6J`7NW3?i4$&Ti8+^fcABQrkL*a2Q3d+&Ja`F zR;Tr6%RU?uD_TruqglF)NkhWWn7yUmXp%_F@rF#b%o)y!3Cv4=kX!<)rD~-7+#mfo z=kih1UZ=FrzGtIx5_-epTB}>Di)FMHaLPAwN1e8uwk$D!WG*et6-rBzGOIvFZ04*f z+ku=jm<%ROU_oLbQE@AIb?@X`a4HqK^V8XMwul~oEA;x+?{8vmV%}ldVL4$vVI9pm zoNk-JcpQ@xR*!W7-i-1(|AyK6ci6*w34N|t@R|9ET1I`~t$cU&L4O7xB|l33m-;WY zh`!}}=w57MkMa*wg@NJG3iwdGr!gQ3=;R{fld z)IBePF_tlwdc?$c(0=)jckmF(RRKJR)KmX7{b_nwYFKJ{a(VK;E@~CsTs-XY#wwW(l5$;w2w@WNJlc^%;#t$$X89e0Nt5$ zEoG7NNnA!Bv_5Fv1@?fp;0a473n`STJvmHY=8T?a&u|d;)M92mig<@~t{Vczt`lvN zZSXX;r5?anO})5X_*d*>=jcy-R)4@(L_J_}zT2$ZtaWU4Y%ZDz^f8Cs`^;=2)H^oE(_!n(CU`h&O8wbhMQpx2E>gE+xzL zg;VhH-eB2adBOU;^<(RDYj0~W>q=t&L}Gx6FKNpUDHvLyebGPBD(skf3}4pD>Gr9I zQ&*G!C82Fn(^6AYqv#9oLib$0OF1-&w6`&Ut@o=qP1VJhwaDVP%meE!>nvR@-7HJZ zOU>GGXja&)a5ek-()-u!@F}!I-p#y|nUbEIK9oAdB+ca1g4Dvi=T;zHoUVwgg0z}A zW@XFC_gfg78$U%a=maz8KbwCxt9E)9bO(FPd(4MThfVX~`)))-^KEw0wEz4Baq$Aa z*gR04FISrJ zde5cjznfh_@siEW&CPF+XZ5l6vHk+S0X5m-se-fXYP`lZZ>n9x0EXiT3P*G)Xl{O{4CV7puG&v}64Ux&SRqEx2!wn{T4Vg(f7vw}&~aVC&5% zubNQx+5tS*Jv;&PE95mQdfP`i+J@2@4(XZvb6RbYLSC$KQphV zR`_>eAH0m;f6OCIBTa|VIJ2>|Bh`Q*=oBBtYiN3UT6!*b z6_iEZ}?b*rs-13FxOYkUolXrT6 zX@E&}@HqA_kFghgC+cfkP}fwh)-&BRt$x@u;1$5iPU`3M&uQ`1z3{S>M)*QBNAG06 zdQ0Iqg^X325^&RsDF>LDP+glf=eR+P=5GtXEo_Pk!Bpm@{y@vHKH5x*Cz_M^kTD^0He}xTKIZGV}G8>&fVTv8ZowhWn!p(B6r- zfIHwnMlgf8hAnAY+1b}{0uZ;McS|Nqst0HD8NGog>pr|3x}g&#kCXFg-Yi8IqOqwl zUaX_d&$9=30R+HQV(|v^hWzINrC_|*aIaxBx=Y%*uZdFjLFTA`P5qX-9h3*p0nI+# zjsK4Hi66s(O5XDOn0xDom(YIGKF-HU^DN6O%Mq|1RJK&I)WGLJdi+nIzqpEeB7tJA zen07aZ%c1YU!cw$3i_p9NbTWH(H!6cd=$djNLD)Knm=3z$5tC{Rh_dJaUl0tJeH^M z<&~GL_UNveu9<$r!%*59jH03O^lF*30q3FdJuowncWb(?-_$SEJxI5w^gq9xc{wvL zJ1?vMz2VG5D34Qqre1W!6gK^6{>gj~v-XN5jO1DR@pJp*-CF~Hs};lq-RaT;(B9Qs znKv^pr(eRm_EWmK_rk)pB@%B*%}l?O-kRA)4bmj{588DfpfB(^J|v2ZkC-1ZKV#`( zaaiqa;I+3_u$H$D!Q)Z=wRB;+@Nu5kc_<@{Bola$wr8t?t%PqJlSsjn~^6B#AKm9Wth1@~<6#5)rMKiUWshnvL zHUB`%K*>&96<2(R69jc%9j>)trrwogC8S)Y@-5A+8A zrY@y^<$Y6rB<~e3+rpa)J}=($8@2Z5bQR%msN(m3PS-SS2Zw z*3?c^z4V#Bbbl6{CqfA?fu!fZ9j`FLd7i;HM2Y@1p;_4M)Zi z=;D~sEt-U`N(^XU$POXyupO5^h_(*D30$Ht6T=!|&?D^!)Tr`UM@q zqp3%DcfU!=qfMS-;x46YHH|s;mgs!$EZkX0+Y@^$1D@k^ncDuA>8PQW@2Gj#o7S7u zllh)Kf1O)tWE@A|cM|gp+JjWiI0h^RwbM7JJsA()8*Q^&(6*C){#CZmNAe7g67y1~ zGS0xXVp&NN|Ef@ZcWYA&}q@Ah=I= zpLU!1pX%?wweI(=d)Lj(bf5FqTeWM~-d7XPygoVJWpLp(Rmo6_Tqc_BqMalfnjO&! zkmb&U(Sy-bky8=r5$=cY$@n(hAK$);^bIXyEn@4?9?X=UIejTwA9l9q`{?@UWG3Gq z|76)oE`%>&3?OxsVWdIuZ1GkVO}>3-w0zB8u++2t*zayYPcCf4>-4l~ z&=557?eMKv;LZLodux-4IfMvI{S&zz!5RU)p>Lwj5=}z!-MXl|$TKk+!i4aA|KLXK zPaNgUY}0SoHwE{Q9>IuSL2EQCj>L|}zKedBxI?Cer-jQB-w`i~`^-DP!1wHT`e4!C zhi<769+Y6~l6z|zYa0(44;qgXt%zytP(OQvO ziTiePcoK|;li{wBu91$>j?uN~h-Zaw@;h1$mC+3P4Ry&6e}1L|8&vZ zlih#OVfYT^O7Wc%-imM~zBCA`l*MpDe?p&)kh!gBvWcgt=t}ozC%P`07fsPrUH}fC znf~m3`KHP{dGGUqvsv_`fmhl^qxHRLw@;_BSf~*ZHYA zIU}-n`GV*|k1jhvy-<$7j;?Gc)YvI1l4grf3*7V!c)7lzcM|??H-hyHLj@v-K8Id* zvkIX}GnIVx5^c3UXeLYEEgLBtSr=Xx9v%KMaSwLq6ZM9NeK>X~CLUp;!!r}@@D!a> z*N<9F_JYb%f6gX`lTGA2W+&wL%Nb(rE2&+2yL9132xsbRycAnRT1Kw(8MYH22)WZ` zU;1F|Al{0()7GM^l3$Zwvk2wa+i)=Dc`v}XE|rkEv-HkVH~8@pILF?_Ab4ehbFV<_ zL%2Of(9f?EtrOkG+@m{M4MQVCIDK~_v!b)26VTh?CcI1k!x=6W{|w<0 zH2`;*Ob^wAfX2rbblJqaCC^RrNgH|uiodigu`98&(X%p2qw1N-@97@-HL^7F1+Jz+ z`1cML0otRJA^InxyC+`gr@&}V>QCxNz_F>0;Cgyh99B45Ci-5FUBT^KzXJHhw$MVjc)6hYr_HGaP0`6C4Ot>`Ui z;Nk$S8s-w`;X3VMU!ybH^RLl*>4w+BJGAhB!MkNbbVBrx$RCmF;FYBaIg2In_?5f3 zcf5D}D%>2=0TlgQnYqaM@albhjuD3Cgz(|7;1T{#_f~gadqFF@*D2@$@4}0&CwkG+ zXGr~iAMWmN#7UxTw5+r}QBg`OjqcWDxR-a)0M3cuNL6%si{Kak7iUmr=Ou_|@b$mN z6S6NH&^CAre~Ax>Xt%CGhg!7jevJJX+fV&2y>y(uCu=lobRr?|g6P+ZuAOLn&Vcj3 z58eF>XkzXFUzGeOJTUPqp~bXH2@n@P(}-xk8LLSdK=LB)+$K)AOcp!uzBJ{Lm_RP)qG##eZAJpsxcS@wTWEwc%qW=TvkC z3xTPM=GF)8d%S)v_|(1C3mS%3`|u&#e(rb{7dv2zej~gbe}h& zHTetNm=<{N$+-xDD@hLffjABy@TT@w!ZT|M`Yxg^%sNb3h<7U^F_4}|z9Zn%NbP8? z#JjbXdEdeK!MNz9iucuz=pSrBCs*#(QTmaIvzSk2snlJQ^^^2R=zagd!)831?xKTu zFYR8M;D%#3BQkf9oOP6(B7I_IdXo?#&AR9}$xKrGI;C%wI;*q3liozl*u&5hWS~2n zIYxu*Uv|-T)s;e1`Vqb!V^B|&y!{$Q^Jm~;UvM_|kWZEqk0XyFL#eM?##+S$PZJLt z@$~D8V$T}w8tqQrPx+gT{M^b!4(^W4`px8$cRKNGJcoD2RKBMwxCLuCAM$-$3F!f| z5gCY1%!=H^Io^k>@vCt+sze2upL`D=b|{*F-NB@D>T~LUVJ0DYa2t3`9YXqd!GaH> zhr9^hQ*SW8+RW`M$1BIXfLq8pY(rG$j_pei^)InFwm3E+J|VsUO{rt(b-zak&q+-x z`aUi&{Dt7-9|)QY{VAd{_xT9j2;E3Hn$4-PGQyd@1>W!*xndsv1b^UFE1yB?U*QnS zv)>lo9u=O@R_>{{D5VSTw-D_ld2im}>-Hx&ck9g4N+ zmz4t}eGq>TUm05&TM}IymHM-Hq!*6Zt*N$FN2*7wN58^Ns|)jL!HbHbOu8IRD)C9p zKyN7dY9_tNaY8U=yTN7<3@R(R;4*WH_Gqt&|HJ>l%UbblJ5U!&Z_|-(trx#Z>Yo|( z*8juDT=3C6D4Nbj`|K4erFrq7E`~p}+*93ovnCU@i9eX5OAmhn$JPnFyOJBk=j@mG zukoqO+J2AzPFByBxJSg>zEQLhi~)c2N$hD%xNC*+JL-Wl))F*&wxVA)7hJlcz9P=+ zzmeIG>*wj`lPPoP`|JAaW-`N?h@N~8_~La?u`G{IifD_>ip`P|IC_BCO?-@gic0U0 zGoDM1O*{YwBAztRJ~U#s_Yf82>3GNobbeh?`1ZNTB!A&_REL;_N6k8Me_*yMn!2(l zD$o56IFj%-9)X>m#KZ7K^kuY3tO-uAo|t%^Ttq`xurF_tHwn>L6n@;=eY$S@6mI};D052GvTbC&Xb9)mmL z=MMQs^NmKhR{i)+D)C*(`H=TX>Z_T=Kf1ql&$Q39$KfWAgO^mAeoDUU`?32mIdhGp zO`_5_BRv$6{P=;m6}uJt1dpjGT%I3M%sb9(;3b;-(oZeKCs)o!MrzZ$a7!ByBXuKn zeYAbFW$-?Hk51Xfw2f&axzmT>Q?>=)_5y?&@kTO6GxA2wj8@0L?;B>r-=jvh7;RV4 zgEPT#&7sSoW364c98bAaLf+wBc%DkV(p1+}C%$C`!FgR^!za^Drb%BZd-`vpZ=$`4 zVua+wC4^wSjDX^L1_pAcHA-rPKfz%97{+pkbk#ZWu$xBg)$ilCE$5V1(XY|1NqFJj zV4vVn(jlJtFX@8oNPV&#ZlR0sYX%|DLTVGinP=na+5;a(@!S=y*KKg|E~1@w6|c38 zc{g zCpWqpGeHEeh5ESYwqFJNllMyU>?Zxj#PcW%cSA7K(Zm+r7TpT8KSk?a_B_s@r8ga2 z#vkxlScJ#6+)t9P{wAvMor(ASd$=H(@CoV!&qz2xDxN%tvF0`u2F)h)7NZNgJZ}xaL^2u!6eTv0QF>|Z{F(EcysBfs;osY|Vz8tN?CG>^=!^fl- zJ#ubc9^LP{t%>(o0S9~zCt(cn04@i#Ij#6EWJN39i6&nbdhkkUI?g0#nTe}>XE%v# z=#8z5t>?Y!5pR~(93STn=_BBfNNpm$p}fBuy%sn1UJ2jTmh4*mtNRxOsz3r`%BRVf z@C>|)tBq(g96%M`6?IXW45YgLI#CDhWOm#EkDWRwOLk=jD}DzLaN)JXiItyY)|>P@ zIemJAj;&;iLHeG2#J9K_h^LnLBy2XuIdN7R!Gmqg zY)YQnQSMv8ddtFRs?E=lnoZ7MjC>+I+_n03`XnO1F261dT+@$WQv2|DnvSQ#V4P8A z@Lmb#(4VLutrs0a$g^KaeK#sTGCqmATKtnvp}j0#NEgt~pNj{#;0rzZt_INWmLPW0 zHw1X=M6W~kNJPY3`bmfexUc8rj0}oNZ*z*c0!AlwoxHoPr>L}mze*b^0f zS(yh4wvZVvgWwybh)24|xaTz1iSE%_uz*#}HAFXCG_-$Vhf4Yc;e}s}UW{(0X1@qG zNcy#F?9Z%$PbmHX(np>|PxmU$X(#ZIn8rPoL7ze2gOFNOW($Adc@$)Z0FhBEz~%Gw z=jj*HE~E)&@d(}eqV!KkqK8q+nUnDFwj+QgefnZFgqNY8eE_9n@ote_fhY7L>+w)4 zOz$RmdslrIHX*F!_fa~jiMODCI}iTIKs0wmf3+>{RKhosJA4cN_3NYSm_EOb4kpKx zCBGL!qqH)0Ut6>&#D7kF+5|IxLr5zRVZc7!UuCScVQQF zDoZoNea@ZQUDt!{*FCzkx^oGy$;$YsY{MP$Bb-17ksm#C(XDNQZt-M%m>$F)pnBIM zmXF9ov?b(u4@IxO7CKzwqba^p#lai0^Id!b*OOjWr`PGrlW*m_5`4DF|9`Jm;P(ht5Y|LAf5T5+fo^HPw7z^-E#f_6J!AW#dpUviqeY^HVa~OOX>um`{)tG3-1fGRAj$fc9u=#llfF|7m2+@3qtNF!G8|mBOo(k!I{d?!xWE~jJIKr z{si-zeuT^|Hbyr@OOT1(+=FlN-j1ck(nQ<1I@;ml=TJ;njKBDSPWpe@z5kv&BtTWy zj`#`eW)U@|%nD`RG=$!GCi@8IW9MS!h}XQcw+StK0aCMw2*eXY^oGx|2POGr7k*-s z@H7!0ytU|mJ=Hzay~N*M<_dy$tO2``IxfJTnS~Hvi<&&sDe)=zjlGRcj!mLMY{I8% z4Px_4;trAAJOV%UR`}RfV@{lxydBW^HR5MfL02B;#sc22KbTJc3d^as?ik+PGW-DTmAKE##>#RFUyLol z!(s}%)AOib*P#)-9W7q*&Fh3aw)}kQ*UJ+Ss1shS2eb#Z*U4$;@p}*tzs+d-%AS_Y zZ5k4C)@3d&ccOeI;o54z?BtmXjxJtJdcFto+!%*nk=(J+#`S_(F4Qg3F~;VGDXSIT z(nfsdhUhSV2d{Yoo-j9JH+TZy#WE9Fh&HkB$s{)uJz?{-772~^3i!Cl8C2j#-XNs^ zJVU%DZ%J<;^9dh1i8b+)?T=ROL=@)d;9Im7-Q+9O|B^T6;U8ToRxxqTYmiTt5&6M> z9^=`t5ANYwv`eL?8ONMl=8_uD+HA0j>$Cam#rMso8PW-6-Q9BDlm1(OTMLvbS{ ztO7}el0<{I30nPS$i1)lp4!3@n696dsOOT%U+v+pP0&u%jsp8=2UlKnfxpD#s2G|Y zJ@MbXAH4%2I*-b9K2QFBv=8`C33ftr^EpbSm%uN!UQ%0p6(OuAe$=_c^ zUmf|@O!}=;*&NPYA*7=t+~J$>@w^y28_OQg!cDk5 zE}vC)j-H}jegxNs|Dgw7lR54Kdfacp#>R2JC-Cn&+`$jvC09e6M*LJZqU?PVN2f>N zOhzuvR=BiWCN~b_9&ZB&RVWrtF26q-$E|D zt9uB8>M|9>D4k$}CGfp!q^YNA&N*z3zI@xXmTBYQE?&T;s6N_cBD`rJ?>6E;T_a|o z9^Z$1rZ;=BL)aS|hL34i>gs~z_anNKIy?1GUVS0Ghg>p+=W>@EAjv`eJi_TAybRoo z>jIp#yzz;#F;qL2*mG)zfb_cH*pFj(xd)fUr&B9Vrk|LKX303PiuT~@8Nh&+(*wT3 zPtvQ4aI0U3an>C?;~YN9F=UjoYVx8#B0Y3-@ww#=`2=P*h2PUSR+~v@J?e%Tcvc2u z>-il$P#dof)|n4qXRSudH+5Gt6Af_(ckUp*pC#Z|)8Xt_gR^!Cu5CeWDQ!wO5nNBY31($3>Yy{ubSuogd`J}G+S@wI^Q}_PF{WgGqz9QJ) zEBH#i!36g6tzE{qc?0L;TU`Ti#Y0+E6T%@S8}&(Hu<@_czr~ki1U>F$W+E+P%|S(- zu@o@g=H%kb?1PSCuHOV)tvYTa)lns{f{uJa{C+-b-)UjSCh9p8b>ds{*8iwiTz^{G}Kg1YM4|JHSgN=F$1X4{{-W!&(n6qlvs9tQxEd*``AOiFS$borH#gmbR?Ml z0K5n4G4qaSJ=zKMPiJ|nu8^x1@qBWjeK?A`dMmiZ2|RnQ^2R?#GgFi1NNY@uelB*2 zZ)g|@;PBWI%*Cq5_d z+IsNUxW=Ka!W^J4`u_`1`aexQkjz~;6n|GOr|<%vmnZPod&A#f6R(&H%+d#@bxA9V z|AU8J+GEU{MxggEz06YPj-UBWS?CWP?6W)|8;{mb!S6cEx73RMc6rj@_~2y5M?iQ5 zckuM;0k)T&yChDg$`H5U)Y}BTdgk?b7zfilY5VZb5e@i~WD3!~@4-2_P8fA&T_#;t zotryq4IHFATJcSqif__|q!6wXU-AA9V&Ci>J#6K8mH3m`zkG^6$XG|oh(0_#`@{`! zAkN~JOLt4%J3OfcZiv}&4>`xK<+oHL3yDpf_(|xS=B9`KpLVYHGPudxBv(=pZikk- zAvbg4*7OMb$cOcLm$K2L7p8|E$+Jo0GabSCYB@fqi}42TzHT2IpnUAyw!*Q|0n;sAwK7EygzR-H#)%cScwMhXng)E@$Nn(8d0s! zrUzZfY46J071Ji^exMH$&i5zw(^I&gD>B#lfp=dpAkjg%OjiFjwuFk|m)LdAWNB)z z(>!^pTg!6>#rr^db@4b7?(H>dlp_4?(&IFT10opj9(*0Y)aHe&F;pX%)Wh_LcyU?N z8{F6THXJ|{^65;x28 zaK>M;Lq3$<@Y{HvA_L2}Wz|VfJ)OQGoj$4~Ic+1@{!8*zVKB)t{Eip&8H3@D=Zk;A z6VUV5XGwUboWj4XF?Wm#UcHU?sy99pxtXb-0lRO)Jn(?_1lc64)x))XN2j<(yPmuD zEA4V-03T&%mATPi?$CqG=p1CN>C8O7;Ag+$tUu(rr*r;Va?js{cQ6$1*`mxyRS4yO zQj<>s%PI+1={Tod_EB2#eYNJ_d8t!QFmEZ&ZyG}#w;c}5-*}@*E-HzS&O|(0{qUkz z^WOf*8J`Pw_K@7$o*ZDHvbc@!%ziMS-*C8?$bNTybd5fP!}MY|ZWFb`Hn5E0WMQq& zsOtu%y%f)$y?9%k=AV)CYneoLn>0ob)-T$MlHm~MckQ|!uRE4Uig9h z{yganJ}Yy;4~x@FEd%YlN*?)>x_UJ4R)CvDe8Jfh}GfN9Ul9SPcoX?t1KR?;%O%s^grw(Y=$4%5q{c7o<<|Sr4hWjeW@7>pfj@< z%q9!jw<8$r0x-gp>8H|VceN6+fnK~6XZ<5R+C%R4Fg&Vycz>Sc-Tj{DZUnkKM@=>b z@2YR8{RPizg+tCRT(O>TyFcf&9L5i`H_kjRb}2gGxwwy-F9`rme8INky^#ZaaT}h6 z9k@BllOwBfM-71waD{iP9(?p?aQ1#i$Dk@$)+eyo1z@1rxhrPiHhG!4^f^!GI`x%& zhxzd2`-R+@ia=xqYJhR*N1snSk@h9~dCNHw75FSkbfIBh;t}=nECQenWj#j#Hx1 zZQu^JYm>EYxo>|?nhCbJH~l{x&%Q)sVhWhDg}auCG+F%u&--(%8WsH&?%^?LGuOr+ zNccRT;3w^)zwJoR_JsWRHK(FEwQoi8?`Qs-;pCFP=?^k!6ipqxi-z+(ZQ~4vxI_Bl zOsL`SzQ*k3A~PgEAWW-xXSNSt#HX>lSCd&Xi$zTOZzRoP-=QG+dp#%HPmam~4(}kJ z+$FmVtZt|3dCz2_i5^oK@b)34Pep)RY zf8Nl0u1fEK(~6Tm`Vc;L!u8zAoAsGVl@_q+EpPKW92ZN&30RG@yc?{y3_bBsu#-c~ zo$P7Ow5inTIr%Lw;NS|b1)P+~TMxm_C*uQE6R$JjC_iPsyq=%Y9A4}L-lg(9iyqwN z?a=HN>}e}J4e@eqNEI{^jC&bAmM3|yLfol>%iW3nO&zWot@sk%IqJn-v1+|~Qx&$Olg{D*fn4|SY)&EpC~ z?S6@EjV9V{yceQ5BXiF#yz?8F4+z(2Dh^I1_?brXyI@P=A1*wODsWlyD=|9_E*ze(5;0O^6TSeO&XVz@5$ymUV!+yxbMjxB>ql z_EA#{9{vsQ)d}X21>s7K1#b|H%|S@r`-syZJcFV{CPHv0@tc+%grCt?s+nFh;h%Jw z`dxTzMft7-FB7a%_?+1jwe@`};okJ=S3zOz8u9Ow?`j>nNH|li3E6x8gV;?7?j$pc zr}#ezCf=9*x*9mqiO=H$%|p#ZYQl&%3U*yDfdf>bE_tne%?;I^y5X=!<$QcekJm)_ zN%(0!zz3-*&)7vSJV#ukiZkJXID#;84~mEK1bWW~cn``P`cKVCaE(?x?K1*lP`hUq zsR0-wTR4MXC1z7^@G}$dy#egs%0Hitytg90g6gCO>ZB?BI|G$yE&iL8cur+Wc!0_r zF9ZAk7YR0ZWz0e4JDk(-C+adUs7@ax{F-IgNM@d8h*`||Z?gxMkNRX1=UBY!rV%pZ z$w7$6i{Jo%5~7hH`|N_hH%Mxb6ibRGZQ%VC3}!VUzavV#CFHYI2XPR-EtWBw7I60# z@Xy@`a}ciFT4uQwxkaL}NbDmV5jiKl=z#u9O$Jk#qLW-}+GaQZ6=mGFH`QFF#9_1q3pvbbzQJPvpW(cLZ(`5!L zJ1zrp-V*Q9Cz^jXrQvtYK+mL#QbieNA8s$~ER4fSHRp84498B}4qIVsA*+{N9?|`j z+%*>7?aI)KkeC+!?fJ)3&Q;!3`*ZEjmQR*X%RVmsnEKK6ktF;1QtGAD!k)sOC`9&B z?168LY=~4Q7u?48u8pCML419Fw*F+b+Z}d?(}|zRq?DE!TA>I(7j^LB87ik#LbLt2 ztT*o6Wo2zuZ4BG!H$bKcl(eddN9_Y{W=AtyGut>c538_2e3;!FJGo!9a1VtJhrUNksFm7W zz395+y8HRw=Xsyzec~a1EdA;0PX+MQ5v|aCp1dBNPw(p*>=G32pAg5=K}8?qJuw>1 z)J?WcwwlhG&dO-dPRuwyqc5XB1U^kk5gMbqP|eSRNMPH_+AHI2M(c8v4@^T zW}Cw2tYi4rus``g@?R)NOtg-(9#Re|!_i*+6Rr6rL>zEjujrKBXc*eeHgk#O66ggL zG}zFX5wFn`++|zgC>)IJk9-Jy2(?D1Pc)n&Xna;D{_)=SoTGpl%l&)h|N;eGJB&IHe)iIvTNSG}VGeRxj0PP;O@GPzip zc5QI2cggqkr+P}w>(A>Ka)|KrW~9wXqq)}fgzvM|wA?h>I@Jj%*_ph#B zT@IqOtCY*<^1DQrzl^uEcdCE7zeK1+NcdH`!GZJ9|0IJ49Aw{2bb#zuyLA;laJy`~ zY@!|9*xtnc%Jza4m}J{U>ji6ZOL0qW)3>I=#)8IIpnB40*5dxqg5G?9OP&@=4>dt6 z>Z$*!|Ge*lFX9b*XM1O&$U2NCa>CogNBFz@52DM`0xgA-krI)bOb4ej>v)v(FsTZ2 zpGAg+hAYWz>YHzw7vY9WlL$z!>F1&&#p?ec7j+e+BBS+`onf1zb^%jETFHtfK$ zP&jD9ts4>=9NLODU3qUgZ&}Ybo|CSVuD7YLQ}?CrPZb?&@i8l)=2xfVRnj)tHaH8u zvMcV6OHTh!{~Qg(f~G9!)GfEIwEgP%)!}pcoI6u?rifOv47kN3=ug{eTT^RO>j=|G zQ!}_{Npz&*&nLUp9og;O?BC+=?Cs+H)$@y|tGg>+D3=n^-QC?i%QMSU!duc?%U{zk zo++*2pydT$6(7kf)IP)6+xQn9^;C1Jd98J=^{Mhy*+G7c+9I}_L^(n<^sb?=l*ydI zoGm$fvhaI$a&vc1>YS7j&dGD;__B8z=6&lK=o!fA&*3lVE99H!o$GB$jPj23O1>2R zDACAXg%(SHboGa^bG->4#~@rN=^tdaC_XQ87T;LjT81e@l~sH%9qjE$PP`0BS+z!b8^V!JRh(eDu1|JxySB0bUC!g;57uY4XSPd@ zOAaLEIURdbej^?^A36s)2041$dfOgZ9$8+qA^$rpQ<;@MMZ-gQu#1C>gCEeNJgOd5 zGkY?5Om4G#wQIHOCb1f=cI=2e*S*)g$pKSf5&9U-qRpbRC*wm;ay!UIabq!KFHBiL8FB-{>>=+M{QQ{g^kOH@|l+G2J)acgcUr-wzG3_V}7CWU?kp zm^0~lbJJ^YV{ck^kLz0+Sc;?9xZSqhw%@+rUe!^>QNdB(u@QaYX|`!L(fAhK!}7`H zlZA8AUejJ9Jxji5zG!hYgogTu_?=#-x1gt>=Ys2k3!Bn}w^46bZ`VTiLihLT_v%*P z7Th|E44fv5igm+U=Sr*|#)EbVRWZ5_~>KI=T^6z?o~9wy?Nl!*KkMO886qEBY$>R(e-@+Yuv(&)!eo zv*?nEMwR>>HN!Q-O?fxwqLaecl`cKRE%phDBo|3;ZEkI@X02uw{pcin5=yy;?VpKN z_SN>&wo{3mH37}e5~dQSDeSl`pl_4nT1V7f^ft%3abecgMZdyQ%r{ zz{u&&<=*Gn>v`mT(oXe92l z?6p)>Dk@EEO>7?sse_N(j@kT5K)GnWi1uS;OE*(DQv+jtBLp@5HqGyv`plTz@NbX8 zjQ<1eU8&`I`g{1l@s;!S^!D`11NcDH^Vaj4d?ugxGi^XKY+z_0nlfV|$3PMD(eyjSk)LJv53a@rW~me5 z8FXdWu5Yk!@SyLYub0|e6_32;t`-Sz(xZ4^h*tVP?%VF0>P=PZ<0hddp{4jJN*}xw zybTD{SPnfCVAH#Zt)ctKZpA^!*GJ!II)%Yd~PhR@$9XJX% z2i3aB9yV*YruXLe=26yB)|JXirM0aU*?Wa;81b+2uksvy)VY>9me;0Nrl>J$ls%ud z%!8ZZPz(SVKM6m2O?XXsUvOU#nUjFjxS|mbTl4!xlk9*BFItzbOFx93+i&Q=h&SqV?=5 z_Ad4=@XYtfyII0j-1R2)O==zP_4<4#FFh|kSSa|m1-1pYu<0atqu@Df$yxsz|25t> z-!~6ahAF?;e@UE?+$p(J1`_rZM~dQ9oI~tG?DdrT$`11m^8t2eXXs|?DkW7)628>k z@ZE4E5Dkb%^F(!`s-YLk>CWlC<+|k(uLSweQfG;V`r^RiKwgxOo=2ZY52YPUo5lR1 zg1&-&ANm)sc=wOt)m20(q7<|hq#N1A^Ei#0K{wm4%2H*3b%6D~`GYyHDW55yF`rR# z-6>F?ap~jItFs553s2uK(K_l7Y#$VTPeT;pKXH92K|5^UCY{N4}u`6~z(caPC@ij39ee|-nvbKKK ze%8X~BIaqvX-44}4oe!ARE@tQTO@lVA6kTCd_Vfispau(9_4Q2YUDbddKwp+=czkf zJ6zd3**rPDIjDQr`saq`hR#RNM`dqg37UYfIipYwO-HRqt#W^zbewcNbv|{rOKF!< zjQAd3;@9?9_BYB~WvFGSWi^_NvZK(1n!v%7Dm9WCNe(54M)^nin|qskw|cgE=DO#) zkvwx}#+UQ3`-uCM=aol#f_47&elx| zwDs}l>1OGc(8U(KV4i)hT|5?%S+EZxTA*Tmz`EbM*1XnS0KJ*E`nLMkn%0^!X=T$g zu`iJoUC<8x4*rN5RmI2Qfa`!uykW!_aiD9UYlC}(dz3m-{m1u@Z$ofH@Cte=!n>6@ zU|1j47c&(zNe>`?5$zrA92=b*oel8Ru0bqtE^tkz(~s?`mPn(FQ#?T3TAu+ zP3XTve}^gsDg`V)i?5a1N)?=D65eK#yWUE8-g>&DrC!@#+dnoqHlY_hpLuT$@c*~W zC}h9w7FtU0P47*6z(_JFnUoY;ifx^3EeOg9TYq9Z@9He;EGu@7mWrl|ref5}pWxuk z2Zt_{UNBuS)N$zfbf8ZigP!j*-!tDjJO|FH=hT)&3$Ufrgw(#G8NU=yhh?EuQy*+|ZEx-)^D98Eo%DnbciSHv~fGuN}%yVv_& z0QJalhw$&{gXBW~h63`sdgv?1y^>o_Hsi7&%; z^EUGa;|60-HX%4pNiu_$UC+M*e+RnbCpdt53K+m$z+KS&+V#p+)m_z{kGgj*9%SMh zy$%m-$yqnqDOjAgIIR`)4|qO7Dx7QeHfh$qSu^x^-q z_O$f0Y&UH;?M2f-&S_?6 zfAuW&%=FIirutL;CqpMg!u8Dz(?*`_a(2;Ig10uXHn7TPuZwr@VCN4`KkI0Nae8o%rO=R%R>T+rGE$Bi0bv z3Gpg>fl_>3b6s=KyU^r?^dj^YQg%q!l-7}lxW-$Z86B0d{g9a$aCoh_UnobS0w zp3;?+bxKbpo+7s`w=Lo|Q4w{LFSK81qiK;e*KG3|cE&hte0vJSK>rX^2HK8wEdA?qP) zGq8fu_R;oyj(m>##525(Khh%&rOp~-8Dq(0%4BM5Xlv-C?WnDqUM*dAiEJogNzVGy z`=@uWXP>8pyM$Z3g0Uq|ZHBjb3wKLAR#NeV%HcZ^I2kyJS_p&In0ScpgOee>;XmM; z9mq+2z-wMQp3|?N#*HzGm=)+$}wdQ`TH$B`(L&jwr_2n}Rbz9t)D(0%@D(G4!L6#T( zTLI=~+u+*QjD8!9p`7Ol_yb@0%lOaZuXvJsqkvjiP4gsikF-=Xdoz2*_wcR%jsL&k z(_o=UJ}~&Tu?Fz2W14_wn|=fO_ob5OnP-`ogV)rtRkKaT@2e`f$uPW*b2zd)D$G1~sgA3}(8JqbsX*)Mf6q?&+>MlqVToRbACx zHn-h99)IEq-Z9=VJ<;RP?T|5+7VQMD;|R0PC^{NCbHKFMy2<*%_QbZ_G0(9RzwYcQ zDJf6MS?P`#URN{i)07#C6`-+la;@Z&@b7iZLLW2#ycc;Hv4wJmR{6L2mwUH(ooa41 zBly{R_YU`I_a%2<&mhk{b)i}a{55wVN1z+M!bA3thsOKGop8_AYnSm}8VvQ5t0q^% zU*bLG!kcspX1tT&aL>c_BwmveisSA4gZmZu<`V0P2iQ)-Be7<{{== z#)n21JAnTseNH+RzZKuf9^^T^lJnyi@QQvkH`v7sm+GqNYR2#2!Ui@SC3kD+0BBt$o9BLMiO2NPjpEm*ST0 zJagT-;-~HPdo^`g>2H;yAozb$!uZ^PBx(*&}mGm0vkC}u25?K`)8JZND zA6OnpWsztTb<7F+^r~tjwIsdqLUpy;hY86J-#%YkwB5U)N4S?7ye8ZwFNX66U@Htl zXCfU_v+uzrIx0<+0H-u7c=sR736D5-J4$fBi-B?bqL;UTYc^DM`(qP=ydeU zt|XmI((5C-EHtIh%@55Dl-j%xW$kMms~iLI_*~^&<1FPY<1FSVsa$aNhuY02bbRu{<*vH@BKh`?|S-NC3lP8O37f<63A)d~=)m`+4O?}P5 z>SbP6ggM#YFzTi!O-m}QE2P_k2FAza56Q30ugp`e)2v6xSyOFOZTE;nw!=7972;km zrrfmrW%u_s%TTR`;o4a^VWnlYoBzrLr;V*rG#!w-= z1OCEQCvG#_*E_a3wmWw@?KA_|otK>-9WNXs?EUOxlzxiE5-~Rfb8e!qq%Wh%qsa~j zJ~z4@9Yc*nAN>FNpE5ITsMb=;d&+orlCyTY|8ST0RPj_->#Ha5(Ub4tZtzvGF^VN` zW5L)`^rULS3%J2MRvhn=x_C1v){NF+$|!K8AFzD$FtbatZ?vtl-Bd0pi|IuI=67Zj zORSF#*9;TjCu(4MOoV@{kA=~|-WZ-0oE+Rj51P%F)%O|C#**sS>N9#Fi<&{*rXEmF zdart`FpJ0$EE;SK27glaq0wZ^z~{MwCQ@JY1|NVCY3a>wE4O(^zp>}V7j_2Eq?4nS zW3zpwy|=BMZKHLmb%?pU`4MM3hC)Ruyv7^oF&v8Qid@0>Fuy;K|6lcy>ZCWk<@(1} zlo@IvS4r1J<`M>v)ALY$Mb4`1cY_&dP$sFzj?+pw8c+4Fd8Gr%2bsAj_;bCmzpxi@ z=5t;Ihrj4N+vc~covb8607+A7*2_r>uFnY4|)2C98ZZ zeJ{z4+dVrxVRr;n^Nzc$r<^B?nnfLq?^#LweQKkByja_stJ!W*>w`{ zt)*y2{|_INbGU#A_AY)>XFX><+dSL(5!M9uTisW~mlR0%=M8-sT8MUaWjHM+G;*G5 zpK9f-)-lyJt+%YF?%k+VvRAgZaI|ndAs!Ib9W@-8?V0VplwOK>5A8_ak$ep=oFizv ziJswr=zyqT$$R{J{4MZ0?c?d~(Suu5c2#oOiJ8PI_eytNwXQnSH`130PbDkLI#tM< z;`w}&y)w7aZ500*sbgB$TO@odw>h^{`M!6~B&Oj>E*OS*gne)R-aN%P#VC6=t&&7X42j*ph`F6B*Oki3I@sJjQ$;?V-<$~qBC9gT3xdP`j6Iu|L zwO6#g@jYfd6W_qDW*<~VJD}gb(7({1*_YWTn8~*Uv{}#BoRtTJ&+GF}!pCetaA0sJ zy0E3$Uwc9AESjUDua+k{Px3G3CFT>>lh$eE&71hQE^{n(+#*I0)9usk;)_VSvaX>w zyl=Q~5PjR->ATWru=ybxXq)hxDda2Y%cf>ir3YB*T1tgg%{7AVz4jpq|H8kwhk z6D}8S0K0!e`uOyHu+^@i6S>2*!&J^%&e{^(TRc8Pj<92pb0A%Modgd^`qOSoHzkiH zk45VA-_fS|oq5Fiv<+!{@U2Jwn(= zc{}2HHaj>w7z_u(OW^+3LDR&G@tSz=$m}TtbMxnx=a%M53#Ap9(Mxy^f>mrF9w_&f zjnsk}@UbanDrK@7EyhE-L%MI-$-BrdxM=r;`PZ%Bt>9byQpCG2gExb>x>{X*?D>~b zYN}@}UE)~pIIs9}(E$YB!&T{w&V_;8do}55(y#2GHbpn;zUjUxw>6Jdd^@M%89C80 z!SNp4`#d4Imdr`s;)}QfU#0iP_eRlKklg^$Z0L&KUC&^z;9=hppI}z|-213|rzh|% z1z-CsL?LF0^0!U$Px3d%x1=xp1kv6N!f`H+R(VnSJ?Z=c<9vb74zi%VB!5XUczy z@Lk@}iyR|z)0<{cGANrY8!i8m<3(F|I@^$|vveqf zp1t_1e(BEZZbsdk+m*{T&$Ym{&b{8xJUdEorfw}>@PVhdy zhkH8$<0V zvP)dbP|7d{-@eJ_N#-)t*Mgr6=MG6Fgby_jPv-r~e!Mh?S#QDPdW@d`M#CmURd}5H zVZ`Q5%bT_Wf3MQvGO{`tNCEtr=$+^lY;lEWg{LF&8_`|urmg|^ZQ^g@?}|^%Wqc|` z>!3RCR&Ms;RBE>ksJUmfWU>g~j@;Q|{DRc-%`sjs=Hb;`+rkj-CJ$IFIo91_lNOs^b0E48GsA z^y%rx*f)?Ic+_;%RM%S9+RN6{X<;}ekMGzkUN;TLx!kB)u;H3?!}kxE`3vl zNQKB5_7OXyUnx0jsD4O-^Krv;!!#G)9S`@no9=MBZH8?dAv3G($~Hx2by+M~Elu!( zsb;KZjIeXL1V70f={eFj!F&4_eSQVJjL~zT8+fN3_uK+>>wkFu@Ejm2&?SBYXKE`w z!0f=xz?smwP(w6gC1*Xux8x-IqB2v?Zq8=zY3*qhJV~&;t&ZOvI;Ylo$#K!)V?MIj zw%E2E&-NDP7G}{H7d<@DdT2mxQ5t^@@n1U%p0-e3puTaxabI&?hkMe*^#f7dUEDp5 zUZA_ThxeHOsDC(~E26s~S~yqXAHUPT)8EFMZMbC^GnsARCw=TI94j3aofTn{R&{R2 z7hZCfV6JB@XDoG1bxfk``iu4#?NT(SHn8h*KYTwdJhiO;to|n6CisPiJw-jmJTKhO z-NJJa48D-JkoOAA4c<|Bl^5ZL21^o=jJdvjP*?QOkd-Hbjo_h`d)db zY_M%4JG=*lKTgK_znmo=trt02m-X5MFo=onH?yjz`i8J!R_0Xl`T|LR1CWsT~ir|W%=#%b@?}$Hx18GDL zgcXqFgSe)NpX3YMb6YvEn-Gzo`uDKou;ZBhn7yK{qOF#-ruDt)ovE&|o^cpEJyNHw zXP@Q~ns|-S`Zop)fxNzazMblh#5-Aznzt%(fw-hzN^l+Q0ej$^&^ICB5Q+BVh4c&Q zJ=qs}hfZSk>2DSc9|jGp)XiqUBK+{o%wTeYVse3 zJ%$>(8oIsgmF5C_Sd1=Q@o@1l%gupI%#3GwXL-A;-PPU9mPZrEi1A>*2fYWqUHqLB ze4q>A3*m0;E*4;}f&rOE^f-p0P5vCuPK}bJ9JL*_MeJew0mlKyf5bS)SjSZRR6A?0 zN)#+-9z3dxhD!$Fs;@*7WC(kf-SHBe6POdQG9wamv>!lPN4ZA2auUJ?YT<6-zU{f= zdG3Ag?FGK~ZMaUjC!3U;(l@0Gk3Jbq$`A0vMp#E$f42Q>%L$5>)tSvXmZ(bf0macE zOq55-t^7rOTs*mWa&vuieH;7;#pU zTb-@G@xJkH1M@l=Jjp$l5?O%8O96Trso`aoy8!)snRkq{j7#J!J%a|xS5Js_gm_Bd zwcfS1!%20zX_~2*v6ssAb_d4%u(BMkNsl!#juH8p3Ui-)Az;p#onSU-#OShSj=Axj#hWC zU3GA;SNC9&>i*jEH8rQ3oK@H>dE^ovX!1S$9Q`@LnY#eXUvyhU4^>MI=QI1w3*pvY zQLZS9Pvl~iRab?;*8s}yI7Gll?mGs0oF+v_tYNCsOI-)5O@bwX#lG`j`PXiD^p zQ0|a;_I~C4%G=G;Ex|nz4p1+`N96M4^8BOzqv{a76K?C&$kfO(Gz88holg2s_n%ID z9e%<)^ojL}^%PvNJdQk$&qN_-A*a+A5A6@_-EBQ=!@+m*;7K;#INrFCoyUDidy~$B z7sy_7%EoF&X=7I_wVG7>q6&7LjbS-aJua6E;RQI4FoF0wxI4LVK_*y$O~ zwt86nb?_i-Z*FVO2!1jcUQ`!bm&Eyydql7;x#I?cA>F`d@frS?%nI)i2B*Qf&auw11@3ijDslNcg;OdT@F%nW1%n%W%uE@Zf}ZkNBNutb43`u4}HV2HoKzVw!uJ+X&_-XIQ*4JKXD}b*L>pEn!$>^YkQ2s3p{a-a+0h{w)4nc+(9C4-9`s z?`}Ril$FqJzlYj}^kl+qm3ehmC96``R+l?OYp-vw2NTI@?`i7^-{D*381uaQrhBF> zcnnq1SA~DRLnC{vL&@Ki6X8w4O~F|5-!9J3sch?R~Nj!ST~ z`rG>1W`jSMGnX^Z#EW<_+>_C0E3^V{t%3hf*I?J+P2Vlw7IlltijMoa>$$5tF_k@) zTJBoz<>c}4^eN&=E&NaMD>?ud=Ovl|*jMQP<9!>>jP^HWjnaf&0I9drA(jYtu^mwo zF8(xSsxkoIWoRbJ^$c|lKWGPQMbrKO8hNIODI#ZYntz)AhWCc|XXfZOF43-0(TW<7)IZ6^{$zVYJHwLXCCrEBn#)_uTc_~*dhrY% z5D$sIwm!CLa4ZE=m~EbIo`rv;@Di?38&yQJW(|A6DddZ7q3xjwfeC@tzBRra-ke^e zYE%b$2GXN8_Z%c=$umN-&U?#$%byg|gd|_cj#dVC{8X)~6>pZVrmm)=@RE)whn0G~ z4{aRZIqnmZFA5NOv($vk%j+yVDWb(MPBcgoj1*gRM!QYIokRFje>C5axMcms_#k23#D z&bnp0Wvk|>#=V}!+1A<4ndXQ)Y^*meq4r*FU2Uylu3=tmTm*-5ukJ9~o2OAc5RKUS zq52`lb^c^uvTu(1vno9*a4krD7S9IaclCGm3*Q&MApe^$LU}?nP;+;(54W40`9|!u zT}P`jZ*tz`@^C4mmZ+ttLhw9%+#!I^cInrlLMkV$$E|`vmN%6*G2$|c{<8?FisqSU z_Y03Y1Gqs(ys_m>mQue``@q+eyxoS#sAg1~d7F8W@ABsk<_<2z6{sG1Fon_!rDxY> z(za79!xJoZ$n4sxH6Z{ z$$URwIA6Gbpnrf15j-oqx(np{mg{f&^m(q=#69;tcPq8E+S1q3cML!EG2yY{;q0#e zl>T%2dUoYj8CDy*m^zzoFmJdEpP{?Go4u!_SK^&GNNvG_u|v3oDN2gsGP}*=lE)=W zeVEEj+=i}$>==l5OtE0GU=H>(hOsA8U9HA5nd9j|>>$RdW7T8cquw5HZ@UG%2RAV{ z$cpaA*0il@l{Hl~(v#)HZ>c8!oH;EyEx%cRvz}B=CNSUq-~=;>m&z;Uf%U#s&gmx8 zCew0yGSQ0@en1cOVO}t&8p9o35g+ODf%1W=zNx-q-eTSwY7OeXE1nyK;3ti|jS@L) zIkT)=@R(ZT@xVG8yE~7PcA;C{&)CoCHn~kDtR)k8)ggtW>G76o-!wn5n;?3D#n5)T#C~uuHqJBS(D50pGaZ5DcK-H$#=kza-3?c_Vje(Jrm*0a{awj#DH_AGSA zv+RS3o8*w)$}T0vn!%cEHkvmXHzl}~;+;^3T~zU#`ZM%rs8yg|AI;a}j?I5p4VP>OGl^der1*D{~lcaLq4P4>#V z5}(-%K(ECKZYevVyVU*qwO1HMIzOMc|T((M@N}5iaPn)H_eMR(UUOJHw zE|BoCJ6SqegjZJtUsB=LhS+}Jp0quwB^q0-!N>j%{~f*^{3j^;QaivHH+eU)1)1!9 ztUgu?z%6}2KPCiG;fc+`Bkxq?&q!gEVfLUsRRe9i)6^@u!QiWztC_9*Yqats=X9u~ z-$eYt>}-HCK%wok2tNIgxw`1h??=y3YMeUgZS7@FEjw#X{Z0K_y<5Gb)zRuj&qX?+ z-(XxMsqcwq@M{YM@(0@D0Qon1#DeWrPO6+FB=MgOKO5fRSsB2yd!2Qi^?~w05gz3= zxN4J$gUUf=oOP`Ap81~nN%E8AP2hUf>5*mUxdpQ>md5a0z7+l!M_l2~N`5ZlE8;uu zl`M6XxoJMiZ?`X7AbVg*a7nOvxJ6jB)tjM>GMJt5`Se38@SqY*rc!d{sya7NBbL&jPU9*;{7aVN;ojh(XA1Ww(-JRf}zffK%mx&4zaMN$`U1Va%D1$MB@d+ABb2W1`Wzo(3z~21@{HgDU?uEXh zwtwt@?0@5X<7-QNMabF6=+ETO!aF;VxsdpDK8gGrd5B7iXu{IgX(VScT+?qeZZ{S& z6)|-+cQMzo)Un(lp#EBgCnwy+dFFZM{-*vW#8iy!4ebpx;eJc6E;{R?|0z1yC-Ftf z5y}xd6gU)E<6q-{?0XE-J=QngH_rEx*u^aQe&Bwf9S*34A_XHQVq;0?AUeic1WDl(%!GV_q=z#AAKKvg93vB(x>-EoBt4AKC-JKpXD<= z**wNCj52)LZQgB8wWL~PN9HS~6x&M$m7UgI*2|X5mYL?6W;dLSoW>l+Oz0)LG^v`? z>8I0I##hA`^F18G4>?;XTS(@)7wLm#*Y1_?l}``hawgFw&?PXF*&^eT&{CXo`k;W- z3JqY{`>%ioGK;@@>4_TQr#Fu~;wSS@X1OnBS!TnEnPSOD494SqkZF)fb~9EPRvAPG z*sir{^C#s``X=rFadZ|?Qe4{_u4?a|0mg6$?(PuWU4jP)F2UVhLU7jr3GPlH2~Hrv z1LPt>f(9L9q_w)L?zbmjq}JtIpZ`-@jBg+T*t)SX~15$O8WY|F^y&z8^?o z7acMo(%u&A(-Ww8U%angpl;xK@ZSuaQ+S7O(Iv!)PbP^!mEjr?;o=eBAxhRL`{}wqpBk)bF7^)B|9w-qIeBI;qcw^J!(wC<# zPn%1nQ1{?k=ktBxyWzj#zd~}NSMzDD@c2EV98nxryS0|Rw!Ieovs99z+j-i08b&mV zxJ|vG7E@O_J9fhLEQ5|q^4sR%;yo5;hAw!rG{DQF0bYVb$g+dcNBj-`&r&VQV* zNh{yx-tLa^#CXc0G4yht4sn0$Ugla#hV?+FO3ynG4$*d86~veIneogB;1N{|IcZ^_Os94H((5};Ip&Y}UW;aZ zH(5r5okN^S2+Rxd9B3ZhGdf~a#8mY3f_=90wDS~k7jbU`bGmQ8ZC>3RRg<>iiYN4dc>@f6oc z!EmH^lHW5Id$2yfKG+Led?7x8#=geB*OX*EdjsBp^ko0xguM(;!=`v%T5(f3#y(j* zuLTeJ$!r?px}&`eV2XFz9^oLV=xbncrgF~Rs6&E*#FpHJ6I?9j_mh~;_!z5|KG~r z%1g4cp4y(-PB5FbakX)6Vo$q@U1{NnLJ_SfIX}C5x_R2U+qyqEKR7GE5vymbXA?ha z(I-p4wgfNn&EyEag<~_*H_JE1I|lvyWz^~OP`jN>Z^d0N`sD-u1OBgq?Soads+#!c z$&PCqTrB%xAHZ|>(DlHT%w4vFU1`u0@VxcBLoGDWv%2^a{}}&1-(Fv3N_w4E)HCXg|E&KhnepYBOAn(N zZH}K)!0=~eXtu>Excy&^mQ(M$Sc5ql&Q-?|E!b$a-HN>>218=;!a}KjAyUZ{OP2fST|7-dE6{-=7tZ zV|zY}8=)JaDYzMZ#o1Y(OfK=SaoOCqdn8f{Zg_!vReHYRo?#$1r#+iJTRgd_`tEve zU~<&^_c0(eFti{2bq)WQ{_MVNzINVrUhyHxj?aUfp)JU-v!?#-|xOSf1LjeB|1aN zn$4}{);8l5SIwwuh&Q1;;}QHE^YILRM6TLrM~dT~^R9EKYpClIb%$C>MNy5&{%(r) zGY&o6N$bzn$~X#bQZ^}1$XuB~PS0HXT>H;dKI$00L*l!eSIeu3hRdDmPR)^&Jt-JU>PF=BLk6Ug!#t)pIxwj{=#fy@TcPybED;F&7gAQS)LBKRM7barx9=ANAtIVtin7*o#7x!`Q&%9KbSaL{?s zIUg@YdG{}o6DCB9?dXLXCN@gU8J{!0$EWU}qT-|Ct0q=W+y)mr5GN4 z?W;ViJpZBBDi~8RCOR%UZf)F}xZ||jo$ z{|qZGTl#WJ<9sXvXN2PlM)p?&BL+o?mPkA%q;EQ#elGn69FsTkZ{oXu?D4VNhwdLF=o<22{OqLJNir)p zrpLN3Ue35f)!hb$ekxY48!L032}YFgB&%%d{Tj+h<65$voEM{xtWri1Zt zObEq?+6LPO_k-PGjU5pEXdJ!}z3_w;4owsQ%M05}o6TW$G^RF#$GB`x+mGa%Y-C?t zRjZ;s@ISyC<$8Lz)NZMQ=ZyS3;&Y>v#woq<=2-7r?>i4yc^)}48zi;Hy}_L`bB@e6 zqHjch9oIE(P1aReJ5xJix5sXQ=Q^2ZVwQ8ZGduXx7V>O`UsMJkk4MRmlFuieON9QM zxG`}<;#hWdty5d4N^hl+shS5rFHP0d24p&&b)L!akvQr;>Mlp!<(<5WF1SBlrjj$Z zl`NM>aM~rWb|mEtJHul*pC#*}1iNF&@R74s&Uop)gcorWoj?P4zoMtjOWx9J{CFFY z_b7Vo9;w|^uP0qkYM9Uz%BZVlT!Hf$J+cRvg*R_wmL(8$KH@A1EJ~jn*?YB{fCfgALTB zluId4?9-&DY)`t@WBkX8;!O6@`qBE*{=zQz55g|GBhy}wjIK9eP?hi%pBtVNE)XgZ z>WKEI2YaqQlLlNYI0)^a~)Hr4wBeP*Ln4ow! zNPjRfFfs5V_&kH(R1j}u;XKTRlO93p$G_AA>J!<_F=ah zWIkEQ+-Ojn(>JGg_jmWp9WV~hL&>_r%FsOkyc?J`dM{p0L|Ml@qngJykL?NuTr09x zWNl|1r@Z^Z3%%;Q<|~BHjl7FR5{e{LiLV;}3$>A_^w{TPpHHR#k}h{>K0L_J;(vO} zaoa)Upr;(OPH8-LkTgZgJUW|R?ug^CL(Y}K;PSFZ>!tP7gafyj${xxVTA(e^e${`| z2jX!j?|QT&+99)|+vE0}qQ0W!&Z+CD>kyyYOU5N*Aa`tD`u?WyjK747UN5m;;>v`T z32hQvCr(J7kStinDE}zG|4T(eZNNAr_CT7@&Fh+ag$VqP&HS{_Gn>b@9pF=BnD^_fI3T?oyW_``4=dj^nO&kEL36QAgB=x^@By~g}KxlCf2#Le-W z<44DjiT^F(w}hU_J(EkPl}>vK&JwG~>ccEUEpwf7oycP&#%Gz3<&Wq;qR+*gi}{*5 z5_KdhK2vZomF#tb9;7D?imd2Z{V~E_9gl2LvbeTL5kfn|1!Vm+~U*XncSAAeVzVwdLv&W zU)^BcU^aYk=i;wfk>2*K=d9=V%)e(&icXA9icN}L9=AO1OzfH1@zLX=U%?HjiHFWV zI7ELzR)M@P?bF()37&wMP)u`I=?@tMZMss6|Fqw_~+HZp^xcM;DBG0PJ!#WDPZfX@O|LRCVg z$UNC%Y%!XsO;yQih_}bvyE(f#<0;wM#5v*|S8%Go$evg-Irj$l1}pn2`9$AVD5YSE z=%&Apts*}0wL`T-kG+q*;_HHJE%{#3y(H|Ck_LPp@cD7-4kLSi+5g=Q-VL@U zFZCC^5)$=9{WRXtkI2K&93jUw_cb@|Nkl`GUQ?<0k@F*k_gD=+e;Hh4R~xI1-gS?pWllPt11>Kqlhu~YD}!cm2zVq#-r zH^ps=J3_UK{VH}lda74oS_54JU5oMW7S4Jj_-HGAD}681UZizR?aFr81-t%D>YwR< zrpqjTAao#gX@np&dknx){A?Zak}Qp{paV+M6{cYf3wM?$-&g6CP9LlgcMu{(Sj!yYzPH3jzxQ zl3gOcAd*{o7LOML?R#FhML8(H$M5+7re4ZX${{%86Z5H=8cq#w#S1HUFi%iC5-kMG zj3kr#D6aX7!4glBsUTj7va1qoM{uS*k$KotL`S@Iy>y8u!7;pJ>)^nAB5)!gegc1^ zdn}z)I_dX>O9{UuoJz=sw6ofHB4&;|9Nuiq|_I@ z_oLwvVJQ|8?YGgUR-l~aYYGd4ITSQgLL@?-$y!XsfebFz?4rp8Q-Sr@yG?ygzvmgp_fr!t?){1^Mg zDvl}+@%Wg4hjVNoCNK{D%fBiArij0YXpj5AGnth(D{X>rg3lN91qEZOqt;P-@_hd3 z_|wtM)y#FBYJ!)>WBfpmk~14Y-d#H)Q zBo;|LAAceKI@L6>Nn!!G@v<)h77YmIagAh^cdoatHkn#yI!sSj?eC$h6`N&aX&X|yE+B?Di1zw)j~TajjEfv|&W$Al|9YI)Zh8I29;O}gL% zB3RD}=Lx#VkIr1q+|Hi%p7z&x>c*3OA^CxSve&BPuj3z!|H78^A2aq9&3w&$;&Bic zjtgURp|r8JvCVVMa|z$OEqbP=^r9gMCY|w`_!?gr*%A1hK4&g`latAkc@}sYXpr78 zea7b*pZ`hxCvjfFyo9w0YZ6#EC7u0z_VdK_3F+?x?*sev{dylpvgIfm8ar&q>Ki8UtE%dUX1KV4iv5qV)t*XlZL{ zTk2fue9u0x3><=X5pBUvyL-mE#=7o;=ba%zVG-OS;hE+N@&|Z&+^FSk(Dx4&fwA|q9GTJM_=;WGoi&4d|fmOCZ^L5 zlOH7ik@#mK#`B50sC~)%l0TtzD~aYXXEX_=$D((4^zLZdu~?4d z*j>@PqBFt3nF0!5(^8L}AE+2; z%$z=*-bC_FbJ}v+g7%<2V1-_+TE5JQ}$fue%9ZCT7V8zj0-zm6_gn{__a0 zGsTi(X~>R$O>lLvEOJj9O;WlX!Iv3J(ew2^I~? zzS%-h+yVIEgQ#X`nPm^&InX&Edqfg%l}2`|`v$k- zr!D^H-`l^p3vPN8AH&P|A)Sjj8*##O!gC94Mtw(v4Byc{WQ^_6ck9En;o8UGM;r?4 z1!qv3*cFfG%zkYAW6Z;Ay_~JAP4-DWTs>R^+yihSo9o`~+T(iUc;sN~W=q8-U%b_2 z2C46>?;DXeB5gE0+u5II;obDh=e%g$Hm7e&cLrR6Ld>NY0FST$8cKjNGt9w z<{gW_qV(vU&=qxNmu7`zBeTX>$5@n=pB>An-e}Vo(a$#_lkC26-NdVKTRmGn)1A|uThLfY z&fxvf{gCjDkuh0fvlNahf`5aVCOf%k=+jU|lYMm!i}??A7>G2c<2j;~Hb zb_}E8Aa%!Q=mu%El2@IN+|BW%oYb+`wYPG#K>_of<6p3>K_uWxPQe-ToEZvh;WnYR zAvudWq4k;KorF?z8J>t+eY<&ICu-xgH^y^g8(w|`!5CgJ$6kuO7DEcYjCloZ@8I!GkNjn1)qC>X=Z1)KQ%BV z&?ww6oLBimIRmHRKF?2C_6s{a`#c3Aibd?_S^b)wephD?=NsF9wwm}3?Z%tEA6`!T z$e7)Rrlc1h#Q%l<3FQe#gW=`ZfB>}`?O37uE>)Ly9rQ)l84w9~uCdk9{T8WtS za;D~kHQFO}ExNIj-gDk*fq8+w+EFcuTpv42>3#h9I~@BQci=tcbmen>?_A8zt&*d@ zt)VSN{jAP5XPH&WZE20J$zb0#Jos(!NN`{9GC1&B?v(%}&|gVfSV6Yxmz?8c-DBNh z_N#j%_C<7$=ot~kzW0Iik@Jr2Z(DUTiaL?fF)lbE_}=@$>*MEp^ZCEePm`a4u7;EA zq|{GYm$otOf$xd$Z0J%*HSOkC)AOhJllOX&T$B*h_Oq?tp(WJhCeuB#lwX)`a(5HnJ`|ih=A%;>pL(Og4^WgY^c-DuVy# zKD5vUQp%?6#8<9fO6Qa}se0;A?*i|Rz=c3llJ+u_L34=Yxu=cB2*@UeAfip}K6;(=Kk$nt>MV|nH&nH%83lE)o( zb;Z}MKIcLa-L7{CRt?7Z!rmV_Kl7uDK9q7Or7?WTd+@0PH<|9Yt2D-BbV2mTs?KTTH z3;zZdw3%MuJbqtqt$ynR`$v0M=TK)IdYyr;F|LdBd2Jl+9K}f^9YdDt0CGobX{EK= zfii&uXj3kxok-gUkMFzGIjOzy`Yq+H;Jrz&9K}BGG?`HI(8(2cRCIK7_jW&ucpfpG zp1Wk`5}EJgJH8-tMr40aXU|67seWWM*j2yshyJVnmVELJfmHz)-1|1Zb}(v3`P$$E z^(62X&$tA1S{3v$Xuuc3uc=OYP-k+g|FYe-t+lPT{mQd5TQ=B^u2AMNX0)Zlj_D?}D1li)|sB-a4+TF2}U(Q75JXKjj4Kwd42wh?~v z12j_)0}lc#>8C%2QbH%mhI4$i)e?M~NoXQDGJxZ6229|{YCSn}hFldC-;D(RERZfOZhH`_0Rb$2} zhJGrTu9FL~*Bi|aJua9dI30~{Cj2rN(?6a;^E=8m!Zx2iBHsSN{v&>Nhi&_9Uy^w? zN*%7w;r`f1-d}cn!1R!!O@%wMCv-402h5ezRo4uw*#>UmCDJu>!6VDd9kkZH&fU$^ z6?DF(XQ;cs`y@QqmiBt~4(zEsrfD3)-(fab_!aM2@3FK4X=Cx>DVka^^)6n<;yZW; zf5Jz>C&5POXCIRP)Wp`>)|tEfmivG1X%X`x+C+B7-ML<56XvBg?#=Gj&d$y~+=I_Z z&?`wcJU?r| zS>L(d<579Y^E;T06%xQevQ?7tZ9RqO-)q}*d>wYHO_|R%a8{@)0nrlL)9vZC(`w-u z&^@hJdiV5_zQVqBXj4X!TRx3vc^ZEDm24$!!`Y+QT)Oi)e1TMWP%Y6sOPEJ(G$`dr z5A%>M>%_~cGpRRunGL3B-!tjW)uNc=%94vCxm)AO8LY=H?-?1pU)Xcn{{@@X?P>Ng z_HXTVz;?!yfAytORyjwmW+knt_7H!Mmv9$ndnbEe!fTB6MtckR3ivd?i68sY&>C{X z6O{lM!8f+a&hMRN$rPy?*#u9VNjMLl#~L*{(}akb5&7X}Nl)^Y%+ksDjaOtR(GtI^ z5CV{a-tOLA^z;|l`S0euuH&!j@5O9;55JpUMmOUgS!OBdV%BqdipPrRkOdRQ_A!G) zQk~vzIXT!I7RFxvAo;MDNc8JQ#_im2Mbb$Jkxi(X4&^HOcbmzuZAL!MX2%}KD6|Q? zoQIudoRyq*`n@`~+BQGh^KSTQZHAMR&Ms{;8pvzjpS?e(FX84a4Krycw!aBp)1T(w zi2ut*eYJiCZ;BW2fDYjethpTSEuQ_J3GAt-M=W7Zy6mY)|DD@e(z%s)DqS_y_U6}S zGA4=vo&muj?&D#6nSP-|uuX6{o>58KM>y>};W`a5GpQc+8_U;Z&{f0va~TY#PSy>0 zdk<3ktMBmlt8dgXB*VF(R#$5jsvo+Ihioc~?(?BDp`u{9S;^v*46X$79Y?^8KZVEG za`zhdE&O;|@b38O^X}k({1%U?PGlUk2J3RcUAc%S?=OL014VsBef8Lx7l-Sep87d; zciJ}i_a(g}{e$ttuNdk8$9Xo{+oyd3ueu$&8)~Yx&>G>JvXdFICZ2=Olz){jq>0TUf2|7H?>*Qb zrC52(&?QZS=d+)FV2{2_->vP`9^t_(zB!BWt!nT83Wt)rehGekipE-W86(#+ zbmJbE+hxU^wnIdF6h;5CJzo_eTHRf)U9Rem>iBo{waVNlJ?<(vs*TYO;RNg3Oh(7I z+$COiBjx?&{Q-z$`L+C-hx;%OJ?ma_+Va`*+dA=#N`}QS$8bkps=U2|{V4Ot z&-CfSMG{Z%(V@|yI)U1ODZVK_!2@5Xze@iSpQi43s#ObA3&<{MnZ8`#OLpre>qYv9 zO%8(c+}Au;JvSq6vSA2Ebfr?z>AZ3N=llkr+Le}-mS4%r6r$@nxcmYBdF21cKioge z|1%|79*Da`PsDp$|69LiUNaZN%NA_qIT=Bk7;qip z{*Ya0Q~ZS_(?hc9j^G(rFiYJaZt=J;6PzN4JEyxP_vTIZGE1o?FuR`OH?q;b!7lHycZc(n(}N|9(VlbhrgBqhix1ifIJq~`#Z6*Q zCmf_QR4H4j3{K%O^up7PX-36x#W28Ls2JR>-{J3R-mo_w&B6ve3WMhypl(pGGk>FXB6Pm-k)wU2EXArC2{(^QrmOPDUr=I#|VC z=Gg4`TbJ>d7OMu|Ao3E%!lCg8{lUMqzqIT6HT|@C#+;yzS0zjNIz37?bovFTHR$v9 zkX|RgC1pqp<;^ty)8Fc%%X-NiB1^awmtZ-09C_gMBspp@ zFDEeDIUIJ!GTX9@+=6aOH|3Kaug}ruXkVcb7S6lydk=aKdT+8*`pNf`FArMo5~1Ru zjp2>qhWJ7QL#o5c8dwH4RuaGMqV8g-9>=@0)00E_a0$QkFwf^Y^4TV$cbx%#dOv(W zES@tjLeF^Lu z$w{jit`dG^JT^vU$_!f6whM2(?C{GZOL|RcO(-pp7I*`m zHP%1gzl$15R@af>@nBnY8wHsq6tsNj;a*hZ^k_r=uNObfeDE?K@iUizyIp~-%P8`v zKjMw~(s)fWV>Uzbsy4z&3KQgW#kgR+VlJzumQ{C=PiwXLt)=1cX!g(c&W={FzzaA= z*azE7+KSsok^I_=-ZmG0MSpAmYA4ynC;G$w-OOGZ;V6bT3;*d)Uk={cOrad1(eR9O zk>z(^y{`_leQP_8MthoTlxv@Rqq~SFt0%$z7^p1OwZJ*vxsLgvtF@WcUV;n zg}qSUq8N@)pTTFGO`dP8o>Tu#yQpmlZ3*28{x3KMOnpE6=>Bj~#Urmh`LCH_0@$a=WVj4nHdR-rbb?cieb z{fnS2MEfiHYe4@n$rx&Z4U0~8NHW=h0pk^Y+XnQ%X*5>y31# z1NrG=NzA-P@37DK!T6ip^B$z{wuevj3u)@YMOly6%PaVvU$WboW?ckNd$p}1GvQGC zBzqz5k50@Gk=7_{Pqn8y$n0;nM+e?itF4V?-ckZ-IJ8^+zxfXN+3-H{9%W- zLyP1L+lH2^GG1J3xQkXfH#sBl-G1**M5~hBvm9((IN%rHIvxar=*7=!S4{IJKjRay zwoY)yIs`ieU$aeA=o_~M_XLlHPK7eTyIrGi*1y2tWjZYQM;q3AvsvO9yy#+nX6vtd# zu@f9u$u=nHDDLpuLbk5f?$+LFKed`!)g*!v?~&wC3Fgkb{@ZMmOy6DKZC`DFZGU6V zsQ;05cTKy7_o7aAMGIw~WwvFyZL%#EzGf+B5%x+)U~lho=5R(iBj5{fC)3TeXyha} zRd=K1t3eLe7xZ6)@oy*+E*owe?n<}vE_?#K?JT~p_t9!RRo*B^x%a;0-5SJfSk6+$ zvWiTFpOlTtFutSgeD;^ZzlK*ZYwiyH82SQ#{wO>tzYEO`&D5rAK*He*@E-rdyCa>P zcDvnef9!aQk5n^P8GN57xF@-DQ90oN%;EDGN7h3$8m#Zh6t|Oh{2O!39rp4A;b8pW z+v1x@c0+&#e+>C-2f#)_^0jMx%3jlJnyRT@Ae}ucoc=_f_1gG>d6?^ZvGeX|>tu6V zBdn5*+>o+vlVy~!{< zT#w@ww@&?mexZ`G+Sq7(A}^{tJ_k;E;+SC0;M%|@HXpkJqMPXz>W!w#uO*Q=pHs=I z2w(Yk40IzMlGG6%x&i6DtYv%FeC%}rMPVS34b(dZoHKNUw` z-H*F#8Z+7w^65{J`x`@6;u+2~`Jdb*GCwr_XFTKn$f;&kM}Qyy1|Q^^?H}85@?Z;b zcjQHDzZPt5B|FPpWWTjSk1Cp^GCbda2{|`X+a1SrHoRBaM0GmQ(dSoA~U!m2`tk%Mf+IZfCI&FXIe2$ zkQ@>wMP2UlJM@ITDdF<|PrI+34W9{n3{S@VHBKF?Hn%pnTJU_I=$PnOz&R?DEN9y5T?y|qKe0$@Nk9C zHkkdN{5>+W2)0lNjN$vx_aWIG9*38R0+PJifbjb<6v!H8($kCGiVB*a}QYa zH0v}rHc}s~bHNR+*xi8c7bbTK=qcS5uB&R(mSZo_> z8>_t2k&vVN+WT;eG_ddG*;;SiU@c-PVi~9mRHhlzjb-e&u7oa!>IWMHOQOeI>t6%X zyvi>e9nmp;B*XPX_(MjX$WV2tx(VODMfSyZ;hg4yleU`fVI1{`^AG1b$2y1IZUbv8 zXRV{wRy&(r%pbwODuV=<)yipGLYqNGXNMkAi@`?chv$b6Ge5jAUU2^FW&(HUT6AB+ z6O!*q_QDEz?bVfPitrewfJI+Kb6Af&Zm7OYU{y&}6<$uF zThgeRj+q%d>3ra>RoG!YXHQU;yl?SCXbjHS86<2oJNW9s8bR?v5e>WH*Zq3~`vQM+ zf5@94ysuK|%Vp;qZ~0^yY8z%-jAp(PcwKKQ4&7RJdk=eSTPvHDf3~UH)J94pC6aKi zY(`dNG&5##O7frfQo?I04+bl{SzQS$f?1R%!@WI~pNx%FWayq$PAZ$|2gI{1o1R@y zfY%h_pPp3dP?^veN;FG-!hORj`sWN^gVS*Q4_gmgC)g+0MNh$);+*B01yg3M>unqf%m0ymT`eswEm8C{E2uM+JnJ9XwWX@5>QQ(|HOV7CsvpxUu;-DSp~u0;d`mTi1{fTG z_i>F-jnE8jhW3U2g&qdm^s(!IZ+T}Cf8gAl$-)ah#5sBlY`Fqe1N`ba7_(%{%UQPH zJYZT3tFa-xK0KfM`58Ma;h^57ZbmEznuBdjB=tLW_}(AQZU7H*IN zj_dfah3Ie2b3Yfe6t%QdzT$rS#uyzQ9X=L17HYuzDLfhBHQb~I;A=Z4I478eJ(J9{ z$hi!e=_K4<_@y#$zi_-_{;p1XOoX#P*my@WaImYh4z>(NcY9Z9W3~~An_+~_@HgQe z;e1q6{B(r(wwRsGbk2vF>^9`CZ3t%bHzoRSO%1CnsK?|pe>6XukC{&|>zC={uj7be z2@BU;b~Bf$>ERjS4f=+R=V!CBS!oG30*7^LPkXP7cT>ErN3q+MY|d{SJsf%HndSWZ zfgWOmxxw7R=XjG{km#>VGjlEsEM!MLl&#v`z(M@1MGrOxZnXHzK4h;uoPCV=JUvEF zFpqujHQROD9;ysA1W(+_mdO_R?kAwb5pPB8os5;#RPdN1R3W~@tJHjaD22ZwSvBAC zd2OWx`^rQ0QTt>(qp#81 zGlP_6{7r+AZL~4A!PzQGrJx0i zfQu@c5W#|)n=Sax=PS?Df7SBV^45One!APcaf5{I)i^gSa1gqI|F^KUu*rN=6Q8BA z<{0w;98K{X+8Npr+8o>jRnHpy5O^18$nGXK6ccL1rv4l~R8QVz4?W3GWS<&@qes)r z{6R(AW9)ugz&3-~_*Xdv@x9xo?ot=BcU;JsbC&GEir|guaB3We)96DX*D-!Je>Ug9 zhiFQ!>j&_v_Vmu>$Bq_50_}MsNOwcFjt->wBt+dwKdOT9=Q(dTM zc>3SPcdIa1sc5fc*D1YAJ~$%V;ZFSJxC8%gG33=^r_EeyoLUpDLne6L z^SMX1;q^VhI>`Fm@(Oq7LYBJhXS;#FECy41XCyHde^2){z*x#VDqNXk=5ccoynwOl zD77OvYqT|z`D3~Dj`b=x-)?I~IBY%9h1Fr__}+YDj)RA<(pVnU4r^=q-T#Nr@8sZg z*e>gWdEtL#MmAB2r3}61YcT46(dL$*?rC?KnE$7h4VMhx2ww|tQcp8_SSjqh}RCZ`tM^IQ3z9A?<)$!=?fxM8ZMa-Cj&pE=qXZd3$M_rTlEj(Bw#xYZZniq-KwI~)2nw2S?n>{$jILyZ{b z?knnTwKw-_+FT1KClU?TC3^9*Ovx^0k)P=G#?#x)VD}_v+y%=8%O7aw*3joD2XexW^NJXF;i z=*fm*9K$!|8_O8W12nUSEr#d*AA3PK(OK}^S%=?^_<8KN?y-K$IhGxq@E#h>pXqb& z=;!HTi|Fq`aN_Z{s|q%L8lIB)T^GQo`H}g|9K+t=B{O3-G&hm-QsR-@lsRF$`J?%s z=e(3r#F$SmVe%2|E_zR3uBynFV? zFxBtlH2AH31HP(b$y$zJh@Ps9QT_#6Xa^#eu6@v+!)q-}9`Sv&6-jV}M}>xm+Gwq` zvEgyytNJay9Gd9m$~xty`aktHPt##nQh`2}b9V|u_P=pYK9U7rUou$w1!I(j&}MYS}c-)pWk zXT~mSCNN)|17|pa{`^1iwxOZ%sJP+Z@ji9e2JrJu3qPR`nn2cW39#KqmVYcgnGb%l zZ?VsZe`laARGcBwyT5bnv2TMT+m}1^xuuF)F@t;gR{u|*!JpAr>!etJ5=q0WjY84ybu2JM)sU=P#%UK!Opk> zdJ_x})rad5ylKDlvrji?nuV2Opt$>ClZ2E^c#6E|SzV|sPz)NQug#A9t~+sFv>J=_ zxy;Bl*q>Lx@op@3%_=PH{~1qt#vSk_YFipu29hg3*fz#i3QoP8?fdca=*SGa-nPXy zixaPqrJ!ZCvRp~#ck0Xx^hSH6o#eZD!Av|3yjkAUgy4U{KSCFX&Hb!>qxaO`@pO&l z_kYj)R+yVO2fLo*%!diQ_kY^%(K)rZEkG~6iY?n*w1MN5;mUN*jGytXEDFx{f_?c* z@Zlo(u5X7o)R;U#oea{W^rX$z_H?$F=}diW+TL*@E#>!5C!L~@Qi|`jEdGME`22># zDZS6$bAdJm=k~c^VehpQY-!Kq8)!3iV-$bqTlGCSR$J>Va$iQ;r`nxN@YV5(FzgYI zZ+J(0v&YG8&1aRnHV&`X_E$1YfC`S;jn}oK>pRC2p|pvi@efYFh|y>F0je?GDElxI-_{ zc|XAOcr`qSDtM*e$CF^GF^?W{xW1iTY(9KOQ^6u~GS@67XSO<@IYc{D177g(hvr6R zyz;!)OTfVQaFd__1vSZ|E@MCN+I-G$TFP9&pJ(TpJjHjihkD7`(c9=}U&_y4$` zI@sp%{D04hIG!_N0KMo)_U}7+BI7`Y|70g}hDzd0>6z%`FoBIbERbkCpC06}dPJ2O zco;a_VD_>sP}vAHM6MI-n9BRQm~*wgwY@cgz5Qr%)oEJHW8g%a!&`Xw?{kav<<@Ma zEunJ3?Ry=56&5be|BSzlo8~QZAE#(naGRTGcX$jlX8b)ot&$BO7=>Vw@-8MbSMH#e zP{;B1h%sY9SoiXN_E)5LcjDRb2i48m4Mp}zm=o8TL{=bmb6BgP$1A0lRs)>x$N9I% z(Svp7_m|v~|KTyTgnMLnXje!)n%+`=o{8#44P%|T&P?ZAtHG|jowc2{h^+`W#(uU9 z|DgUjiW5!^+e|pZk_Eq%cWkaQS6PJj@GoFY*^KPGQzzNftYxl0NnhqN<{RG`ImvoC z!Q50^sl)BDAC&czBKhgJ;HnH)MldJ7gJIFYTm$bmMNiR(P|Sbp zg;C3_X?9jRE8o$(3m@l_^^)}`^!9?Qj5rXA)lv(L;0~CG~YkW_rPxE8)4cl$rM#d{zf{XaM|T8xtZUwKdGU zaDpmE4FQi?&iQ&6KJhc|G{I&Mf?y1$`cs?eMOl~dNv<=$WKZyv8lnzS?@>0on;@AS z2hnC1p!)KDPcx^P^Ei`Mzy%ZEM`&MR*_$q;#K*T|xMR2y-D7(^UpJYX%nN-aSvFP>0>ZzeH^FJlf9&%yjmM|GGr_G)|SBnEL>O+f+m zRGYyLs~x-Gx<*~2GCf`{B^Sv$FO+d`a^z=DRa4X_lwfX!)PnSO+dz)LQ1;MkW-Otf(PhKImdTUc&TInkb$wwAI65!MSv{wF!0vMV?bZZ6;Z2z`X!pSx4^ zl7ch;7CKEgdOsvtKQZChuwVq=^7-CmMwUI=Y|AXmcCrsj|f_kB@UHbfW^tZC3 zx&a2a8!qo8WwO$RJ%H>uR=`n!PO0CdcYZ|4pDFlOM|L>TW;Ac+Epx0gPV5Dk7aL{F z$W?gHQlXREc7 zt+VY4bHNL+U(wP>P(`dotS0-=gJkkGq|cB$Nc@|YYb&(BLVt084xq#B9y(6-(fVlJ z;L8f9?jQ63!i5^Cj#LE?>e zrtb~!1G!&>bJ_85LA@Z#m;3rfI>kra!SZL6q9d+jtz#{S4(3mArd((MbJ(-n&*QHr zKB9T8d97Z0sYAR&--rh!NWB}Qi?Z;dH{tu&of?V4MDUCW;fdj|cs}I}XbooERB58f z&v=unMef@OsxOrnr11cJamg!~!#$Q{CYhtb$Z}I&`U4IIe%mJIDN24{tg)DpSE)t8 zyJdH9kNS)Ko_wxyF4q7vkX>{+p6*z7vhsV&c|KSh40BK6EJ@1P(LI3Y@;ljBvj1yj zHZ~9PJ7vQ2w57F`wFCEgW_uR++hgpLsY3R`cJX}pp7*n#rJtp+T3CH$zA{gMlO2W4 z_AdNBJb&=Wa^c440B}&eK6L4;y;L{#K$vb+}xCL4^8rOxkU~YYw>3=e?IpS}hV*02- z^rh!0tWG%95;OjDPo<~wn4Y3KwTyfIlm1cf1!Dj>B>aGir<&?bVGX{8CwLYN@RBJR zQC7U!uR78Ax@7wN+yR1$2%mv~7+*ckb6XC-brh7_*6At*ziPT)f zN)UYgW5&K)c(Rw6n(opEd+AkjDmj&+YEcy`ujK?KXJ0kA)v=U#gchX6v1>h}oXPmz z$Kj=g^_Y3pxCRP(QEZ`%mS#)3^BWmw>1R3}@d}hPILZN_k}j=f_66CfTRq*rfQo3s<>TxE5TO6*$_K!~rv_)`@zny#oV3 z8@{dI*5!F>%x-ihy}=LkjI*t?GkToqwrRGxboVu>gVuxAckJ=xo|e1TUmeogiuh+2R0=9Z@TZeqT~_uW|4_Ycy>U_e2?gjSr|XjVTM4R)Ue3(cj2fx{V@I4CHDe z&a;0j(P}g-s~z{ zyV!Z?N<@2~kCL8W{;o0L5MR>YBD*$UQqpHvf0XRP?AeN9Pk zAbUDH@2K!<N3` zuOT(mI+Xp#VNUvEu&{<_yg!B5r&MGXFThOY^E1kRbR?W(@m+mE)x+<nRK(LeR#&?yK2I> zBj3|4N@guNS31z2%9$eX)I3V|&OzR3xxmHyS)SV<+?U?eZ{(#4XJ#(=RaQMtmmcvx zC7$~7dZcg-sR?MGgb62&EeB}=;wr6ew8}R-lhrPker{}*i*~{-)yC{Qew>* zQ~b`v1F|f2TsyAKqjpoWA306Q8M*+hXTCY#oQMugb`8Qs=nZBs^Oo>in^I56c5Ta) zEd5$O`f!;E`(VmgY-dq7qq)W;dCtpPuZvLQx8}UpaGg?&0))d z0(3B`pd&e-O4_zDH@)P0^GX;4{WS7UX?M-?_!X|ySHMOo!5yuKg-6qo5?rIB(Gm5{ zXG7-6SS1$c<5^7bf3nMX!!7)PPGpDDks^wPZPhB+8DE+qBLph&3}>>BhVUQcv&#$? zA{qzbsk*p>f3$3|5PJjS)|OMQgEhM~hjk18zYpMWR@J5|1P;g!S9%0r*bn2pQur|Y zx{=Jv!tZ!OO$|>C%Z^EU=jrBjdi*Vl%y7~-HscvMLkVB%mi4xE4D}p*xggK~SM1Sc z2021jk^KHMd6UW*W$7kk!1GJd?Ti7Ld1`!Zc4d-$W_D!GIK}sxM%nn;1Y_OI-&LBD z`$OI%(XAxFSzM?u5El%+JGBL#LJly@8`Mq^lJ#KBtI1iFKI<#%S1=xutgX;!_5=Ga zP01Z6?~(Wq$Y;BkU67nTlfj2%4$(D3+eK|)2lkNuwsW|1I1}HMJj1WyxIY2+`JMSd z&cCAYxfX$fpQ83rLn!I5W`mNZfhEY^U-&62DB)2xHXE7U@L3Vvf_VBjp`YIaCL;Vh zIe$A+jllmMs*_oBE1QC>%4jcC8)R7x7MDVCfh(p&#GtD3-F3A(lg(|{|@K{w&^#z z^m^B*$CS*8lG!DE!nf=%#6znZxSI5Dxz*gfiETlL+k>{0QeUxCl(W@C{a|k739Xqi zI|+{qmE0Nsem}LJYT+Mwx8GAS^oa7|N#9tE8VHYInlg0omZ9f z)H2Y=n(Rj8uIou9(jzQmYu<_yFKgMKN`EeAvOLFKz;VP=`USPzvfPr}nj1Hh39th< zpaYpi$DGqT!!pAno_d$Kn=Y8=&GYDdq=y5D24^1$oLx<#im75=JlwN`?$%B&`M zYFmEWFZlOFH}@r3WZzNpnT%$KD?RX3{w>iZ33pNM{BoA^me=GQ_M-p%ne*xs8aC;z z#J5&7ZFj381kIR>?fSAePGG*8Hi8JJKjyfZ^lt? z>8J!p=%#j4XRz1V&lx4Xr)bMWzjcB-L>DeTg~jpB5r0t0F#DboeP2tki`mo~O7MVo z6cKI80lq8weRVi{zcX>|GIoQm9%a+?9z3LJMjtT-XDxeJ7o4q)u0|aW`?E(`z`gX8XMPAhZ4Ig=wTWK8 z065V-N^tfe>@+H~Cw)(iXU6=8a$7t&{&_6Yr>q2*DNX%`KdfL-@_cQl1Pd6?JT7PO z-#kOb*hwy+WL~TT<{;YRb#O?&=iQPXDG{tdd?_!XNsFS77ar7U&a^6$c^dvFe3X)& zT>6mJl$=xIQx}O38`MPQ70>t{w!HO0MFbo9liEkg=Wzj!f#A84E7O)|Ydk+$22Rf{ zwGD1`Kk6G)HVc{bUQylQ(!M9>X)3=1OCP#|Dav1z+EBZY^qp1 za{i{9Jqf;knWt3)*pTz}4JFTZNxV1iP<>#ROGcUSS#w%*S>-MfuA%U@CF4+LBsmv~ z8O4kidUJhEcr9)bIl|K0{Kte`nV#ngwTPc~f-y1UXOusG3h(__+#xa}erx@f(|J9N zlm)23zJx1w29`!vi{KEemDL$Pv&^r@*f(^eDs%4FpuVMkq4M(gOK+FX{m}|P%SDvn z0fLu~g^M8Hr!h@I3pbayk?5(B86J26{m?9^s0@ebk zb7ULR4KBhL*8TJ%a+%6m{S|!H0dN%O(&L=f&v6pv)rI>$n_3cH8vY;ET5kn{m#iOT zPc;@yMsSJ`)MTEi*LVl!0bwl8oouJhu_NmSLM$`j2xTN4qzWFsFXKCtj02e`M9=Yn zjcQr^8kTcIe&iXg1fJZR8mxZH?c5A%SeQ>?u_8Xn9Vj`Axv0^u#oBx{fo?n3jEWKLy%ax7v zBPZ}UmL5)e?o{+{f`z{fzX+GqOQBfYsn;@UWjv$n$fcLx|948}dFew$hue#i9l#BC zHv=fzFc?Q$n6f%$>_Ljc*J#EWx|De|l^VvmkjObFzQOX23)b3-YCt(5A8!JqmOJ$; z-XFPte=&YFFa*c7ptb%NzxP~9e3XBp=W+3g?1s}kjD2G(o&ov!@~L0I)lX8_)91;v zFMGMKsp9NuF2i`LL~e*^PXwEgo=dQ{4?J75sD?aSGLJO6oZZ0M%YeYF8Yd{vGMJp5~@Wk8&M0dJurPW58=EC>ti0?r|6H!g$YwH^P|6Gfiu zKjQwN8LASBp3i#lQza~%u;I7pC(O`Ob;ay)3RN6)`fQw~ukyUkLs|wpTioz0p?{}) zB?rwhX~7@jeQJbv?-tmBlmpQm)e-jyou7K#EW1%7(XZ3oOFc1Ga7m|7-+_0vKHr9X zr=ZnZo^Ki6iOTs1gCp%S?E}r|nRELtWcqFXv>CTW(cCkd`f$>z(YbX8JS5t)5ucW@ zTVoNSFrsSkpds5?+s<{e#c~qyf{V8H8}00^o?31WG;TQ9eu)3Q~}gE`2Y3((hISphA%fU z6YlxE3rwVgn3dmtu8tkwKFp&HfpO7nOrY^Bau=GVF#g7xDB1zFM}33pg45!46pe{X=pMssLA>}gJ*_s+(~ z-vH0;x4;HwqhR%sGzNV52f$@W!@C)?0rA?2(@*|ByYXJYt?IJ@e@8bwsYg&oJSX2H zA7(c29QwVM;_jgtvk2-k?)h#g<+FnOV;(kEbulqI(CwHobyvjqd>VeU#Alj48{qGc zfz7lFJdvi@Rb0cjhsREUd{Bzu?4*4VVT`+hv5`)nzSFhP9go2rM!kG%6zv%@u{$>4 ztnTrtJ3g<6pJ-O%@O)mtOxYXHfQT9Xdvqg<(ben*X0i^r3+-*_9K8h|=3tZ)c*kvE z;)LbUj%OMA8{(VNGtoXzJ9P3pfh6b2y))<>o`oWOtRnbsH}l-Ylh6=-{8sd|UvTqw z|9lx97^EHfgco=R{sDPG()Z`zPxo?l6?BJE|CN?E6$n!(?{45Y)ZflWZA8%w=0^Pi zjG1PJY}`{NQC)D(ufdE+ym#6KcEml>8fW!H+)n?Z=qx2Z*M$cH1RX|iv!ueexDto)(U zhvx5Fyg!tFIK926gJ-{YuQv)MG|dNP;D7god&*VLUnT#%LURjEEi}21F~2eYL~b&- z91b!~z*Ra2pTZJaacz0V@(gO~Uj6s#zgFoj(({V>#D4z1{^`(bRs)Zqlf8reAJ<*i z(SpYc4lXjN$lAhx7w((CZ~pJN@3{QPk$Z{L@i2Tj4{8Us^O@%}cct%4fAaq6`_3Ob zetaptkd6mV1Z>&X?7QI2WWqnRE#Hc-l~y~gaDgHPuBTm3>nd~;ezNzqAA`3ZWtCNf z2k$ubH&x8^WS00?;^Tym6F*GwxZCM5k@%@Ie8`EXC3oodB$gq%XpIUI3py6#mU}DUds5Uz@kzq zB~xZuXIUwq<+<=exaa!Ul_sPLaVE;VhTqNYjEX^NFLjWW0X5O25NyBv$ znWF|xuXV)h2qG^Im4-@Xw6dBKRD&jXj2r>eEES$Al;3`ry~lpybNB=NK0e}%I*Ztf z*zQ7mdm3}VQFt=^9-0t3@4e_PpcYV{C{GntQ?&}gvO#m)8h;PQcSiDu)S^gM;Rwz`X}9EeRw9#^Um|`ly}OU#6m`tNA9R~(oO`A1s6lN zUKm^Od4~B0Jwi7>u<7hZVT15d$Pf;42f4bA`VNQ5VR{A*>;Ujj=Z5Ep2^<-s3{h&z zHRTD)?~2pM`PRZSYZUx+C}&WFfAmxPQ@hM+>v>#?G(qJRX-Bye%!WDKGb}vj_m|EZ6 zz}{*}>g(n!As3gscshCNdcO5Mk)B9*y?4D^B3mNVW1LAo zlUxp&Is(hHFNIfv-ksw9P54#l=lq|u7Bb^^L9aPAXKK#w@Sd>UYxRzhMoXAS2qrWnUN#yjc>^@N?NyHb0k^+;>(ZsuOYu3^ddb{}wY(y81D z-44A`U#p)yUpyx>PGr=`teH7R8Y7u}24CA~+vp!)3|)sOUwK$_uyAJ1!gHnx@b#fNLvoz(nYH>XzGNkz(qH;n8X)(V|I^-SBSIrWW3t9%5g%YN zG6qR(w1eBhfqvk6C_ECZ7`{UD+ROKiFRAU+DkDJ=6uhXdoyCYr(I1iLyj# zgKUnG+DPq4;80*K^73dGKQsA{^2tT{BtCpMcs!=2{bY#LkDUe!LwINL~?sWI7O zvNwk}hjqSWUp1wgvQ^q5EtD6^&$Sm?nNZn~H=!l^=k1^Oyy2Xog1v%0&c@j_!dl_3 z@Q*Nqo6h05bzC)GH_lF)l|<)J)o_*YG4C;NRXke`nURO$Su z`3L+5{e$5-Rs+5rb&#dF7U$ArZVLCUyS{sP>hM(ArMMokk66l&kl_!y6nDqO$fU?D z?`-dAeExSbZ)d*9e3`jcS}R>ZHr5&V4&H({P*O_1lxgt$9Knuc%eulW0cD&|a^Nv(|>ax`3sU2M%UGtsuoRq)50ry^h@Zp4z5E`M5P~Upqc;05b&DfE- zBeRfPNPh2o?`sun6}Rd~WK z3NH#T^e*(Slvl`tBuKU8+VU&yrAB#0rYwYCctQXYs|YGyBwF;OY9tE28m9Oll7*0y6>6 zXhqAg~b);*At1?@eePelJDFS~U!Z0ZVjg}tt*=^0-f?L{?`BHi%mGPDF)rr=P zwg*>b3bI8!R*&^Kdz@|MYUOI|ZtR{d%n~Sn0JLGtNZlx1KX9Pw?-=17;dRSyxt>^0 z+)cfftX{RY)Z=p=MxIx+*0nc5PV<9j$| zvOzX@QaPzi_e}SE$oP-}GZoJR`GNez|HMByJ~(~}m^oz=7jzVKOy(!^f4FD5-=mfY zON1xP6Q+*2j(HMx0KaDcnvM98Fh*#vSvJc{#bx3J>4G#;8>O`lwF+&79+|XAf=Mt< za!hjM;lFT&T!mcgh4sQhb|L$n?K@j<{_(Df^Va#kC@fqWkAh@1NfP z!tcVpF(cFgzhbRxb6%83QO5#Y(rZ^+i&`Ddg83EjIWHBgyU#; zt-E$qJ|<5?omJ1OMFK?vEY>N#>e=kDbtkt^0)FBWsHL3z&A5IGyFf?--P8BFcmPhbF_0@=dN>r%3NoJ zGr}hunAwXMNz!PZ)94e`G6*V5P0bNPk**!$SKKfFIoxhmC=Gtj`) zz$7>XhmEsx$8p!cZJ>Z~JzPCpU%4x|dkejVG-sOgvH7u?IDdrUbqRL~-_~wx z<)!ixhLOw(o(Y~c@){XZEI)mpX`X6?e1++@>9!*18>YFYxxRBZb@vc@2nZHt{xbh% zj)FrdL)qFR+#_7bTgWTnr@B~OtR_{L{!#x?R|Qw0?+Ye~*9HlPNpi>zH1om{_Ypj$ z2i!j1$DencckDFoGLFtWIxi6m>IUisAc#>wzsdYNJJ?z zyQwBqlbI+?6xyY>OZ_=@K`m)Us|sJi`q=KQiLHsf_P_RD zQ7$X*#CPIs)D`)P+{xG3cQ$e+()3f)PX(a?|Jm|0a$&nVTL>+L`{wAY!mjB z^_2A@)P6<5XgQ3WkEVg|0*ll|Djqo*7M=1Kb&Lwjm_R*v01Wg_mb9 z&rZfnUc*$w)B}It1@0mz3LfE4)HU`hd)Ic?R>M%kKv;R%MA^g-@VZ9~hW1=~E-|RP z@?H6*_oeq@_+ps$5rmQTK>l+XM`;JkvD|)sKmQN+4>y;Y!!))uwycCEgSZYQVkKgb zb_V`d*Q!J0A@T|Nxcs~JyEZsDI0%7IoOJngr(8tVPLz$Z2*}CkZp`oFIS|RPWcw5vmwajy#vz`)43FU_WhTj}F$7!~tzoD1Cm;DjW;F;vPJ`V569xi;;w)zfJa05%JY>6cElM= zJWD*+mFr4b%oIlCq|C=&`>N@x=^^uw2?zmURqCqL38?MDc3}vzVt+LKXljK`5NWN~ z1=j^ntEW}7WR}97uxFvPP}-tx(awaFre6kQmtf{m&ZYJ~RI_SRx-F*XB} zNhSP+=|Z|tlr743v39YRPAQ#2&))<1G0_21n0laa2RLAzRy4+xEBqZ#{8=*2UMwGXfcb z6G%ndA?=V%C`4(Uc`HBOG0s6}S+}HaNgbgDcocjX+@oXX*Iw6N(eSmQ6n6N@ z@#Hw=qC(m(PxVao?8)4dxlCLx8Z<-h*+=sw^_s8DFU@P5Yn;7Yy<8hoH>8$85dm_F zV~V4tv89ptsIhn~z6qH+n&MR^h!eyuo~@n<((lqu?WSf8Tf-}|S7gu5H#=VvF1t!h zC8i(Wk1ydW;c6^27G67FJHJQbLL=nK(C+bR^l7xZzq-Gp(m^>Zo)OQYIxC%(`u_TU zKo`;N*kde)YW=qLmUSLGkFDsc=<4Y1=zc0Z6+SvYIyH-CS(Cgb`2;kuCE%xh$aly` zz34UZsz}yDmvKJtN0v(UShX1K3o&}7P;U$G&#R-y*(1w|w35wKuglRdQ5vwBlNEWrQ-q zLVh7X*E!cY%sR|^3y$!FAF44m);)kyyQ>qV36c}%Xc?ufGRrs1w=c3U5&+j?nr@nI zj(M*6TjpB^upvKK7%a5q+w%AEJ9dHp`DA1dI)FXCkETbjAe(T2IzVkHx0Lsz=4f-Y z*}>UC$~|3xo*e5P{c784+j@3A`IgG2YF%nV(HRo5)LK zL)M0@CZQ&wAGIH~719dascppr(gA6qwov;$^n2)^tbei&B^^p?Zfb5i={V_V#y8_f zyGFZWLQMF;eqiU?=GvyhlYw}L)-3=6+xjnj?U$8 zrEjI{$iS)>t`}CI{UZ;VaprO6jm!q-0)K)3pX-0F0m1+w-I?xeXl-aMg{%bH^WKc! z$emSx2OfiwQ!0gej?Crz{`>wZv8l0gP$x%HA}PtXWZP2qPnL{3WtZ%#E7TQ=JBvG6 zkYH{UUCk+qYZZjUIWaXq1c+k;}ON7dRI?7pn!%#F3Q4DV?pItpl6` zoHRevoSDgHvXoPP*?8GVc>lQUaoKba_w@Dj;doJQ$~Wc0YGL)d@4ByZq;sSkd>f{~ zQ+tYOimA7ww_^l1f~zIe68_+4@_n6sou#d%tv|zW^*wZdgD`JXe)tDuofnh}Nl(S6 zBByZ58s8e9i0qeEz<-0fpf1IdVmZg0W5)C2`TN3sVI#khN8F;5GX4IBA0zeBk!U1J z*_4yj$!dS#DA!ScX{&OdQ5Y~Jx`Nld9a-Ll$3X_i-r{fZEbgwC>`S(*y{nyk#Mc4Y z#xa$+6}$z!&!Ev=lOm>wy`)}JWv#N77D@~Kmi1c}`NK3dH8nwY@A$}n=q8u0h2hpkuhSc_O4e;xmS@_+JO&t1b{+NJN2Rap}RU?o$qY#Y<~vVTgrOt6zddA^{4tb$Q$HI zo=G0qAb1)`4J1WVw8`Nq;cvmWZx5e=d*-`l50lCGc|SkVHPO{q=qpg}7p@*F+A3gv z?-9-Jz z|Hm(47BTJM5q}?89BqC;g=%IEqa{zIH_g!RZHCY-Pp z+mg*MqzS`N^||`o1N#H}ZsTs_L@4l6!5Qxs?iPl;#rv1CT3G??!mOIqyS{&X!y>~X zl=(vZ;~AzIrtcizIcjhT$pJSM-mKj*ZejvmJD$gxNku{^>A&7{624A@t?@@>iKFOm$0jOV{MC$zJTj z?!#U4w*R(&mO5Ldc@U8t@;&XIb}@J%SQGxhlvG28&fq=HIW`j4-`|2smpOMulB6=&~s0Dbw`kE zQy+eawD*+I%d}!zF{k*G{9)H&*bnD%9YsoE1>09PJ$|h4YNLMpD}M#QPxi?=>?JOG zE_l9{zm{!2yYFS>W#kdIOKI>GyM;S78KKZc+(q5nQn#fJbpPz8zF`cWk$+R}r4UcB z5i-L{pr3jpy^$b{&wQBqD6^N;Tk7QP>@6E98%cw2ZByh@T(?}e+(G|IcqTpbTZL`H zHRpBbV_>#)f31L;6YJv065pRbouX4-iLb;C!0~&kKd2kgOUyymF7c||aADNhb@nz~ z8?L9Tr|Sjk7=M&6&y;7*m`>2$$Ho&{Ga?)?kcyES(!VFpGZED+#Q;O)L3flmj9N& zkXlIHC~cHhqb#aLJ?=m5XR$yaPscndc~UUGTKYTtJLz0k1x5Ik|COh_MbRvp({<^( zUSRuFj8=-4_Lue}mY1yhYe^SeIr{V8)OaaT7E5mia*VF zXS=g!Y-eo!4E+qm_ZyuUm6#Qr6*S@;T_dfLHjA6Z266+rwYRmm8*S6IztcF^IM)H;pg_OZL+c~!S$Oll#qKzNEPt#6@?4uJO_W*U zEO8(zAP3~v$QPrtjCd96Qr4$%HqK^8)_8_1!&N%9bn1TBe%EGp6Fbs6(t0iVYBK4O z2Sf%$#(RIqUSXv4DDyF@O55NYab>boXimG_E!#hOx0sgv4C-4)msSdUBu+KX2; zR5b{8!QPH*$F+2|bR9zdhR^VYS^>EyYXIK5HE^d)o!XK zXbIL%)K0ju!@Oy@Y52wdi@h(`m$SIc*nX9Bo#)PToP%>5MxJvg=yR!u3WNfo*}%9< zDW#P1a(VfHazL5xo9?R`sTxVkNy{NGKH7IW0aS$85IdKj%WvnlbA6e0d z^nAV@y&awJpYO*iLit--2lV5#M15a@K!Lytc(v=mJ^c$VJmamuTQi-RPU_jKxT?5l zN4SaE#9TxU)jD`r@`tisS})a=>&h*(7TU1ju%H9k!oNTRds%;3 zU&dC(hL+qpgP*}~K{Z3>?-AP(+d#uWLjh&5}g1y3QrL)*s zJn1>6P-_`DFe$g+^%bcJ27L_igOAUPuegBL8FFF&vpG(MQt75BSvmnTF zuWPUCu=}uE=hC^JI-fc>TQ*xr`^rI2GBz?c!eKACRo*Jo_nENivFcd$dEj~ALHt3S z&W1L~Oyljmy#iN(1NFw$7$tEMM>F+)<9;LYC5l74{yg|Rh!I6CBbAY!c%FEux25~+ zQSec)a8}`54CI9Iq_M4|t%LUJ3tS6a!(GE%m$*yZGwdPj8tWPlK%=aONoS!@q0n*d zxJG9v?Gzd-jg{8E*169paW{!qMi|I+$8<+mt_$~sf5JcD9&m%0LCk0KXES9>5a)Sv zbaJ$Xzq$Xea#vX_EtVdj2pgLa_&q=v5AkyIBjea-^;!uNm>^8ZoyDi{Q~3T&f97ZN z&t~F2F9aX23wq%$zAnBRN)2U*G(;*69J#sHT$>b}6f6%PM&d5h&aEom_e^Joa|l0_ zpNQhI%cNZL8iwkI7}y<46H60sgKvZDwe{Lid8oV_J>LjrgtEl9#J480HbUON>)|2b zHG9naMtCDsWvj9StplyaQs5Q^9?F>LFHy?O49Q`6 zyf|LmB5oB&Dx;J?{eSv@Lyj(SJO}81*6+3Lv-RQnaBp01T^HOJ+#WP`bDVRWlw(g` zfU)d&wjpc`|DgS#?Gg8g6EY`enmi^?bGfmjIOvNZ7zVf{C43PdO z4blc_zlDAaeMGWnIylvfk>^Og`&s@RpMw4K5!VsdJ?5*xrV})ZdH<+Wj;uZIb8;<=YEcz^z-Fp|@ zu?^An(Fy(ux&0_!BKPb=0G@_pIxrcz;^ZgVPv1{3*mxT~qaD!u5$=a51^$uak>e`z zqUHc2AwS%k;hSMP>%7>}x0TvTRpqMkG;NypJoqfQF0n2_9Q#g&PKNci^|qR9P4;j8 zZ+;F6QZQ!=TML_C@7M3ivnNkmcoq^~HD8;jO_C?c@1*~vo61eHVDYC#Q=>n9`stH7 z*_>Pt8T6%`rJRL?f&$&A+t8~OWDBytSjSlD>?6+Y;^^Y&1>XhV9(j-a-t*3L7*#?p zA&0$T@7ld!CB@#}DV_hj8C?3$ob@9jGwo<=M_-_@i3OCd>)Mazq+%RGgW->Dwi`il( zo-|>fqe7!YPR*&E6iX(at z{lvWv=X(@@=>N?BGZX)scGX01eXYILE=yOWGGZCAhEzkkr`}U%B0=&5{Imbc`&Zs3 z#wN!1_H_GE?kHE;RoUf4_27QsXjWZmSZR0${d^R7*ptAMKwY)2`j7aJ=)n)+k@VV> z1HKXtfNP+Srd=8BZ;AoStnIGtKIA&+qP<~jduw|iLm$IhaL}G2Wl;^Nfeq>gb*eN~ z`XGJ~pU6+-H0;>vt{(x72CngZ_!!OS9OrWJQH57{+6Q!Fx-lQkAI&bjaYvzPSQ=d# zo#vnBuc%g33&;iJ8K_=bPpxaPYcK=(m2JSCKCM5k?~ZKVq3jU$N8v}DFmHsX;6P1x zOv~j@k;igh_|Vi1*A4&V{mJ{A{Hv^rC`pyNYu&W_Nb)-d|99d|ZZvE(z?RRpk=?)| z%0>wCLB0>$hh1;mkh@n%&y${qGLdcsZvGE6Yt#nDbq#y>;hj`#<8!&dU zZqf-B!GgeMhI(YeBAW}%gyYWRPNUUm{SW!XuvPfnD%vW#+PB)bL*5}nf+o^gI!B%( zkMND~6^j;&l8!4qIX$_mwW`&|+E~KEjBcZQ12{ORoTr>Lvy1{CfpplxNH8+ZH_b;g z(*^N@NISVoY9)1KU}T_synF6mA)=4yX(w2RtHZT*wR7D@(RUFR?94BwUrgjBvk+N% zLHrz3kEwISIpT-R51CO<)U#dLt}F^H444w8L~G=73^fil&U4Ij(ER<({mfl7wP@;b z;kfXMdClZE=Qk6#m&B!mLW4q$v_={|n@2oHJhW?Cqpnd$2S*1lA=Bj;aw+JwKqGQI z<{oo|NzJ8ir5yY-|6Ef+5r?-A$`sG?R;39oo0 zJ{AG#%Y@;ti>!-y!8!gzH&Zv;Jlp&g^A+=yd&U(K3JL#Vf7zI6%p5i!HvbD1a$o2g z8b=#Pzx6lpBOXI_%1(J5>MuMS2Z9HJl&M6xduc;y1Ld$2pM-FRbHaIH9ygD3;OCC< zj&XR>h@@M{X{I?jqD8dIa%K6x_(05pAb5ecKr0+790Kg0MLsT|R~nkzo7d}p>xE)H49P{=@9^O1>>i6_A)!L!;~?X-MaE{$SUR&D8T>F*Hj5SB6X}VRv5*M zVwRegn#lLzfAE)i6?_$>b2CHC5a)a5d+5x%tX@`61y2R@!v|7;y5pMhnz23h;@Mm_ z*VNV2r3spl2jc!mwnw%ceU82!GV^{#PUx(_tlZ~{1($9HxN9``8hu9JK&0|PqL-t> zh3^N;50)n*QDa5BQ7AqF(?eFdHs&rLWiL1bX8!Qs9 zVWw}U5Ayy9eTFsh88x#sw}@D7P6WoYQP?QdO=)$#%Dfc7T%Cb$p|!DMzr=l65l3)=zq0NYLIF3d(%;i_`$?Cb2!jLnT7 zp?YfypT)+Z#-YvHW(^j!@;&jMNc||?6U5_L123`a$bgy+?$%}dWqUQQ8uyd%lVC$N zWt+0ya85thKi5x&UvkkzvBZiXN?V~FmXBbfZy>i)TdS-6tNr_so%8(D^G~gkTO|{p z6t3Z7v=jfeV9$=P3Aw~Q$f1)L6Jegq+LG3=ji#ohB~YqR$gJhP5I;# zphW1V@1`GN8(~B21>42d#Z?|$I=U}PI7>JK=74#uZme!PG!}_)R``JTfVZ>US^l5+ zKauz@G(TSnTnSt!&t7okyBN9{O4&=W1+hE#Y8p(`g`U(96&8@kwp#pq>zu>sw zxM;j+JVpMOiMa_OCfIqd{b_nkK#Fe+iE%CyE!U5V@J`9NDJqNi5xoQ4d25!nF>m}=ml#wYz!R`Jl`d9R>@2>Bbd`otTE|Lg|f5?Bx-F@AC z;Yc__y1Eg`Ba+ux)>zs)+d9#<^3)^KIYWD7!sF@t&=KruKFUWCndiTy+*UqFA0)b4 zS86M@E5WP5vAA<3sD_#unibhxRZqoHFnx0yR3oDiCzdaym%wzf95 z1IQz)5A7MvqIH8Pt*-Wy{1fcXb0nAQQpfqn`8OaN@AaqGpL)Wpv$>_2?xXjk_ZRsWxwqI`e2)q$0i{l$Zs2QVoRgUFgFamk z2rzdRC;kBSSPg^*xKm#-vyjA2+!PWNOaZpu#@oir%e>qc`>HZhX=#o+N3{p-!9s~b z2~bV){DmyB7WNkQhT#4ZZfFAOkM5k4_LKJf;F^s9YkqNJQ7%Vfle#JQPNjRE=GEQU z8$Sv?3Q^xQ9nQ;b&27yJqcH2ygT8aW!?t&{yBFV!kJuyjM}|iR(gQDzFN@a+)Co*i zrYk9;UMz#%7bJdS2d#s)GqfYrD!Wzo|KKogH`~o)m@&*-^bJp4&%p94<)S^>Fxzn3 zPsp^Uy~5Sl)tJxk&z+yWqF3A|ZWpmmk$3ra`M!=;jFNWpG`PYBtHG)|Rp$k8Tm-k^ zz6rh{=m$=h)n&bcTvM8J*eDwv?i-$a=g>1+2}Qe)r@p7Y+29gWh9shiQ;JxNSWh}n zI;#scgqp6JuC3U?>}U2dH_SK8f9Y21LeRk>nF97+LvIS z(3QlM1nDm6eW&^IFngG-gnQ>})Gl^6OMTZ^?DljJxDHATN=yw-&E=-huJMX^Mf_R* zSsv;g>g^lu8{U|`F`M?Y2Tg}eFB~r%CHNA&+vRpm6{ZR!*b!_!TRqz}{WN{{m+UXo z;?v`R9Rq&VuNIMu$hV|hQcwvhKjQ9K5M2-@?kM5gr7fi`yO}-ASNvCeE1{+EmV3)N z876mcQVU*&e?yl_yWvv4Qoe`sL-_&vkA6~L={Iol&j-#2HX|*HG+?EWsmOo}Ml25AJh47gJ>H(E{cbbWRK(?XLXfhtO zAG9yw7Uy#5sCO8~4ds5fkGEelTr<$zSSe8{VGUY?qtsC^@TJ(O*pZ605y zFO%@B5!!G~2`M4+x_F)Mb-pF$C1yY4XIcxbg|hB)?(VMct{^bUp0=L0YWiyW7H}J% z6q^*==il#NtE^R?h);mD?h%VBMHSGeeM_QCq7C6QSe|l-tb?pyv0t$dg@=OQ<#+uo z{4Dfw_Hnkew6na?z0tjgHoi`zPUN!pinoGX0eDK((?{$hc2~M9i~URd!(+o^q$Q;g zX}!&08_SMm>Aa#H^lE-J-W8w5273yw-h zrJxuT&&X%wx8DD}nc>VZ?Ps5XZ{aq(&Bd5v4DH2P7we)OQ4zKX``Y^2${}%(^gET~ zRpKY02YIKyQ)|lK$gm90AOeDOohD);ric_#KkR^5#v-d(d#mFxo!G zzKC1I4FlSD7Bz|=#ouz=a(rj{&O{ot)9_Us82UN%tM;olUz#t`+0ab-P710)^=R;D zP)R6>+sI!WVH|EmT!!N^cbTi|s_LS1l=u=&?M-s|kfb?^#v^elAO;4hgH-AlI*J{| zYH~H1bQLedFTl~}> zuk61dUyxUMR-v#S# z@Na0=2`~ZX0gwuhL%Y5f_-{>b4eurCl61mz!qZXgAWl=JDjvVb?~nOo ze^P(WcFtCqE1cUSzjM9I-Oo;BCNee5HOyDwLmz>U&ff6eTn_$m@aT$wH=icwm*;77 zHDkyag5`XIJVm2Ooa<=sXs7$VsnAq#3arqV?VF2fdi7pC%?fHIcG zqGN` zwXM2e+6TtkLW%Z7v;4FC&!f+yq!-_gjE4!936{6aTc!?Qhc62ppSUU89NQfCO!rJD zkVp3w{I)=)i15I-lawT-snk@Woj^~m7xuFkgZq$`(<^VUya_{=VV51n?E+pj%(V&i zE&nY)%Q4FVd9SfYQjeq&$hj>VDjNDm`$p>~b(8Q2cuHVqdZs>8HwQNdiT_O8(Fw+h z#=?%m4vo{e{;vM6Z%`w-kz8+kZ~JoOf<1=!7V#9rfpB1k`iI&S&pGjB2y398%rOdmcmZFvp&JNC*!c2j9=#Sl<2&OUC6B`1 zf1;-#B=z&6U_+(%$bZ z{4!_{_)Ykm@MjpVoR&^WZ=hM&0yJ5{XZTZ~Pk^}KZQ18?`TkX9 zaYQQmzV?+@$}5D^{UHA!@6vW^PJmW9iJSy^TGcYvGTyV_v+u#qxw)%3KD~~v8{7@f zYxmlTOSc+#$!VnY%>_5*k@{Gzi9I2mqf4cw(gbay);H8QMA^jSkdaHX`!L5ahYmYg zn(MQLY@rZWh@)M3EkiBC1n8=dAeZlK;B26e+DEM`)sYCtza(Fh8)3(^BeFA6AGvK6 zlPe~#w5+sjaBgtYyj$E|+?^xj2+i1L>=5e^YYKWf>64T@^XB&z@IfLW_W{eLx93NX zRkq57e1&|lTa6|@B|gy(;&1EU)|Kok_Gi~X*KYT2cWqZ~R}=7?Ygubs3I9Ehyb44j zMMwKa`!32Cqb_G zq>f4RkW9bBzTFP0FpCk39|!K!V&`J#0_y@R8D;K(PktBR&cxk77^&7$ZY6)l8(2;) zt5W{~g=ds7@D9lxlB-&(TCOqIm;wC%_+7#-f$r4Tm`&PP+FAy}uU~-|%>n%PfB66K zyHr8V!0lXCE-OD&AF9g&%LD(#{)>@NxGXYcms*xu7BCB#dC)4*xwnj6&K}3E9_s~D zd-#*lGx|U5#i>tERa4dV@_KoNvRugo&!KX-a`+W8;)=mpjGoc&?cdv}-~PaV;CG{l zm(|49#0I!tPnz|P$jm(iozEm~vesH|El-jrNrYk9iBA%K5q<)%a>^QNXKH7v4^3lN zU{6)hyDtS#Vv%!^bGmi96%nr~2a%yOCO#%kb5=vGfwolsQ~nM$Tpg}H@IUmUb<2IO z8YVYP&NgS6Y3D+CQGMv+s282j%x8FT;3>n4X2&_0Kg#&a_-PME^E}OjgOx!_Q-4#x z7!{+dk(bd8xjMv&roU;4uvj?mI__cwMxX$=pgCyXqT8awSeipSjU~RtJ~}%$Nt>jO zawpt5J+;Z$69W25kQeoQWJrCmez2}|u5#AmYx94g`mz03+OygKOcP)HLDqw;!r{W< zv)(h_hDt-lB%5T~PaO6h_NImNho2%dvK+E>ni`uLf3W{xKhK_LLwtz8k7^B0<96G2 z8)3HH;Du5ax$%2LdqbB~H8Ex!$?n+G;JeI9{ibw~?3T2`#3@1|mO( z1$bH0T+>_{eEx21H+Bs73->+yJqziB!-^fu9o=nRHhhPEjP;38Ke|cVq^(p|C=Y>) zHT5?29u6K3(s^C;OU*AtW_xdbZzgW^*X-Bmtd6k|r#ngK16hM%Gd$DmIkub#eh~Z; zApX@Jb&q-;ToUSu?nLfHo@YPL9-1^XiDsFSwvsm52i#_Fv$U&7cf5Cuvy8W_2S)_b z^e-)u@kxA(J>ETDAI|pys3PD=D;Vs$M7u^wgS7#!5qgu})B$~w46u0!H-sa+j`~{C zRsc>(>GS2sFZYqkX9-zC*Sy!gBh-;<8`MwUKHglt0y5Nx0lNXrn_R(M!Hfu1M`85q zX+=@{592+`AySAV}Jz(eRa~ zyudA%Ef#vd=K^DB$G78eu-93)!{yj-I$#oXf{us<;O^3O+uD`Co2KXAaP|d&tC>bsl?v?17=n6ld zAxII|OkNXl+g~v+8Pac7U@9=8Rk9W|7Bseox33M!MulUAW2wQk;AZb;Z!xVXexqaB zcm8Jn72y@({8?#PP2lFyC*{YKi{^{w^Y#n&1QTbgVY<<=vQf zIdbT&QET)dbhn?N&93LI>;1*|i*F@#OzmRrV~|PZkdN?kB*^x$_OTvu9Ceg(mUa@S zm;^f1*R})>TjoodFNMI-J|8+4+UncpYpb=>h-Y!ed)oVJaBT2u>{@IHJW(bXCm2aT zL+8}A{L}NdD$u$>+q5=m3;6l`dE0s0sFcwu?{wWsT*G<#pwCv*6Q4 zeH-P+R*YAUA4aXnTAoFCCVA88bq3v@l-((H47CjdP!_#aUtd>WR|#2g?cv>BHCi<~ zCNL(jPur)BSH>w7m9G_8OR9t+kB*Lx4*E3kQ%QK1zlJ9A0sD~cmf9`#d4XpI9u|C1 zuwsFV1&nT!o4CcVjjxPJm_ZB13&mBR<|8ia{EzcK{*?Yx`oHP-(+_7H$slgl*uXCV zN5YXHudAYlVusS_uZK7XI}buv|B8E^tBu-W-(fFiE^0QVm{Z6YZ6>mhQgN22#@sQ& zAJ@j##qK5UC2kOU0!dy4q zFg<{de+GOab_I6@iThp5Q_M5@+G5+s>Gs=JqM=Q^>1qAl~EJ$b0S^?+fYU=U8$=mnfZG zDx2~a$$!SIGwEuiR8MKFZ>*1?DQko*<@WI8BJECkB0cd7ctz_1>jEBcrk8NJuHLTR z=iuC?Me;|U;oc&zkSXB4mavz!Qy+WNeZze!?NnOVv~Fp{p}Oh3=_GE!pSnMFW03W= zJ-j_EYm!ED^Yx7D8SaeK4D!181AA!F6z+=divA0)^E0|Lx;v&jrZK=A8af*~3xJE@ za5|jb?cMGD&Hc=WQ;wv(%KJL+uunrj$;cDihglO6f#~kop4chu>B)Po3_QQ)!E>Z* zO1G2(hJuC#@LU)N4QNCc)is6(D7jx1h!==o3SA0y^>_2P@V4-VwXpW9?^oaJ;Oiji zG)jWM4hny=2b%hP&V0_R!Zl$}>fY3@X`R!yxVO0J*}7x<$M(B^yqe&*$K`mfSglxAG%IS0+u}8{YG#qIT%kM#^Z1hjNo+Ek zo7rqgF{aGd&DFhw&s}GD8Fob?$)M<P>F&%nXAq40A4WuaxEd$GH*VaUe#7aZ@N zrkd>|-=j`3rx=UfVkh3iKPh)o$gis- zGBO%wH^}}Gul+FoFg`OeGePGRwTgTI$>XX?PLmvcTpuqQE*f?R z+<`v6K48za@*y@QFfKeU{BvSpf}Xoi$)A!3S_WFI&|Y*Fx(L_Y*WDP&Q}es>y9}(J ztzxZWEtpa;WeEJuo@+a86Pt~W@cojKzB@MSm8+FNCMoif8pVZ zC{Cjho*-kHv5b|qvX`Bgoi`lU9fZM_FqSaVzR(2EB=QRV85sPV*qhky*sj=~_}=(V zR7K&8>x}Dn;dh}DTZt`fD{MQWKdPUC zJ!pwUiA1|#yWkdei@IK1FK)=(00)TMnLNmj#JznGd=PAm4BIH2{^%UtYu;-n+$fIw zexh@Nvo-ci`@oGO?BWjcH|Ig8NgjiA7m{wI3hE?^@~Aps&vqF3Lm%MbM|&N@_B==~ z{1vHa`aJqPr0*f$4p0yx?oeu|RiIVing5wT7zhTohPQ@q$M3}H`LO7$y5gqdrfc@= z*wc6C`nmeKX1f1yFT|ueo12aA;0}9NV^<@29_+yTx<0fav{l=x5zq4l+$~n4rixR= z@4?&M3ch=0EHg&FbB}b7bZt#-O_OYsYzD>v2Z?7)$Pse?DFY7Mp$g6xmvL(C;Ut%ayw#&pzgP|3V z6J~8iZ@3JuSg(SkrE)!Ox zYBVb=JBz{>rX){IPMG4R|Lp(ScYu44&cEjgXFUPmqNYq!<{Qg57Ra5F-SEM!8Ltt? zsxt6Ey{~qWI!l*5mp!$`+9Gj6u4Be17cLj>gtW+A$h2CXf-}; zXM$&u=a%?d%mZG~9sf)J?&z_o{gd#i2OPn_7;+4gt>dgy9HSkNn5)brW-znKzRx?|(vjxg&5O;K4(FUV12v z5a)_+shYG-Ij5WlzHENosJRl>xuybo6NSZTMN(6M7#i6iyAV2hVy)d{Dd_Qe)C^#XM_?8De$>{#$NuJTv-Z^6$Cfz(?V9Kxb0sVURHjQjE=emi~`{q|PvZ!NzpfSb}^ z+yL(UdHDwROsl+WfwPQHEJ!RvGG0$`E;^d}ni$}bogLjAc@Qd7%2B|P1HSny(@j%3 z0MWreYMf^Nbo8=i8PNj(9~|h z{b5EbL?I;Pej95XdyV~8+fegRIsz}7%RcnSka%+P|}pvh=jvG8`~G&>hjm zk*l`#)AUazvy-!Tf#*~&Q3{E^=Mu%>Z4^PKo&rJFKFo#^oGAw&A0P?-xfk=i&2t5s z($+aY=Nw2}OSA=6G$*n$ax{D{Y>6|wi}jX1Yp zr@9utT2Gv3odfOd?MtE0Jqey!m(LwOXUD$8Y6P1EXW<#`B9D<}Fr|B8x3CEs_FsHU zeG|gV!gaD*WtE4%`5JO~7n-J-O4#hS7LJOJOvep}(IMLv>pkmR({)n|=v7xDqqahx za(ViG8uV!_GGwP_t;m{+{Pgz79Xkv!)Nbexz3^53#ZZ<@K3(trVu$h>-{+0E2h%ZsSuHX1Okkvkk%5<-H=2(en+35VpvWOXcm(#J!vH4j`v)W;%Iti}R5BeVZo8~L#Irgdc%D{GpV~=WO z^RoGvm}9W@C+lLvY{NtJ&qt8&d_HdsTSpu_lLUM#{95O!#ka{Icas zHf73ZSIKUc)dtUKbBu;LSta3$KL>d-50T|}{>zmwZg4biA|vS^_~JK)|4gs!AG4{a z-WuB)8xb7=6w4Cb9o-r28~;B^X8|r%y|wYZ_w>w}a}KG5bV-M#fFO-@NlTaHr9_bi z>5}g57DPIvK{^Gb5jov6vtz#BIv?-jeeU(bVfO5Qto5#Uy{mhmIBWbNPQ^uVcRu9W z($KUw{KIm8V zYx<1fFTnw<(QEL<>8Tm1rP4~Ji7v?>^as}&>x^{#fR8zjIYxU&dk;q*j+DG!fywNj zy?^#Rc;yx6WET!l{3ygzQPefhsjs5cJ(H#lZ+%<1^k@f}mXO}WNh zvIOts^7eA}LY_h%4?3#lQ7fYMan3XYYa`c2zW2TNNuTfo`vZGp{D9?NlNp%6au{Bx9r2Dhzzm&3`fvI!rT~A;_?U4z{dD>e zAYM!{)b3B~r}aMJzG0blk?cxx*(2-`{i6Ct9mErBRo2y6X~D~KIqGs$k%%G@9bMnL zuAs+A(Bt*y>CMyoagK_oOxKt$F;bTkJ>z`*!$_RCZ0Z`Wu3$xyprWgmQz_zWvu{mMdyxQ67g$<^umf)^+bFouhZjriaO}UxQlVM zVrs>7`PlhmS@_5e_&kkF`d^at4IE=`l$-^9oPC@`LEadDjQhJ28 zzVvdga<22X^S0%wf)7=&_GpYZ$1P4LuD#j9-tCUaP^;-$y$@x5#dhzx$5*2Dt~h|F%D|_s5sL zH$9IzjO@m`(7I4W$j2$uI8=goZHO^Ab0(qmuF1Tf+_+dDk?EH_b4_NYNL^NP_jvl@$mTgyCKi zlFz@I$r3U*Q@pXCF-PejF4vME-!twor?bBv2&M-w1ug`#2eQH<<_^eEzlZpRO*f~T z;>-L8{vPYx>)c;Pd>K(Hs#MgcS#r}&eKt#wpSUxJ`H}86S<0I-;rR^Z@oq?wVXC$l8S$7rZ3cFRzq}$g44}Vs(=&6Q znP#QKg~KUU43kdsThEzIR$s5JFAXjV<_Y8qe3p?f60^NW)usS3!c+&=w+A* zR-Ac>U0r=$eSJfGPaBfAlJ9&m_XIP;4C#(#6CZ;7v600@EZCvYHQRA z_~3!`cuw&Q^Hg<~cD}|t^&T8ybNs)@GxK{`Xgc$yt26n1PN*v9Y6YX7QIwg7FYs}% z!aNKyD4E36$2rtBdgz_?%AskpM>doB{;uv+C;6jtF^1WueI+>`e+}rMsv}Rl$U!VyI=D+ z^VVREs;=YY(koe`DHMiG=AYgmFZ_-P#j9ASt(eo>&}eJa#B0W2`qH;}6o0{_;DyWp zpJ+@lO5xLRBX~Zzg_>zf#_NpKjF%bL0!ITgLt{gQXdW2O8S{m`f<2GBfcui~w(kLP ze^Rs)hswAt9ncZ<=iVrc=I@N_u4^&*k_(^fB^fI-_9Y)oz7T&t{&RdibH!wf*@36X z<+!tP_0g5zO1qF|Fz34)eR4lI`Z?ZtZhKnzEBnWAKh%#d8GRbA+#ebA5BK%-)o@pE zUt~VTX(AHTm15wjvbi3&$f zj2;lZIeJd?z^HanPv~dM?TPS=why(-3<#CKJx5x}w8X@yq=dMf@f|on>!U|L8J85d zGVw;@^3+SIor6<@4L9|ko&E%ed&+nCHugtgjy&2pqTI`Dkb`@D*N*Z;`vedrHf zqyHX7yI z>46zkH|_=A2R{UFQ5*b`xtFKmP`{(D;o%+ij_4C19ul{sZ$!7x(lW~wJg?i}r}NtT z$UDs0%lQqHC*Bed@4zS7gD7nX+V(PgHW zcI^Tetns}vA|ehxOJyq7w)2T zs2EDKwV^S@D+8Ih)c_v!Z{DBVvdll}$jcKi5qhQux{@_YtxBnna zHB6YUGPB#yRK(fNh0YjHoaafzqX;cZkIavUsT!RYwIuSF$hW@7zTEC8_atfp!^uB8 z2EPq%OWl$BXX3>~8(OSwvAbfg;uAU`eqel;q%KK4dB1sCVTGA0=0T@E$lc!^*W>Q}cUF2q|#^0KUEO2G$tbRq`#DuV-%#|o; zD{E`(?CBisnc}GsQ9GhG`=fPK=cu}HCn*>q4)=}l{o{J(8fP18Tf@HE9o!a-PV=T! zz!SMoeE0bO(AvJnx4aepE7_7Flj2hUOPxs#Y%=R(5Oa}U@MmYzt5Sd($JD4PoG{y> z)<#TRv3mJutKaGn< z9(JF2M(k!jZVGon7Cl=3B2+1~7;pNX!S90CgV%yGfBZgki)4=SbUb?Fxun~B+I#v% z^ozI^c{B3s=z5$mbE0QP&5WvnuJ4TJjHjKWtwUxnMf3Cg>5=INlMW?yj_(rRj$W^8 zG1p@*$6kr8l29cC+CmOCEg|8o&H_^xlwbX3Pu--9?yF`<3H{H z+*i`)b$i{v+mF~~PTVGIlhuO>qW6fi>_GIoP0*WobT3aG&#dh8oHHHF1weY+rI!t= z&B%qHS5qQ`zhJBG2JZzYh9-uj&%t3iESb^x8pgPktCXu5I-TT*q==h5<0kyd8-gAF zop5|ly>5)ie#Bo)>JwW6TLNWL%cRaqoRx^hcKo~8cd=FCs>G$mr^N@8LP?~U=?6jw zLz~Id#iRL%`-nSVM81d-ks~7K!TX9Ps6u4zWYBrbgq{vbyg%2d8Lz)n7Phgh^L_!EBg3-BWJg4-!EG>_T0*Nkh% zPG++}56UPC+Z*Rwr@W_%5fvj6{Yie&jtmEB5or+}y&b*cH8Kp(@Dt{7(-yP^#dkPQ zQl6w$@vGze#`UGEaA{nLgwGSqBqQk#aX|Y}`%qD4GCj9Fw|(Z$>t5tr(S zTkan5A!tEQ#zxOZ&wS^6XLoq;E=m{WqIto*u3y)uQ>XZk+WqU`n_zP|3`#7a!+3GG zHd-6|!3j9|k?8#Y(?3uRuBERcD)<6Oy-@sbJcipyGLy{z!B6$I^|39$6LKdW!M!7T zM-1b+hm;Q~!XnNthZ=cD+|-1r2`iFUB#Wn#_yZS4Q+<~@ zVJiIrHOR#VM*{Lf>1UDN2jM~z-3jh%j;jutMZKGIv;ya78@-KQfQ)Hba2c8T>R<%1 z#R>2Oy-InFyv7W$155*-16jMB$d9W4`8_q6r@n-IZ9ELXGqfD@m_Od$)!volN%G_+ zzF6#EDf#Bq3K5Bybys0vYK02Tm}LPd1r@Gl(AG~(~-)MK79+fKadWG^-YBB~e%BH;o4h6nI+ z9-RVS(`(B6ll}ym51ZGO*Olx^_VmCLw_s$!$n?mJ$lpOTe>49%?>TQ(S2b6x7OPcY zc9_)mlTs5?%O#ah8XG@0UW?P>C^yEojc*%oC597Er=CfzM{Hk)slVAV30>w|=IZF{ z=*vZu{vJH>?a}sV(I&L@xAhK!;#^s*)FiBSIrW72!?)0pG&A%DhvV1=j#DUPIqcF1{VmTCU5S zxDsT=Zff}*n8_`@wToN}T@2>-su5~LQ-4$cZr}vsm$;H%MUTVdc*9I5naf!)P#_>a z8Tpd(B}FAfCe%VLcryM}{4a^WB#ufMog&_m2l@NN=k78yzE8SOy5+2LMYioHcie-w_!y2M-X3gDU`lVrP{q)!;LPA)a0;{zwIS-ZLM!!E zy2tQj&PXi{FC0%ix(0NiX4)3)1{3N3dSSlItnrHm`4L{K;-xHp;Ic*^`ycxUL=K1) zF03`a1LDE{iSrZZ6ZLPkj#?D{SKaQw@}m*`N7rq&A74%}r<+cajKr8&|ZH#|2y=Og}% z*u{*E0Z{{@C}~A4^)K_c^R@MjcaL{>a&&T3)GBJy^C*8#{*EK~rQ`+?L0@nX@P)j@ zr58dYsbK^_W3&zu_sFwW;BF~w6f&BE%is{4FryPP>-)Kx&p8Qi#eZG@y0VhLT=HG? zU5&WPPK={dE>}b&ZzJz)bgW*4J=hK^H{f!_YhL*6s!3In#Fs+!2SXBuBs5QIk@R(H zz0@f5X1$m(A@kfSGsnt?Pqj*4A+4m5ZzA7Psn{7g&_BrEhUeSh-soQCSnZJcYcf-} zvRTD!MO_GaRj4P?WnC}}WTmP2cOd_tXx3$&=3?G}N~|XQu*3&RU>N7CcpqM78m(v{ z;9bHGDOEQ{7YD0ego1zH(m~$edU|^P4_P z{VX*Oo%F@{3-J%*9>&#RhE5EPZCCM=U6H;#UC!$Z)JtSW@&fk)ce*dl*Ol2j;?-~v z$h?&O5&I+fn4Txj$IgYeMK;ltY+@E`f4IPV#FWxIw+*}{*ZVp6bFd-a4z%Rxmw~K9 z;i1J3;XB@ARUmt^50D|PG8bE7#jWZVHH7wLtaFU>mHU;OugyD^^R9uvp+C1jmp{fA z<2&Iw;o0Wg=9JkIJBaT(g*t^Ar#DU)zq~4(qbKMym=r%5E$YIAdr5bb@}_;3Ci_R` z#+GKL*%0RtXS6qq_aS}+b0gV(o`{UY!Zm!P+S_MD}(V^EoS8j{}Xuh5YE|Ge~vWbS`cNxVuVeqJa{-d}gPsmhk{ z{AHNCD?T>;9sM2R8z%nKd6|92kMh~^PATFm!ad*4v%|T=*~HewHj25oqxI4H+KhD> zU#EVZx+iIGlKA89PuQOzUR%SGhb8w->zgJ$`YrGYTEooG1Mnd=JT*M&z6{?H{}F$W z$evuwA-{0HBfTTNCtaspr|c)~f2e<`ayKt!UhVbJ_0X2!=3p-NU>+cAv?g4FTlZwH z#R1f=uY)u|_{&uI`WK)q9Yry@-Y zNZfdwiHwZgb=+{@aNqUa_5I_2?!OgzD{?Ck|I2Q^ZoX~qZSFH1O|JABU-Dh@t@f_=PGhdg8pm2kb}hSB$|_|^ye+*7?NZvM zxC!uXCfr2DbuNKc@x-zzWmBXM(lpdGG?&TKQaiee?yjJ>pm$Zo>WJvb=*XeqjQ@cJQ~Qi~RQf%d zFc)tY5FZW65k*6~6UYq5Kf#Oe%WxNTCqlN;&%Cvg z?o#fZjvbEa%)nwyqt#k(t>2+WbtCl#`l4yc<&(-KB_$>&-cP!pbeZ0CA29F(!s4gd|2Q z1e!2^;1Sps+8UYzFWj4RB&(T~DeW_0*G^G6J!kIXxfTP_(Z-k`&4tz?Yc(?GQ@4(S!SgxA9)|0I9O$WoCP(X8~1=o?Yh zTh%+pHOAH7KEU2uZKaMx_v4~IQHeOl6Z8b<1?Hh1-4kd;@44iAjrGQQ2crW#aLvqF z*EP}JwniIKnHW~JH0v3CU;pCkRR@27uw_{#loHDC>hJ1Yv<@>Jvm9gjy9#&;c%&EY zE|?8^dwP3%;f=A$zR51Lyk!j-Xf&3lFHILc_@C$)ui^)tglEQ=$zLWfOkJ3IF5_Ir zT)yiK;q~ENwq3Rkt`08IO;3rK8nNBKoz;29e?Q`Wgpa zN-w3KgbPdyq_PWd1WE-<24m@om%KiK*z7Gi{Wf-*c&7IQl1H{fZ%`e`Gye#D%+!@w zTfEgCG9&O;`x1K_XItkh*Q?Bcaj$2uXQgL_=ZyP|JD)3`>x%tKrWSmowb7FAu|Oby zUH{#9{ZyCuaCIu%3#aGIw`!eU$ zCo!_wx(-N3oJ5`^e*9_DQ^hNVjJEeAtm1HGdPP&vNTEl6n(^4B} zG|u=vbR;x`Ie-JTfm#%OaAiEDJ>mnC6pFF6xMgOLHQyqr4M|t{hUpZep+q&Dj+j!b|e&hK%1F3H}r~df|GmSSZo0TTa zSWQ5``Xc?G^scF0Q@1iN>TS~7qzcIulINt%NqL<1I89=ZnZ`^*<^vbD7q(AxO>@;@ zW>n#b!V!LcA@_)g^~L%mHeAE~D>;YE&i2#KvVlq1$I!!$3XY;)^#AA-?8H4-Gt`EB zVYD&Y_?c;}&8_CBOCDLd!?~GMQ~>F#5`M)0zKHjM%vSFd?i4P-nh@_6>FFzn@9G)H z8Al;kVOJUMi^F(FFJph4cb#)paaMD>;BecifYmPghn|6+ffT%sWUk;hDa}wZ2)v_C%Om|VRrYd_%5a6jYZdg*(~ji2r-;rrb8t7oyNr>m#yrv0W} z=E#o@j|~?!i1JxGlO7ED=a5)Snzy(f*msyOqWF9)Mj#QdnfgsN=7wkC{EyP3GPM)$1MjI7T?te{%Pl-& zS-q^@3;otKnC(&4C`)tzWB5*H;+rcT8HItoyGOiP4_e_xU<`f`2h~Gr8Cz-F1^Wei zOV*;qY~$TOkv&~?_XYJ`4P3*RZ9v$r1Y6-qmj>+!3;9|Uc01pNx7N)7iUbJ zlzpjtQ~AHsUDOsG0Eujhw`Yb(xzy6<&U{bCmOm`>|W*ZZyYRp*j#v z{%-ef_XOw9PSKk8#Mkx%=1zaY(C31)kXci5e$EFu&~YaNtcmm-=tQ$xS(#w{#OjLo z?y5|zq+@g>3YuCxU7m0e`X)#6Z)nX_>;#K7v>KXtjcN|f(a71@S=&{MZ~U}thij*c z@l?*KJl|w`7sMN0`dWJHz4fE`7=jyIN^i9a!~Wmjld<{j~tJR&KO zNWagt;7_6PyubZ=iji!5#*FXiaCG<&;8*-IGEaFQ{x|bUTZh|(%YY`-GLM3Z$|Pl_ zx=KyalC{3}e)j8*8;*c8;5_L%DWeBnGeCdm0Otn#2742&i8ePpmve4|aRD7_jf@%@ zwbE*(si|t}HvF`{O8qMJeA@Z69Dy7Gm+sbkSv{-=>O-|4^BPT;?kejo>z#-8z#d_X zkT|Wrx1P5V{%JQIHyzm!k+oOaD|gU%$~{;J&Z822B5zouMS?|xFQ{yO41ElJX5=$k znXSwo{OpS1im?4Bm`Iqx1o{)#e!_8k zQD)GXPRrTD)dMAI1y@gMPf6${QnVCprZP(rKCZl8UjKu4C|(2Kq2Zw%H5)d)+l=$TfJeK4cShjRy8{xZn`pSA8 z3I>OVgoQ``Lis`wJ~F?SU+apW!$$O*7aSKI>(Rvs=T1wKvz)WMQ@pRG&uy);R&h~> z?XUOK)9?sNNRLmSo;E%0Me0APS4$Xd)wlnoYR@pIo&qh_LN+rgVn(*VH7uh4E+%59qdKjJuZ-)s^&>NIWC0G zhwKQ?+VTE=A%>V5o)oUY9+<;-z5*>+KlBDU*mE)`ejZrF9QapwqfSS|_k%i4-KuTZ z640=gbyRRvcYaAV=7Up=PBxOuFJdmFX^)5Bgx=aNj-Z#v?qVJcC@{ zyHe;?YpgZUwh+74G^?8RsHZ%Ev+zSIzCx2yKlpVp7d_B5=}nwQ{BRkcw>R7er^6S* zP2nbgQRXRA@KJ8Ye|MsF`73;rH+wSt0Z;25N>8N_6Xy$Sg|(*iT92`hwNIuOrk=B& zbCq+sb0D+lHapfin%L{vhiHAZQq1E!Ozreb>Qx!^I25KY`(xUFX(Q5xr(I6Fnih}8 z(rqf`O}VR!;t^C_Ev`nYngL)@(JU4%68(l#l9vs@G<-RfNZ{%{#O^(;a>3Ev@IQ?p)}Y?f8bi zp-IfNZ^O^}fTClJK3lI6Y!>XEF)HJ;^a|x{!00m?w=&(59I`!^}cjAM<_SLH&AVy z58D(gyg-?)^j5p8!-!{=*yh{zqd#B8e91ESiZpfBcRq34b=-p!s$;8etFBg1UvU2n zfD`l(OUYcVq4aYvLi7GJ`ls6IP17%-WwiK2N6~$p;BUF4-PBe));la_k)2|8z)|l$ zDyp|pCgk^?#9Qo$bC0tzanc@jkD3pamgpzaLn^V%@4@tdlXEmF&?VR}SPzb1EY+jy z{M_7DlvRg2y)bvgANZ?<@RH8pNiQe|l^^jvsKVaN3Ci+L=i)J1mfD<`x!pcnep?oM zQG3wtg`wDob99VjvtzI0h5fyKiEX9rj`~178a@^tY7RF`>ZSF3!Gghw8Iv={rjJc8 z43?xXO214lxQ)2OZ-n)0)-h|dI#=z?=Rb;X?=S8l?j4@_9-B7~c58-blzXuIIK7?A z?Cb5->HT=dd4JHnZ@$re#;>7Mp*!TA>$s1Sh}8DdCwfG`puaT!H6n;LK4A#v`|vID zh1SYGo?;I(Y{n~{lxp0GA-qTb;kyln--X*Njp&GtQ*NW_x~<*O9#NCMK>SA4|Unm$5mx zDrl0I{${PU=BPu}#`a?Nz0O~pv)w)2M?7;qxxJ}mDn#07IPaiASZ7~lFOOI43D(tE z>UxXy-}UmL&Y@oPu9PL-o=vRXnQntg`a1nCvk{6itDqyA=H~b=B=X*B(T`r6S%NB! zej8bjwb_j+@G;NGpS_A6o=P58Ppzs}fx~QIt6^(wuWSDdo^2y@#tu04J8E(U)ZpJ8 z)y`>`(M&J0He2tk&(o{X2LI}IA`ZFvt~D(%XDhg(W*huL1ntAOR0*Q!u#B&^ybW|q141h zt2sBwI;A*!D}kW)G4l&9+5WOEv#+rib(C~;pk|PT9`ELOpL%SOwoYmfwKH*hWwWlC zn|rqgxy6-fH@Bqry^eSIeQ0v%LhvzFmt(=~=wIH3-h=|w z4ojhs>0&jt`i9$uD=CFxCig1IN-S28u_*n|D1+FAMU*c&T|VW;D9V(#;Z(&!iu88< zs;$zd5gT{2w_$|q2m4o!qK+JnH2e3|X&aK)9aI;qSHt_lzr$H?W_IL-;OSr^-eKE} zt{Lu(PdHI$WGv?WwGIskErfZ_PpolSeWJF6FPP|@<^0@T-dz%1#ZZt6S8&~R)s@v5 zSqm6rmyB5PD3A^f+^}P_F#q{tJgEDoAa%y))69=)yfj3 zl3GUnK^;Yx;ZP<=lvA%MH+g>pu&~LaB!^An?R-4(4DQ0Rs-Zfm;-+c$s3XnC`@jI2 z!=l1H!@h#^wG2K>z4=DESS_r&^iDV7Gi(T~4veOc_9N>w8|yPo;uthJo5^d6TUD*+ z?C)9V`coaM^SvwC^`+-)&jZh6Cadl8Tymdwe~B)=GJYB_=_?zpbXJO69;*md+ok9s z7g6Ia!foFuSQ*8|%V2CMHdLCwcbd7}{0pAqeb`Oc)*Ge1IvADBW}a}VT2XDQzEFb7 zLS+lL>i0ZrA7zuWM#-;cQE#g!)s5OLZH%p}tvp^d2hb)wwx6~ywvV?zw4JkU(|*;m zvXd*5i&UYfu^u|c+2k`-1LXok>CN~iqglpdysILEd4o?WtmQJlFxL=Il+jviOYwf# z=)CMK>Tc||dkXRv>v=Y~_qd0-M!HTo4m=g*8!jAmvtbF4MqnoOqKntS;vF>GGqiM;eT#qn(0@xkw@4B>{Tt5oG2 z`XBw{|8bHoVU6_E25D9Buu4Y^GXby3-|2swVV`7wV|!}5p`F)Ss}0pT#DMG2qaM}w z>KYx5d#L~X%|6^te@%W=;kB8|l|t^8*UV#z53f)2Y6HnrhB&`>Cb(ibqbK5~a$V`m9lo7eiR;-v-QYC?JnvjqWfk^cq+)PaX61hkQnIKTnawrzkhW8s zf$u>%dl~ye`>(iQF2nJ^sJ#@=eG`B3+)5>-EPK4F(Z=Xaj`j~R_XD)j{aL5mGWKLF z#iO_=Gl6PRlibHW(U>07yVQBJJ1xfx*EN^V6L3%V498Kdq^FjAR0w|=Zb5`rn0L38Cw!pZ zS5K>_P}YuQVpbOQxN?~18pSH@!#TPT8ZoG>W({}1uPqnah(B#-ZB^`F*gM$U)5V^} z-i=(NmR3_ct(;aA7_7o(A$kDX>Sy_m7Y61B-etUD;{3x5I%ny@-5r!V?0R#(>Bj3| z92&4w^ptOQZg*<%J!kQvy5YVZsu;jV91i6!j%M65?e;W^;}p{!9qQ zbH*eEhlhrQn!(5RHF_FrSU*>-^VaR~)$m$nsgjQ;>Ig5GG?_jnNN>)Z0ogbr5+|ai*BZlizQ!<+10tx3;&l7vY|s2lqXT+C(wp@}I-wh&T3{ zABh>;qG$P(c(Ef|{0f2cfnC(^&!M62$E^C1=1B8T;=uysVjb<@+H1hgt#++)^>BaZ z9t+;M-ngVL;c~bgPMgd2l6dP9tk^sJj{1;~^$7J0y(K410pmkIhXxXBFE^GMuVL+r zz)IAnmp&(6e6l+4f|Fnn=MCfB$t|YB7#39G!f{03>EW+=*6U!pI*oVOUMpZLAd{kO zMc_1xu|AL4j@w?KjbBCXFFxNjtS_zp)aZ_)<&@gwKzf2@#$_kam}<$b(9Mu=76mvn zer0bYz$s}?n{z!gE2ULZ+|&a`q%U?N&TfA zKmPz6$Yk!t?fMQ~>bJeDUe+G+g;U&n)6oHBr~x&n_KB9LCgSM0g45=6^%QGOc;D8< z@Y2t9jqbG$>bI(0v(r&{O#7DJUg;~6y4GsIh#u`9^&j;I{4ysSsMRk6@rWP+d)} zbslI5q^C}DbJ6$J2fdYE^v51o>QbkO#k+rU`^t6*h+c3H_ykDae+#Wg-EiIT zQucx9QRRCT4TRK4PJjl%2Em@34<;Hpge|7%v-(lnl=%W>=#l6{4+=|CMv%HYxjMND zISV?+l7mh|w>nZ8sf@8kTStr|hV=Lhryn~KNImij{!J(K6S{c)l_eGxt*dbTQd>C# zJ_6zBe*`XgwE4;c{^rt3I_pzvFtyl`CqO^?q>8f-UxLxLQMN1KPtcL~DZVGo=rg4Q zGo0VbXALGddmj2Hw2p}XR^TR;uK6&v{|24~p9Z_4(UltZFL1J=ugPN1Y7Zk&9pxJB zYEQq*92|^tx<5gR6n6Gup1?rcK%02-2zMW0Mwr6emFKxc3p6Y^l%M!CC^H8|=h}eY zPtk&=!88#*kR@DK#ha!hD2=zrE%g>>PDk}Mds^mX%6sew_JX2nQNE4Ss>~G^{Y6W> zB*k~W2$-Zz(k7}C)v{z++nLK9ftSWKWcW z6g+E`y$0Pwa(1YE5iSZT&$7TX~zT+XL!Bbqv2>3v1yq@YVr6BU7g-wFB{j zsRnKU;rAxcmok9*&lFCyHQE|&HeO7hIrBNI(0eT!(M=$ZI>A9S3O>8fUXVDj5a(Vs ztC}^RyRHHAVTIoo9iHq(LW)p|o}!CZbdWX3+8Ev#-b)rZS{+TEkf46T8I#UwvtC_C z=2TSOMo#f183m0@;aJYn0!n`F|G7#LwFo!neU-OG{u^QIV(V<{#6LkTs8s>EsJGF* z7cR-%;1$M7Lu!?j+d{2^t;lNf6B$oHH#a==p0)HR>i<_TTi9i4MLCOO9kGsDaLPJG zTt+;(=ep*)1`*%ffG>EYJ=Bg$c1}-==y@xmyDLZsljub^z#A5&V=D)So-K`*#(sM3 zuvG}RRoW_@i0|a*j{>rfn`r}h;a7D!=gBRCc)F}1Twd5A&`5p zBGLE}^{`r3tBd>GNiE72ow@)1!%5;>FkBs>*5%HWcw-=b4z$M_w?nr>Qm>p0mV)xc zjna!NHIhSgGae>pI*gZycsLn+I0IIBsB4I;F<1Z>)xps|^Z8z>uT}9%Dq2;UnQA$`NH0xzfMt2a$?lOBur+TqZ1` zDx9p`5u!gc$eYS2Wt3lm?AZ%I_MvzZ6@aJ7X3K8dr|r`i%c4F}o+xrQO8sN4vDOgn z*f(hU4{{qX;rVPKEffI#jJ`%W&hv6gd8H<2oUGAvupl3)bzCs=lZ9WDg!eP4p(ZJljWd!7!r1d7=5CpXmoZfJcd)et~bp--dr-)s0uj zt3|XTI5GdgWb2=`IzaYV8}cU6o(%`plSrs`QZQ5b>VgF!4Kw0x(2%G z-Sy+4W0~(xyiKR!bur%f+1PAuHXm9KtqjhBk1!SMI5(Y|6Xv?GrjxaA24%oOo~Q|M zqWewd&dfuOKZ;l)SxHr95Z`6fvT?IdV=tc44rm8)Ol+;KB_3Kw4AeK=FPw#b*VD#n zV-dYWqUrw}ZN^PPs&|?L%9J<(3#tnIw6qQW*T>*j^J9(QYnnp*XrX~(uq}GRNKHU zBeB|PJU*sV|ELT1l+DOyd~t$?;wmS?n?M_c)Pko9f|JN=CC`e zIIFM=W1XM4K5-qw!||HqnqxS96Bne1P>EM^;*He@Pl*t{pjaJ})%T?{qy^KMc82=v z1L!*+YKS)f5${l{N^JxyXhti7l;z7NZ+hhg;biLS8@-h>M|>6*|pCc0y(&z57a z$XXKr*%HDf5E;olij$5Ljv3DBsMoIXpEI1N9j6>}z6P`mO=7h%RNZe=BmACTGl|!( zp*s|xymW+BoAoW3J?E$4?y={wTm-ZdS8ruTT?A%y#fULU+cohlsRB;H*t91n&dwWz zP=tXiMD#jZk?(P=I+oR}tG#*Sav#cCEu0h{|--6#OnYmX)cRP_dPjnm$9g7@OoYPR>C9wlGK%P_f;130Um0q4tfY`nYGM$);#MW^DShK?o(pj5%e7$;WXS0AJLQZ z_&@H%uJm8uQ|^#S^kDbpk?>ym9PgU3yw5lA8l5@QE-4@een)(49_38q6IS0SQC-J27 zl=B|7>mKx74r3l<7JCl+_pFt5FkttoeN=?oeTwGr13cOwa`~P--!-sMU#PDke!6L1 zH{HaGrQu!jqg}YK{-u6}PN|pHO>4+K5yUWmvAQ7hKD|M zeuWd;V5~4SdNtQ`F1AxUr~%E=2HQv3XHnOw=4?n^ZY*PQi#fk>bav$6j$Fch^dIk| zCNcDW^O)I>y*8GgEBzqv_?fl1BNFwu`oF{vHY>?2&iP!K*fl$g?+E8+lonPCp!ZDW zu3truPBHFt*?&!m(L73&k`Y#^S`;R$7{i3rkHmO`;c-5ym9)mZ^U=h3-MM27wE_FH zBV1iAI3FKt^d&t|q6q&CE$#{Qj+aA+&;(Y}t1+K)mieQZ4_~c^@F8>YY0PcUWA8|x zNGUvRCp+ijg4@lx+Og9yiu)r?v)jJrXHN>x2|qCZF$WsMjBn{k`i(xl>ExU@=<)oK z{CX^Fce}aT{75WSfcjBs-cmqKR>$!fcT&S$0IG4?9D~33oV#KzH(^<&vJ!*O$J6i| zltC`4q~EeTFDX^XIo7j(|K;5U*^igVGg=ViEu_A&hB-bn;U)*8Z|_H)Vg>iYC+v|> zC=RcpuhGQYjnZZ*a}D~jT1rDDmQOJm-TB}6XFhiP=jg%Axc=zG;~W7;2zGfZo}skX zYi(f|Hdw2zPwBsX%AF7nWrThW&B4X*SA47-IH=!4Yxs|m)rz$0lXrI~*K5MJo=iT` zL2JWK9743+R5SU!iGWdPA7=M_P+#zjJJsK) zU{qBlDp*Wyb*AVA=u;Vs4u6}zLNCOuIGsG{OX_O>(nXbO#2RhUlfC78o2AZC^V$m9 z#=)^pN4HtPS(Msp1Lr%(JM2lK98YWyY@OhO4zvEF&_T{K=a?;w=6G=o)suL}_w+s1 z$9G!S-8frlW)%5$MV_xNc|t*S=NHI%3v!B916lZSRW08N?=x_19y~@ z`=Nkdfz$kmzQovMJjF|*S9oC9rF!x1+oI*QXSdf!w`FrCI~qGH5yhl9TJpb()3CJ{ zUq)3;P@0Boh7X_xZNu}m(pwPAoTB@2J*Q1-Xp_E^8unh}k@?!pjc%(2K1ko9AIisl zwwgZYi`4(N5R){~I%t2A*O%mdtRhw`tdvq7P)$1no)Bji?U9Z49=?Qf$m_j1&-aOw?G-adE1kOh*kYJ5ug+!8n zEwIhA-LYS{AEhQ&3NEGq{X)wf3mmKM%kA}SU)%Pm`_v%2q%9uPPmOoR0sXlC9~`;# zRqtbOe?g8IX?TqiWuLL8 z`z&-+*|?8{S9?ocWu*Co*#O^%k>n39Vs00?;ZS-XixWQ-Ajbcae6UlvTeugzbxo?D ze*@_ast0m`v+7yiObhj)@_>x-d+KS02=x^{NffKPG5c@>T)v0fei-ZfBZVOlAI}$j{QnTHDjf|9;Ul9neGoft*O6)zs+kEuoj1xg$uzU?9}#X zh#MFylM~hE8RUt{j@_K0u?#4^3uS971lmg0~@Eyq@ zah<(NRmzjeB??zsgx}Mf`+X#6s(z!sg+r>(x%dOM%7x@CTg6M}yu?6~qc3A0Z`Zc5LdOxA ze5P&X-zjOG)p=LHfL2 z(Kq}heY21BNBTwjrXrb_Aw8Os*Tv%BBi!;u^&)GuK&FqaXxEmoI+r56s5N+5s4o+ndx-kV5tKbh-MFpca$as!!#E&FgEXQps)1>p{}au=2Y zJ-PWefmguCJ(fkys!APT0kDCV;Z|YM1|BjGnb=;UH0~**m+8=V8(r`uMz%;9%rq;Z zd7K9yDO>_dB3lc4bGvxgj|Kw)BLM8#z#Hw2_A~s7iLdfZYo=A5{t40kPM}_24m4zq zieKAL_+gD91{U6F6Wr(qWxX<-+)wxl;aI){6}1Z5VK;&9Wm($$Nyjwb2wVsTiVM}AH2;;-Io0-wVfaE9O=q8 zwG2Iu_&C&{$9xm`4$iw1oXl8jELycy;a%KlbGZl0^Gx$u1F}y4r;QXVMNR&_6o*C- z&DeP-r&ya?!3hwcULifk2Y~SZ;&UhWig3olfy-GSYjho)#1-b7dck2ysUpV5yYdvLyOfvu(1QhP-`LFy{d zeC8E;RmJa6H2C>JClCj&&@K4Td}s!&fRzIUWmYvCS8g|7wzFcM*@j$=TmR; z0^tj*QL!iWfS*YT%bu(a#Q$CLV(FVofvdR#grDNC=N4)oUT!V79-w;?er*FfU^&CZ zdsDnnTI1g%{A@q`6ZddW2(MnkR@^51;XV6(dl5$whaW7oFR=e+JIo%Ouc1a#Z&2Hj zUY#nOCH3*^mwa04sZs}#{Vo0T`^;*#Joy7bmSY6B0g2bT0i$$7b+c&$1b zfr9XC-Rb2|0Kz>a6023^yPHG2{TI5tm(&|~+IQJM?SpNMJVf%sMKFn5?|tTUF(Gx!^o#a?uFyTsV&Up|GMJC zm`D^Y{QYfmwFcl3-ayi4Abr-0@n63mz89AJPP_r)K^geMdY}lWl5nT>xb5ZlU*;_1 zD8ZS&v3Zs*%pbvI@Z5N2%qC8iJ|a1r<$NlomD0XJlPdh$d5{cF*pJ)u+CQ_)yOkP> z)b)yni-zx+_srj^6TZf;YB1;sw(u^c_qvQ(#;l3=ST|y||FOe*5sBm@_7raAvUUY_ z?Fg%Npq8ShaDMbBr+7>T_-!V4C>rlw;2epshZ+e)x^r-QNA$wB3=h>Wf>%$u|?+M{93y?E8><-k0>p5wj;W~H}7t(Te zsnbbq?>V~W3E_!h@sx-nC#+ypGm1Uy#$M@Ocwp$s`VG0{5^8 zECrplF09c+bpY>A?gFVTz2fJt0aL*W{8%M6EleggfjHn6z`{=b1eHcAnxPFKFBlyj z6+UJiw}k)fPVe)--1qzNvpEY2ngwxoyJ?=VPGrV1qJ6JQ{jHv@o-GF)(=u?}e$4)( zeVqNN?Qh!$?Sm$L$}%Tf`jD=2HXo;smd?yqsm)KsTl@~O(kS@W_V^x2U%@!y;ps5B zL*R-;%dr@o)y|MJ?Sf(Hu8EHMJ0Nj}^cN&^ejcUvw*?#}j{O(@vzSthZ@(W}nia5r zyE1F0ozR^o(f=#__C@Q0RS3+dUn(Cuz<205<3Me^{~nu|w;6d@cKVw{`yU;S zLTi_eRi!J3i9ID>8V-hm>cpjT*Y^VdqIs5?wuOLv?sq`qiSpcaBU!yt|9S@_oCe2A z*EY|%ocyXVIpM7EV>mwPD;`V!mP{|tX7YHci$0~deGunh9jlJj3=VZ1d7kW(+ju>n zMfWzuKA5iBv-X3aE|57VeYJj?oMCcLOk^gl!bDU{4}9r}W4NH@sF-=mrP#>AT6l-Uf@bR>1TdNAa5&~IpV z4F++PeGd2s?+@WsK5Qx4)?se(Q-p*XjrR1nP!#lV+9)%@VXanTV zUqqesXLe;>@{Q+k9G&R*y1*Kh^|X^SQ~JIox2TA3k@S2Qr^l8f&yv2BEJU+~h=6mT zM|fa+Xlrh7Mnz(ny|TTEeJkF7mzX0VbuX#sl?s;*>+stF-j=+xD`Y6Y0jbeX#od7j zDbv?jbO?>e?W8s!^|KblLes$n@HKhU3+6NR1F}ZN>sn^1%lflYsQ- z{6TK9k@H3Blxfsr2ZF2U{-jq}dc5Uakv;eUR6D?cf9?Cy`u2a{4>OwvEYSe<$CS*zz)UAjwsRfGOe0oD9d&bbHAbdu84Yq6d*X z=N=GUh6@a)PJWiVFek32ztGuUh`2jsgp5zjPl&W9n5C`KR#v!Qxr1uaBh`xUxHk2A z=@)E+uDCOBg3hQN`mqN^{}Bp@!pG6;FTg`hq8%Gt&Ef8(&2^YubQ;;GB8h>|}MeN`#Atj1{VGst?XLYyc))UV(M<=m2ZR5TkeKq;dXH_$mld=I9gYo5lPCOnnos{tT= zMDlEM(tM@Wrk4E>7UbK^9JV{NPUTFZlOue9Sum1YyaBn%^(C+P3CyMwY8=(JuQK=R zi*OI-B;29@xi)draXjTZf)aR1RAF9=cqGd`{}x{!@sIu&O$Tjws@!+dTVKLn!rm4X z0~^sc-r{^c&kTq8oM5fUH6>RrXcpkE?`Fj4F|a+i;LE*CLHX6_3ZK!^YH3NlFXuyL zH1|^Tq{`3SnXsNgYGhKoj_mrrI}J zapKPFpb%O{$t`Z-k1Y3Kb!rNEm|-II$HSb>>&*@3Io_ANw-0z_nLvCVqKV-W@x4p1 zGHt-Zl4D7nB%Fc7+na#QpUMN)z_<9R%S(PM7w!&DPw5qvwKoAA1k!t0m27GlYjhTG zQSxKSC#1eQ18`+pW5_>|v6`ExdHzVQI*T*(srk1#z#3qE9{!wek}QgsTp5v6X1q25 ze(ja*wJi<&Zacyh#bUPBRLO<&DMC$5&fXYYDcnHL8Hv%NfoQxW<~_>}*o#hV8>jvv zPIu8Sgg_Va2+^ELJX#nWBQ~l*T~)Xjc~8P6iH=F`7x8_QwI!deG54fs0VOUP$sUyV zA$w5n!DqO8x5R_so_W_C1DbMMNX{*u5W@diJbxVVZ6cb7Byt#;?KzKHp$IqS{iQH( zXej-Waz3o2Rv>Zl*VG*fvntA&YI*+|^l=D_}rgA2= zQd%ni&>_?Y948+A9Ekry4SNYbAHWZ)i0szwrjs>55uu z69YPp`m^L!q5)XREM@Uqm*=SkC+XzIFJ=^F2QD${oApf53+2P3RlMPC%-TFh&Al1x zUt;a`Kx*%j(@P#II*-91kvL6eaY>%l0`vh($r&DS7!V-{uplm&eI;@0b$9?Xq@T(&H|_zbJf%lbq=q5DoZ#+deY+Beuan z@(c(6AGD$>GX~`Bl6+ah1kr642f~NU0!3hflEFXLKh`}uTaU5+L^C0}5P7b-U-9Vh8q zPD?h5Ar{`2$mUe|5rNq0KEok5N_?0)Tk*wl>^0+;-P?$M(+lp32}( z7~%Z3Ht1C3ysreKAa^J7QcLdDNqAGq^A!LCsMVzt-<-hXcQbyg%gB4=Oc1^(2FQF+ zslD_C`I+yN8H2Nag@Ksb8Ht=50z(>*t-Y#olIPK zl+)~ib;QIo&{D~F^%v1?8&C{LE^!*ZbSU$NzM;3_E51AFLl*8?E5Dji|CD%RDv?ne&Rx+T$vG;T9nm&Tra$9nP!5Ry=5;=$#7S}&OCEWZ zc*O%|;I}Efa!(+9u$*B9$GtzUq|)^B+>iKE_uDpnOf zj=h!soWI1>yadCBblwW)wYd}jJcWj{Eym?+H!TdD%`nzza!A!|6C1Id@(GJjGyDbXD^4Y1oBHsNY_QAhrRtVMK$hlpi_d&vgm9m;(_0Xzpk z5cAe$*B7Mc*Gs+VB@nH4UMjn?Mkn!nJ&4<~a;|PcV^WAbdJ~zD)Ff_%|Dwx&E?x=4 z_-8n$>72~Ep~R(9dy?~1?hMJ7BqrzyOm6el)N&gDACNp(&KJ?leWc%A)_f1LtS{(e z;xr&hbjY%1?pgP&SM<2#0lylHIc3_yKz#?3c-Ron zo=CX7B=C%ULhcFSerX)ysk&!s&wBENqAd`eobd4*cs}7@#E)DL3I6+1v=F5WbE@NpOa1<@eN=X!;|r#$0CdQtPz!y%vf5bWbz?%h^! z&q+YE;PQNuE5&ioe?=De9Whros+DcRZNnY#p&F0(&lBSb(abnHzx%QSR~tE*Z+IE3 zN8c@HqU1TkO}~J_mz;Mh_!)g&U9#S%sGMbg-hj)MS?j`wi~@3Zl?U~Ka6tRHFXC8_ z!n4(fCzd=~-nY!rSwk;vb#Nb^TX^2Opfvt+@;*hkDjeBvAiWDEInP8hF8d@Elw#&a zesB}cTR4@UP*^RYjv$=LZej$f3y9w4tZ{~F&T`)0k<90lnCXAi9-GobTa>dvxWnc2 z^oZ76wAXz&L*@HQNaWgs*$cSzI3cZu|~gK8ZN(*GzxLpLnk|m^YP;ctGxnKb1c-*QlwQnXzDh ztv@GOQ|>`klfC%~{b|c#1`GZlSN8$``&|G3|9nn1m5hvxW0gH3BkRzhWF^rMrD&m{ z;@hAh?L`V%NxLMWq0ppnNom-7MIp*QpYy+6U$5TZ^$?9nYYe-{u7=*oI5d-|A%xqtDdFWFZ+1T-0kP?TyM&qA2-(VKe}~z zmU?!J%s0)sdCqzDU&JxkzI|tW)L>xeVdY9{+#9qm>3vvo6#QX}aw2t$x3}>5XSLLI z%y6ESugM8kj&tF3`rNCvA9$mh%hs(MrmxQ?KV268vTpEu!JyAG%W0n8%#i*uF5^DT zt6O4~e#;XomfqL7uao1)-T}2o)8yukkBZ}dxj8VkRlU$F9=oEBzz>I>$M$o!FB7|Z zj=d9O;XzkKHgRx9=R=ll3TV%=rhSG!s5xSFVf~du>W|L}O~k$f%7fH1cbU6uRhKu# z_`VRk_)Yfkuc5c59_5}I`|d46@D87x-G| zx-V+2Slx~f9#jmPogT~=+}Qfq)JLcA^&U<7%-o?Vjvj&`T zFWG*v=_6Y5-rHNtHj%h_%ULe-805vxpBs+eIDKR6@u&e~R_eV-Yjt;{bAC7gzN7wl zRqMp56Nh;G$L6lq=Pmb2ZWpaYRhI^^y1&! zomXaP%#5>9Jtua$a*Nz-bi0uE_GXk$YQ3qo@ARvh^mtF*wTq|OuUe!%+^C7Zzqa=6 zDb8=**t(>3XmS455LOM$+{wY!_KqzF`)fA3!<^^OxwrfNu4;9xB&L1v9JPBjS$XR| z)sygTcSXvXb{smPFBobTzivu$&(;;4_waSj3A?Y0?sn+jCp-*J$`keF`5Y{Do&;{- zIP&9X&E0gk)9hPifO4ewwoXn~aeklj-MibH&o>jkU9&4Uw$unOYOdt=PSmRBzq_~v z)6H7HsyKLf8O@iPxxF&^wrky--hSD-y)Mzx1PCm8O6CX-PPv&?jMtKpE!v5 z9kWz=}>(Vt(m_wuRv;PUSKyS)71lx8jDl2=u?*r<7gJ+e@7 zRsMN=@o~kemHt~Boi*c!@$)ygp3{1E@mmegy=-c1|139DBk-*H-2D6IYTzff==?Mc-swrc;>eY-|2AN+1rr>&+g=)CW9 zTUX4za_&(@!rjszA0#J?_)JTTbQTXsdtyrs`VVt28**g#m<3it?t9AgDT8e4(@&T? z-(Um!RbT4Pg>9SHa2J_#ChB|od8hZYT=k;lTSOl*98<^nNOzO`xnA~;RkGyq`U39u zJ-oF^K1 z7cOlb8sEOJ#s1A&m|MB4x$`4Cw>oobYU+q;qYIR`pH>`nPoOxzQR@ZqJ+p;p7VGZ_ zGu`cFK4JaNtC`7ATZ2nG_LYxLKU#)+{=m`P^LXC$x#@6b%;C`Ttr^|ya&q@!ZrLe- zOQ&$*k2P6#YW2eR)(=w0Jg$83=1w*612*yD=?_g`-;BDmFzVdPbr2+aHrSllw^R5jM#~G~pgSP-f9Y7w zH=DWeZTo_{O{s=oKAw?m;@h>f9_GelMl{ry{hHUe%exlQd4l= zNuB1}^!MeW{mbJ8UP5qbo^e`v%x7E9GV6chd$`OSs#`5qBzM+m{bnjYnQZ5WGI-2e zsx;_byr`Mf57gx`>v4HAT}wCR@IUd`(8R{&pFptb9Me@kLpJ&mZM(X zdT$k`|FpKu{^d>U#YJx}r$4Oq@QjD6mA$Kbbf)L>TXm;(T2GHpY~8JodVy^Bs!ku6 zmtDQJR(BxN%dO$48L(F*<&txs(tOb0>dc=V3;pg;b9!o;#pm?fP7G(%q20@{c2zxhJ}Mu30TT z7Zvdw3=@EEgdaBSK3PMz%I^@i4OR_V-ebiw%Ox~l_Hv%I+U8GM|Hwwg2snUqo2&Uj3%_$0?LVu* z{GxSE@36+x=4)1Nc_h@69Uw$`)gxthcI-|pko zgZo79v)ZuE_)}VXS09-3!8z(aXZJlktDfRr)%-s=^}(i_?wc}CDbBA@oN&JIwas+h z-n`v`RmRyqL%EIm!r7hOe4t## zef&pNkG!Wk{ZZA|cBw13>zqB}F(04v@9O5}O5IWUk81BHRgvC2+dnHlI%DQT-K(-} zv(1atBm8qy>xUO#7n}M_Iq%bY=5w;q1FJVZD=n^`PS$Ov^+jQtTHd$w{j2I$JX{{V zU>Wb+CNFQU?sIN7`o1cSJIsB4chD|Z9cpe7V@AJPu?YE!dR6DnT|ItxdUm2tc|!c@ zfp&ZSd}WJdTe=$Nh26ohU6Y&U0Pc#rZjyXQhocY7nNx-P*g1POYqWQq<}=L$$frM+ ze9y{%?g|4=Y6g3YsSQKSZiMf3MotJ*4EbfZak=B|`3H;K)>vg*KR^XOj}1Mdr)7i&M3 z$_rui`1f^7=~YdBogIh$V3O>S*4M2H_0*!`vg!X> zeb!sbGJoB9#*KQ4uUErgxsx;>E4#fm?zngyZJC*m#5uk?bxMq5^(p;wGdt^r;73n? zsv7=+(_czwZ!A_EQqA{kb+HzY!<|-t>G|p5k)GzOaipz_6X(PPXU=?Z%4aT-4_=iI z9#MRJa&~iE7`}2fxbu3N*CyYFvC-v1nw8thtr~-I2d;(r>rA1rJX@GX4EH z#Rj$T)`R^{&Z_@nw(XL>e)+uQu<3VCKRD;X?D9)#@a@HjBbrdT zV9ti+OBcp_Uq94C7H>x4+!;G$;pcR3_ya9-MgM7z`rP{1&gay(O-yJ|F#~K{`Er5Wh@ewKA5bR$2Gs4gol(X4?W%f z^>XdMdD#83_%rj-r)Hy{XeMI8q&Tb^wmBU=u2owLW=rRH!iEmcY;tU7_`GxIeOkHY zlalY$W=dXNt?6ZRURgx^L^qcFqx;|wn_eLgx;#{Hmx`Rh{Pse9*2cy94dOF%rXI<+ zzmj)u+)URGhI+0#%l`EyR!ajjva-3;Q|WQ}H2C~%@O?v0q1NQxX>upL@$RCnnFX9& zZn#0Z7Y|p=2i5kDjEm}%yr2&Fh0W#QjqFjKi7hRZgnua$K0L|owH~Wl?1HU>%lrOQ zWIw(2!Pe)~qPpk{tBYLSQWIJ;W_(HO#nmm&Yjym$lAF_vXONUf{CMo~i4&zeMdsonyGmIy*EI z|J{}uJ+p%Dgn3P8Pwwu%$NgIR%4){y|0~y%`$Km5?e23k z0^~U{g|D@4X+7AwzNH_awtaQ;;BRO>oOhk@U-{G~y+aIN+cwNODEm9L^@r92$+vI_ z!=@i9?mM^t_10lA0<}gQwl``HdVg0k04M z=wJI>{g);3`xDA$^e4dz*G-{g%E2oBcxE`JZ9YOR9PPA{$-58ooT{cV+kL&o^bO-wPp}x&K@B zVKedav-w)@Y?7+05vPAz9{-i>^vB6MRYG$}=SLnbP8^>`wrYOhkFDLZ(eL(2H}`q> z)NQ@2zVD}sO3%y(e_i}>-@JU`n4WaEBE#BAxzgMf!n3vW`JINo_P1iBf2%h2aJIZ~ zd}hJC@ZWJ`zW$B4DxXjTXj(Ot*dc^@b;xvV6DrrueReeidD(Qe^p`XTcwC(HhvE1+ z{r{6a$2M`%%X&^T$m$2Hx38yGjof7VnbUWNEAaEyIxl8$+?Q_mPp+n^7V+zH_Ss?7 z2~#I^Lita12CvCRE^He31H(DV3$o$ei-dO+xj$W(_eDcKv0C`DOy6gX!PeeZALfkg z@Xty3P%P$&!)dO?hd$E{J^wlJv5yz=4+y1pX+K_={p_2x?q)Ynr0;!9GXsxQr`@Z( z;pEQv{iZ77@2b(5r!#YQZ@s<)nl}15!CMI2BM#yxT{=KlE6Ps8Td<=qc8bN>F~#1qqp88>larMa`J>R``L zOp|Md9DDZk9}6unOw0c$)-T*`1o-Hp;mp5^beFWBCx%3aWX-!|r`v?Q&o5HFA!|D$ zUwLTmUg6`PQu$yfz@+x^$7|E!x$VHm^TGp@ z@x@8Gd%u2tjQ@-M?X}_Pre$Tv4Kw`uB_A)Bp}TK{eV$|Eaz*!NZkHFH)pNt|)4CV> z+0CRrSnvP(y5sj3Gd9j@zgS&)`JU}N<)Yj7FaA)U`g!#Uzf@N7yX@lf_D!w)&}xy( zRg*e1roUYhURk`-r&kkQp-85Wx?109hgjIVvQatVwbemp#$lF8gUglM!_qs_>V?&Y zkICZ>PKz%MU3M=;F?uv~&FMbM-^di%tEo|9`IKtnlB4yynF- z&d*YwUYt5HA6%!o_v?}le*U)A)x%XRUSBr-&*`IM`DR)!EK)pY>bdRJHwGImd^aU~ zXOaKR?seF6>bB+^-qN|GF7oLKkIS;2R|RSDYMl?4xlT{7n6!F^=9b{7KFp%o=5q0q zrPAVKWreZOxdv{Bu#+#innbmquI_wREdFauy^kel(oXuY|puIeF$eif6~H3Va|aq=Ng=2^!?R#&5xL~TeF34 ztzBjZ6}<-t201sP$Gcdlw0KzR0zI?HKhH)_EHhT$(C1h8H`}LYh2L#aygIIY)_m;t z@ecPvo-(YHx|iUvqT_l~KM#dwx4xebstcW(rZ%gWWRB`jEmJBh_THBxTQlny=s%k! zbjLJ%2VDt#J}6JQgZ$zi+xLf zx_Il$)n%NaxFozcyZx-Ph^Mr?rwLwdQ}*-bo_E66-0`_^e)zIW3C<0{ zS-+?{_fxae1&3LV*EM%^apzLxaq8yXOwwIHe=XL}jw5|6R&-W1sIx<^&&F}m zZ}g(v!{?l*_cCt~cRV2f_)zP8*{U-RYWrWUhp|o_EVJV)l-4D2ulf2Koa3Z$^v=#luM?`cBlOKpv+UQ}xOu(X zI!pDzSd|!LFU8@nmpSa!JAIs!T5T!AsGroUy<&B$kN zXm`#}hbL#JZk{=Mz&U@$XUz?Nw8dYZ7Q@)7wSUWbTlbg#qkQmVW&Y+)^yQw``gXRs zXA+w8H9z7^lsTEpTKE-Ae@*e#y?6S#r^L4}j^&ym{zjr=}oABu}#KJ;nSH^>N6zuT@{-(t%L)z5Q2 z-+4rH7kUS83{Q9M*_JMEJHNl9XEy!f*wB@ok8*$WhQ)UNw`5Xo+livj)uWqHoZ#bZ z$k|Qr<2yLq`cBB~o-Oh46M4YwzK`DO;Vp4ZKUZ&F56!Hdyl|z~_N})S!<~aQcky8I zJSh~#W%!`q!yjiK^wjhu%+csSnYYCWoSQkJ>eCHzV>L7~+IM#3E_bt!Z*CX#_1&Z3 zzC&|Q=5Mwu-kZI6dCQzhV+qrI28Vc4cmMF;XXnY@CH2L)1O9hVYrXovW@VhcVrv(~ z1Kstho+4MmWAwAtAC72w-fLo{Y*JkYrkg9#SGysP5bvFz7lSRi{_k7*!e$*l(R{PB z!%u3iX^YOLIM=jw^9km8F6~UJK9nEyuV!*~9mfNv5A4lyTTXA>dU5NRW>n0Jn>BOi z`&(n0=4oHpXPNmECCnw5S68#RCvL$vX4Nl+G3s$3bwcR@H)ad!L~N25y|^}2L! zZo!#2b5G7TKC!r`pSE?&ETSJjs*3x{)_u)V9Z`M2UC8dP@czZ!nz3|V0mhigaqfmq z;SkPO-OyqaZ*Qqp;1KxHtm2^a%7?W0s~J`^PTRKBp5#koePyq~r#(AvEk7Wa88&jt zq0IdJruCgNEAdYa%ia5zCbil2*{!2m<^n3Tm-(($p8M?fc>TJg3k+QJ^5iSyIH2{_>90@gC*!*AZE$u|jCo#h;;5FpVowfH_2@ULPU+qY_iyUk z^09qeV!O|vDCcd=&X|LOF=M}ep)79Ave?ar>8Dkz-z_k3(p&PwU&Lv?8LwlbXAE@! z^&Yh~^*cGkKU*s`qh$8NzRM-(z!?PdVrn4UXQS$$M>os3OKY>vwC&JxuE5y|^VH_! z%|ZU4x$u><(YLn9cXo_Tt|CuavClRa>#iebT3~}STJk`C*k$!aq~$}M*#nMxX7R^N zi5cgWTF#4_QMk7{sk@xikkyXV>BRYew48U{tM7pqsxRT5?1vuB3YcdzZ?aSCmUlX~^;`K3IR&Ea%rXvJjwKyL3$j5)-=6b+pLmjALJ`!8v*T3Az*Km&n`IVh^e!aYoo7-kF(Mt7RVA znQwOG?j*W`GjdVf+ng;O;^XF0-`GBWt93_Svt(6S`Xi%vDg3@W%?~g4F(d!gzSHK} zpnIA1$vE#{GYd>~*nfiT9+dKPThQ!kKf6 zIp_B)GdtoHPT+jkm*c*FD~p>`9eDBfcd_{JUG4wbt=F~8ZJw5HwhRa44bBg}r3m=C zwD>=<)3f5>^JP~D#Yt|;VqTW#UR9NRh}3EyAMe8>Fzp>8-jA-26) zJl8p`Bh%m3+2~V>@^j)cGt=VJs?9vNzdNir{+%im*M%Dk79Ca@=7`oA_{@rFap7dV zw^(vj{$c$td%im99;_F%N*#ii47u6);r1=<`J+X|$7akwbw`!4AJ@G&tbA$pKI=FA zy9485a<<p`^Q!RIpX}fL zBi!07UUoqI<*;JK8~fGlG&r55xRb-VmVfmmCuJLZ*H?H(HGwC^=yiHm?RPsC8xP9| zzngqFra?KxI@#rxVZzoS!v@9uWwX&aWq;-`exD!yGW)zFkG!_uPsPa1jJ-A+J-*EM zlCb-(^!8Bl-4{3g$&E7>+KDzVWcve9p6_kYcX^wIPQ*{2HP;&Hv{{_M`=G57Vy z{OC``sT=dxx!L|2#fd%R+ecSHI45@HyojFC{XN%pEqB4aEzY=F`+Q0N?%-n5@oS9lJ`~fsF4>$&|7Cl8@$mck%JVj=d-R(6)W`NjdJ5Mkmv=zk6yp56iqt2=itUGe zzAqa+J`0`QjNkpu7yc;ezL1Q^RMq}&6Jxhb%K^-DiN|j#Prke^%o^2PUsbK=e~S2r z#oG3&Zn#3R_R>)H?d57q^~^ucHVz8Eo|#Nf3`b{V3k&zN*^(D0`G>1qm}|Q$e_b-Y zt(Sdlktga!+RJ5%_cOB6f2K#icw@T0yI-5(bBFt0>F~qh%$ecZABy+tMb{+hFZ0Ud z>NW3~4KI+Do|z}?-99fI3jA+VjHjhVGOCqc)_nr%ruuby=(CHRXJp}z=FwZn-CvuH z9vqgwyl(4y#g04MzvJuv%&tT6_bS&ioqhUju@sK2SR~w_DZLl>9p6*d^v%$VcRiBj zEty2Kvb|OMzuL@#v4#H>C&ZDfi+|m0lg-}LK0h{ht*md4P~-z~NBxjX^Sqm4$u|`* ze&2cG)5E&grHkeIykEwK*yxI(_|?_8<$xy_5x-Hb^s?#SPCun;%7J+j8`-#B{z8%B z?&@b7WRrVko3Cl@-kG-5VuCmHJw6?W*ev;ONWRZiQF%#xbnR*t%M6*sO8x3tN%yi? z+((Pu=MVXT9_TZ}mu>rZ{(ENMXT@ZknJj-#bAK74;4kyVOOp4R>K1d-;aZ&}dU-hW zsr>Lq19o25_rE;6IlD-4L_BA+tn`+&{)y~w^Q!9iWTQWBs{c#LcT)eI-%S4ly;J#x zamVk()|SopKM;$(IiKDzeW}zP9?BdN&b**Fzi@o%+=0uys+@ktj4xMjU>jyCXV&R` zw489!tX02ipVqPMfHU@U!V~w9xs%5ENp~g64`-!KT;#rN_?EC%9Rmk{LXxl1*Y8>^ ze0QAs^lu=KL<{rB~U&Ix5clJ)A-Kia2%BQ)EyJzcCW*B`3^f4lk&tT{JnZ*88@ z9arjVe-96Kjc>F0siNLi#rl1dasN=%JI&;p?m7H$=(c_+a8-NlY?og4`pL9H@n)s; zxJg#JcYO3iAeV;Ig`>qj4#j$V;8 zn^fO6b@=o?OV9At+5D%g;L8#2?x~l`|JI9%ZjtwHmLAvc-!EOnaJu5wcJ}gOpnOK( z@$cz!;qtMKlk(Nw{_*L)-#O(le+WDOmKJ~8&)?|IA@!B@VvX0dGaqT6H!rXGcT?`a zEV_TYIoa=3N4%_DVv&5%GyXU%n$<2Jm0w>MUtg^{!Hc`YgZ|X*H>zrJf7$0(`t%pY z*6xpMot9mT6YEx6bI1OoWrk0S&uo<+zOfGO$@!@G=Ev$~OIr>d@E7&}oqGOl;%;ll zNSAE>+FbCxS!PguwRv@6`Li#BMts0?OiZn=-ld}+n4VgpDrHgvtjd@?bjo5q793FJBKj4grS?p z)#i`S|FT^39i91IElZP=e<}~(E7aU1Dc4B4wX)J}l5fAh<43d7b7S1s=UX#F^yTw9 zGreXCSML8ygo0E3`Tc!o_dng4gq~rsM$3@Vg8sdABk;0yEx`qZjJjsCzMlDc1PL@>2Ry8 zb9VXtx}AA5^Lt_6!}~$q`S-W1`j{+npJeeF>+~Hq?EgE|ReNI`{EJ1`Ul+UY8+uGn zOR`M|9d3~Zy(fM7q@0<*={KoWuuq@KM(6KuFgkqZeR-n3q<1`;FL6KJ@k#yqbgQ0q zeLLvvo0$Rkk6c|H|5vfJOX?2Zkr%FBPW|3JiWNJA zqAM5solR8V-@fIZoG+#Mm&F9v%=;D(#TF~tu9zOTX&s#BtGBAls57mXgl-VnHO;)J z|8JW=uALO_)m8s<2J|0k(YasslU39A^Qz6fAxS=-zP=Kgsi| z^71^*eCFT7ncsD0!JT~9OU>i%i+y9U=Vt43o2GKcMm^boxM<)yr6+Pw zodJ2b+UEP~@|msBt2ckUa*WjZ7I8wYM?Lq}@X?(a&Qa(O!zguTHE(||$0e8hS=|}& z%h1zwW=-wYUhG{ocyH@VNkxC^nqP};9bL3C zH)js#vRJGhoVx?`DV=ZoQ|qc~rFt*s8jna5Y9#JUaZcU5fw@KXa`zj0cjS}97UH{WY;@hwMeoWiz=~mxJHNbJa<6vQsSk4lW>fnJNH?$EvJ0l0q1<0nk-w>|1@W$?y3go9xQiwc+cYrEqC*qq4`*A z|CU)9wNZ7|H-#kXvbrRhaM%R4K%Ua^8bn6ooGacbVLu4hJgr7-hZ;V68Xo$koDN^6mDo?L3wY(kw( zU0AJ(pVGB^Jm8AGbhGLWG!x;TBIlshFz=~OaYMcNJ6ka3dDUb-)w(%d zJKwD4cvU!RZbV;a^Om}=*&}m)Z)Rf^M3+M;flapKf zwqTta^j)1A`e*0b%|dQgM*glm#$6QZvu|y|O7h@q=EL0+t}f~v<#Bxvcc+gAc%3y4Lq{R~3voy_oMjr#~})<~c5I7x{{_vd%=BYjIBTk?BYC z!Iko$JqI1L4SVL_tBFmn96FYQH);x(`sxzT_hGx*r zNSbTXn_DGJ6x-csW#)*j!cl#Q(MIPEzUK_Edg<6VU3SrX2#q5 zIP{dE%#iRw-EQ-mq#u$eOvb_W;Rw%_HlN7!2wU%k$x16 z@pbOdfHUIL$HPze(7J0;Zu!(Ap?MW^IS1CIP=8SacAkAs3+6au?2a_OI=qR^dnX`X zwpi8jm5TDqx5SOh%3A2x9b|e;7gWzQAL@+jRxRgWeBMi2<_XpJ|1{v}W7Tt49OPr8 zmNOFiq2}+z26Fr46$X2H0!>BokBIeh{Ia$a)qJ$ zR~g>d&to=Iz}wGlX-9o$f%op!M&Txf}8=+45f3^IPs_ z^mXbC`Zi*^KByRPhMJ8!$M1dw_@>8X=1C6*hMM8QGufCpASY0V(i=5{A?};4nbp!$ zbce9}{@vI9o)FY~*v&0%^EmnRVBC@7ER9)+1zKdB)vlX$a*u%-GH2@F7*ogl;3(`| zw$ADj;i)^--EVbNJaF3ZD}m zZ{+eW60r~`#yQN_$QSH~zViF?KC#eDoja5D5aBEiWQO{PmU|~=we$;N%#!8b<_6vp zJNB&VJ@)qamiL0mAC_r7wZ#YjSY^chTrdz8TvSbh4?4%>oU0f}f9^9gUnKtiAx_Tz z#4I+6Bkx@l8*y~@5bMb@w>p-Lf)9>3+MO}|`FhFV%oc3GF<_urO+I_XSJXUD&YI}Z z`FFnZ)FH!PG5MZ7#7MK3FdE+$SH*fW4vU5}?9;tgH&vPZPI-$tDt8^=R{Ts%V52y< zIrvRmVhu0?)UoZm= z3(Oke+xRE{-n7q?w>ZxN*UTNl0Dh$ofNQ%C+1fhU*3XyCdFkb=0gCzm$>uVi5Phj4 z#kxbD{Hp5s?j(W_W+mR7C&}&fG43yJI(K?hInhgon7mG2NWvxC?==Q{f`u1Ve_Nz| z+asL&V)@r))sP=5_AQ!(-hp^e{heP_)A~qwZJtbS>V6=zvAgBRo5W<+O^fE7{r<2z z^=1UF$Oqwve2~uE$>c5r923s)Gc!VDx+fbo>wWuB@qZw0wMeXY^&;jrJ=aUiEDp?i z4jN*F9_gmVRi|jL%tp@$XWpK-?G)=?zb9EOOEri5{C@woq38Vly!^q=M{OGxA6517 z!m^`(R*6}l2(if2LrHsi^KmDaeX2R@EnHR%_*^{wRpnw^<;&|NpPn|H*{}8S7=-x{ zbr-cmm3QMX^ZT7b8hH~tU8`r=E(zb1+^2_lw-$lcZBGu#kH1~+e03d< zhw7$v>GhO(-z!6&Z^Tm%$`{s+3*S-x@vXFUSf9K{R=VxriCgwPUO2=KXAjI6i9d8G z$J;WA%xO3yI&gSLcIrbh(k<;!E;@z4|V@rIXn`LJzOrNyajiUUyR7u3A@Ba_@W5jJzCGg$(;;pNfBz6)`cg6ZE$#IS!-I{= zlGaX>n}iFy$E)-!e_W67u|5@+517K998jLD5;lD{x!1D&HGm`=wH1gU79A_wSTo$-nnvE@KCz>eHMD^;A=al!%f<2 zy~<76^<9$h@OJyG@Zw(~n7#0D2(#!_=#L5FFT`H*-EH9iH-aH|TU2MSD zjneN9>G>6D{SE2vkb#Np-yZGWlWrW7U9{ThbpxKiJ6m$b&pjS%jch>EM zG;BW5ECe3py>{k|^p52b-j#7>S=6_Rgx>ci2Ho9`d@tL7PoIlln-$fYaOcSWMT(D9 zPd>Y^(1kZkvToXt!^y>8k`~lQx5`TOWAqQF+Jk?m4>L6Px7TnL=XSTywrN_mYTpnJ z*1Rlv<;|OHFi&wb+N{zvM%jVhXbBkK;tI;d@P1&2fcD(1ryyg$9C0|>oqFeTp z@?T-jbw$A+#hH%kDR;HuG)Ijy%DBZ+oaHaYLcMYKZ(cX!`q<6S^1x3IJY?yR z;jcwGwyzGlTh?KQdv?pc58j8Ozoz!)UMJ@q#4X$1VQLx7A?qu90ug%mc-V zWd{AJ0hnJgd$C{k1qan2aZz8V_OG^vkE+u;V+2dpz+k!=WWJ>CgfluLduq#kp<1E5 z!kni2qE2h6r^7Gx5Yv#(O0ZEJh95fPqekLv?hjjPX1JFe1czax;xswsz0c^g-Ce6rW4_ok@!ehe7vd-F@7ZU_O;(G`;2dgery8j zg}OoJ?QqK3y5XGH&IJOw*K5?~sv#RWaPUP#(1HQFS5o7I}ILXD0asox;g6FBI$llZB2ps%A`1^|xmg6Q19Gs9`|i zUD_ix3$;-=s>ba6g?78k&0d zH2d~7x;HQfHsPsia`uFLavNtw++FPZn@N6cDC*8P7)#IQjoHn+!_lwT$)Uq5hX{B@ z(*1g<>#G^qcR7%nq&XtzIGrP6pYm$wLk`d18bESHMYEZlNOzvD3C!8m;Z|bvh zl2cpGy9$sXUDeG-^EEiNT0$O z{pwY|hZ-Im75BskIOCkYv$Sd!rvCU9|5E$^a-9J0!qRIp)94(!*kLYUhxTBM6PM>@ zClB^0_U+Vice5V0yOd#m@e_=>ZJBgQ;A{jCxP zZ&YO1w(mWud6>CbtLJcs;+?}@^Z6rMdfNK-mOjvEOXpN8xP5s4hy69v1V`Zv9bS@r z;@~G*Vzl{x^B?*)_6;_>3x|x(Njg9AnK*#=lIX)a>k0?i2OHftJBO$9Y?O@4B;n&_ zgrieKofHN=Bfn7N;Ct$Auob^kZ=^#tAbn?NrP-8cP`4MaoVRk8f4Q&@w&A0v78A@) z!A~*J?4NVI`xOWI4BJq@|7>~R!9_kg#O3vya8Z3pGXn7085np7-_`!@AuH93(>r8u zFwwj$Ka>}W8F2Jz{W+f}7dsUzp4qR>uanRDZCLFN1~JQ-oLA?8>S>i*6)?}b{*p2*v}qqR2)=)vYh)>7sk8wGA4egZck2o zLg%-ab&6Sh!r6Rhj7eyoS)6xf_1FD9oA5b$;LgpT5nmJkE(~MNP1=)^S|5v!+0$4L zaYxLD!sY|ho?Eu|9HOlJ+UGhM;oW}v!s4?$aG!8ktcS<$f5w|(r2U;LR*9SUhG7;i zJ%7l9>yXFu$)Ef@*2SGkyf+K|^N@eS1e_EGs3ocmoe|&qP0u0MbV3Er9hw&1Kco(G zcG8)r`a+TZ9pzHuvpSfbrTX?~v&FX!*!8Nc^A$y**OXx#-W**b9rClIfGUmX8l zHhNqh^TFhD$Litf(Vdbf<(C(>;O+8#7mW6u$#Hx(`u+IlPn#-Mqxnkuq*rlF9T$hb zFciUM@FN@>2gD!PhMazU7vq%!9-3|5E@@tzmA;}+d3jRGf40jr$9zJcV$p1WI!k(J z_|LD^xt$Nv6NWGNvi^uX%c(a0dQ%=I_xx(Q`b7HspP?fC)_#6x8vIBxWaLzQ1xmdl zEBa8;{>ve!TGNlR)9)s&d%+GVPQV5C;o#di;D^e?-jI!&ul3&>(jwdcN;$n*617}h z(_Hbc=?o9mQ=v!s@8((QYVDfyg)`FMSOd0$_a`YEoiEn5_<-GJy1hfkemNKDTreMS z$AWnN<-RA5AztuD?-GOsa0oKvwK%((zRxC+xsq>Zr(fx3?-y|vTm4Vn>6UEIc~^Mp zjv2EKuPVMew}>;Df6zzNQF&53;@pm!h@=Sey_aCv{AGW7Av~Xy#4v!FL;fos5$kk>i`MTMg zKE;^x+H0}!(LsN5ipBe$E9HOqn$FvLgBG1zP{Y9o)rh_pXHn17Gn13T8T?IsOx`H= zm~ZfYQ17BUCBF8(Y?Cj#gV$Mx*HzPCQ#h47?YwhAKk!XyZog3GHA(u`B9YrhzSH-+ zynGvXc76%dG8ap}S7xPZz|RkrH_mofN&@=BWmu>8af!8fjXVHvqhoV?FjOp_oPCx* zng_sFzM5xzKCJmw2e^FY09 ze02FiKHOX^gf(N{3uBxGe%gR7Y~4H?E+ekci@PGs`>3zcAD-deW$wf}IV>=LeEpDn zFFeHKSC!G2J=IGyD=ioFYwttw?r3?7Tt=;Gl55JJUz3yvBUAb0k-D`s*&SB%A% z@fUI8m3@x9P==>o!*I=gT59AS2Je6awaxvKh1~Yq{oB- z?jBOhfCXkgAQz01mzvL3yTD1^i>Y4mzLxg|s;{V*;4*STI3ve33qXJJ3-)0@^+xbv z+{eDi3GrEeh_kU5`3ZiaX2M3H_AC>PMEj6flPc4hOd)$z-tmdc(7B$0Spo8pOCF)8#s}YC1QDzGs{M7pk-0lHS9vr}N{{N1KAVry zGft&Ps3t8=KvDA{eyvt%9^W&QP};){*{BA`iiB{>N|WQM@OEdJXwusk{QOAtMff z)49u9&P0Fo=3UnC-FaO1Q2lRMAhPmdwY71k|NTQhLa)Mmyv@9m+YEs3;Te3UeZq^( zg~1p;`2J8@F8$Lo3S8KJ=!M~B_zTX?2mM-(fnSU^if_;9iSO%qoM5}R{rL}Q{jZHK znT(`dVbG%-83xIF-9toI?r!7%awixH%kdoN6k#r$Q9IEKJfbWf*3h5c68T_|tYx&( zD+e5P?Ue8v|bhObC_tk!3hdm@8eCNk( z@+s+&uKhgX=%a&;{w-hdF4o>;JH#$M34Jwn6`Wr@#u+@jywn*XH5h$e_@cLs-^g*) z3}7z*`hK6l7T}6mU$s_Tm&|Gw>S}C`->AW>tKu^5#?hnjdpWw;4Hx+u`Q*D~)Tf?K zLN=;TB^J`5cOLq^eWquL*a~Ht5=(CVD}?#cw5EDN7*S! z<#Lmr%sia&R)i5})XdnZSV2a*W1piA&mQppwsdF~fqvxm=0}fceInocc>kwQwR?YO zzi~#`<())yctre6JTwnG+UQ9`oNyP1ujOOt<%7;FM#{eoB1`e;!0nQ7s53@sP2Fxn)*A8%qe-wk`%hy3x{bflK9UW+5E38@E*9k9;l@NqV(2CdJmz6NXFn=a*0 za$y*RC&5Pf1Rum(+%YXrBA+u+@C!#0e_);Gr~7$6=;ZK=)2P{=F;1xS`hlO34}YZp zG2V}S#xvsGe2~qW@xgnpZ}Bzqkqw8zYxv-ATQ^l>;m3HUJvDEjcJZO~htr6O&Y^fF z_JrT77n=(e^Yl4HLAfukCSURS=2+kaTu{Rn_vj9a@@@9LkyMRC?%@OQl!&mU3r|X62*y z7x%(1J+pcQImJR4h-*#cW2RIAEZ1wqKrMwQ88Ts}L2A(Y^9D6Whuh*Oo zej=WW3w%)QvY-vlMz{W+?j}0K;nZ7vot#Omz=6qV!BA(4)ivM-{Kcu%)y=ec$2J{0 zCuL5^`3ijycmTWfzr|BFs+YzWKVC*Juf{3N6MH_-B-ZIgIJ1L?T5M&~cXvM9*U`zy zWoXfP3V9Pw`q-dD9Ml<7KZ_l>ov#xMsQ4l^$T2|{`er??0L-tnE~V%VllbsPha~j z{aUR^9EABk7dEj2b1`a#N3>ulS>^in5DylsaAdQdY@7$mnfUZrJKSpE`J;`_KiC}m zV0UWc>{V=}Lpp<{Is%#t9`2vtKsM)@D;J%)YV(lAB;J) zpPdDR>uL<}!1onno_>;4D-eDpaq*wBZKRBKmEgOXc_$NI& zhrVx%&)_;{uha_2hYzX2(A!7Tqn?0ySvZXgIQL;c^uNqyvGZ}7#7q~A(VrOa5Maxm z16R}khQT-+KYSppg0W(bud~!4=tY&0jgk*vyP(Aj`JjAWO@<%i2x=}kBO5i_1z+Bt z24RdnS6iWHae`0tHS&=SkC_)IaJ63zT+MUfYT_WiEt`O$le&zvBXa(+59e{$M^rt$~bU1bOu)SUY>hd2uImwqhX}oyBy1 zRvxDgChzA5zPDJ17m-n4P)$@E^sY4b5Qq~ngAV;WHp&mxD{xVDC-G5zo1gM6{!Jd( zNKQ8H_vSC?5VnY|bm@nD%GcZwR{pu~$FA6>B}V9@+}^XQhp6R@oa%W4ml7-FPW%tI zGEt@f2&vhQI6;SMrSnI*CeHNNkcd9y-=ln64>)SBP7RW+(5snC{Rf`Kr`X&C zW9Uy#0q6Z7o&BXhm_x5(JwLObVxe4|AL`FL6ON18AGHo#My!{!y*}CK4-Ykq2Ycql ziF*foARio+Be73E(1d-P-zJ}&Og+V~A1|Z$ zj>oWlc?KNyHF65_T#{Xpkq&>C4&=k)v9DJ2YGCllr~9TU;Rz`-G!@p5#q1Rt?v)dWPwA zO1Cm(H9WP8%ko2ZN|%1kH^pQ2Y=#<+vPJRAY?-sc@{8TualC^r=tPY2De@C>PtREI zQ{8o}DPL4hSy`(7{~dwhB_I1^}g*SWww`@~(^HScUQgSK*vTOR8C3i9}D-PnK{8~OD-r^kgSs#f0 z-217o2K)Gt{uMk^6PLHE5x5iZn51-focRs+{r)mP7lYjStDY$asV)0#=Lm5%XJGWK za42~S{D3p6_t+YIms#Li#(|J?7c%Z}({YOv9# z4$r~YaO;;P<13SGoQv2c`L-Nl8vDSH=N>7(uN0RptyvKtF158=i;4X&P%@A^Plm)67q>5a&uTpi)J%S3A?BKw)R4ONxb)5 zxG-7W(Q2>e7AN$W-0iyUAfK}w`xFmf)BovjkKxbP7~;gj1DEkR=9~3A%;M1D7yFgj zDqPSUlG6fN498{7-MpOon>{|25d?Edy?_Q*}*oQOx0U z<2fg{YtGl#k2vb@#R}Y-Tw=ce^FebVuuhzv)iSflj$k>QA){aWGxIoddf#X4A77L; zely+at*TZWn@^q`hdXoN^6XfQ9r0`Zc5b`;kcEo%le0{4<{1OVsY8r7;~ofn?Uq3| zo`0;9KHR5~kj0rM@s{e*MsW|hy*iV4fh#&sjHl`bz+TUeZ+Z@~7`CWYV8_mP;Ntop zd{C5vR_a)6RDH&r8vTuZflK=A8`}wY-;Z~3sCkI*VuklD@dY`(*u#E21MWp0C@K!Z zz>&|;AHFuDuNoPRnigE5Tltk4d$B^jo*wZuJXL<;nQ@s3p2Kl>Sm0>-UY<$)c9nGO z^WnH!9r^SG#6tJ|n*$nqa~BP`J?5HhUmV<~Pu)3dR~0p%{=y-4z#m)<#=t~51pJh% zdOk7VeQIiK?1Ar1WK7)u`t7~Lj?m#>2Xy)4;Ez`qi|v$sGh@w0$6nC$dk!@)>y`cb zB}1GLC*}U0Lv7xDjpV`C@HG8#{T;q39ZA4Ai58Y+~RT>t}`sbNV}PZ@w#SyII#Md)l1%p!O<``V4wh33m4?d}9-4F6kTMh@JQye;svr#h||{^GCA+IQwJyFD_v(H_K}D zemn=9QRl-!wobD+iTEAP_Nft~DAf7iR{f07n2k4eaS)ZLx+fKm7m+hh~& zvYDM-JhSiT{sVm9d1W;Um?3tH)FP2aykpJbx*T)nsCR#quHH%(Y;^6`#&aq9dovLjJm5hglF*- z`dP1k?d~M`3Z5goU7)@B`ueG2;bVi1 z`WkxzXT(FjU$U}ud8vQ1Og1X#+cM4}F38-}?D?ab6O0klcsU;=pT3oT(kX)%o|*@K zJ&DijZ+_QzyLs?IT-sef=F`W0+hwp-yk3uR?4d0^JU4&BV#F^t%2quiTYwd#jgB(P z3271k!DsL*u?f%jeoov59^aD}!wqLN)S=B;yH`Oh#JlmfF?V}*wzNiQzG!n)_vXiD z{Vqsj-$}aDhB)};c+GeFlMDNszx5UO_SuW{FILS;C!dRlit{^W8SeSnAS)epxHxbe zW_;L{J09ghY!pV~a4^WdX7JM;80Lf7sGQ>O>D|}zJ2OIVy!Hv+*=!C+Mb+)?&SS7q zGIY_v;%bZMD-ZPb*R{8JyBfE1p=OBrpB&?&MpWv(b^uh=q`GYQRzXl)Q?r>0Rz5Mu?;ALF|!(us``3UhFB@ zru~LFo<;3JKUS^4-ojCJRyc#hkkOnt>>2MU{`-IBTYj)_@yEXD@$f@+Lv?~NPKhMoyo=Mj$K%KA#8;X*^b_kI54qMviS_pDZgNA z^b2e31s;P7`Zwdb1U1J|_aj3X@fVMkJMsa&EOSq6hYj%=ctc*iaaPOM@#*VZZ1l%z zQQuho!VKJxvRZXzH3Xl{XD9fqkIF{bgwMpa&DHB;tM_Imojj%&G1V;}`T@}y*?zp*yMM&an=ZPd*71B34E z2OffZ;~Msg{o+abn`FSB;2YW4r~Q@>iW6q4@IX1Y%o&cVAM!ysLx=j1>IP7Pe~2w+ zHhl(rV4rddpNq?wtF*Ujy85;-#xsscaqa)fNEe<}?(2uXp&!17J!da;J<+|K#Ao5R ze(-a9txn5E#VPyErr4H#Ghcy=bR(X+J3tLat;u|a{;s;Oy7G1D!1JhwI2-St7&U0z~&*T&zDE@LFdZonm@HjRC841BI7y5Kr=b+Z1-$@M*UtapWx_d^|J?mgw0P+gJxd!#ncTwBbml12uHnT zMD1e4QT9W3BZ|65VP4+kx!5Ed;D0bi?Vf&d4m}Fb0#EQ6GTLXDgERU&oXXdG2K7gC zZ(_SSV2eK0EaYVD1@EwLdK<6`c8>9NlSX+ zbE6y^9q0Mr4E>G&=I;K5d(CF#DdW9Eu*ANKTb_Z8Y{?lnx?me(&UNi8UxO+53mL@> z9Z0%`V|+sl=Yw)TpT*|czF&*EIJ~;-Xrm9eb8@?pQ^HU(irs9~$&a zb9`^K(Xr;p=6tPK?^$3TKg2ck@nC`ampF;5*)RL6j!a+dl6>kF7qoC3@_RopG{?8u zy*(3q#6j`LXR8C5$umdj+2`eiV_wHfM;v`TpW%mU7d$}jJ90M9#fI4c`}A3C9$&@H z$>&@nU9l(F317^}sC(Bu5nm-^PyH(ecgZhEX=%2C+=b-d^)h9>a zUVq?EzQ!J_L3lP;II+K@AhOX%23+*n)BQL4-*}$_J*%Z!Y(a0rjLPGEkd2ZL z&mfFb>Jjis?MdDRx7fbVRwMDb~d&WMW1FaJ*W9q`@xUR zGOEq!Q^=dF$()h9M%joT^y4$#*I@RLjf${*oL=!K_&n-Rj|tA)GU!n40$#xxp9d4k zL7p+z&&;Cc*(o0s`|O3in#2{}%D?blxJEv*(H}YGr7QO&{M6_9UThSOiiPuL8Gk-- zQGEh&)^q4RjCsoXN#re2qm_!a@+J1G7c73WF`OB8UOz1I-85jn=Z4FE&>h^xJLrb2 z_MHvugL}S7EF>cx`q~j^Rvh%jF2x6O;-_?=uHh5$XwRS*r^ZA+`t$Q|`n?Va9l(r9 zoS-Z6jW+7-cHVD?%ecp3w0*kqWIh{LVh7?qe}p@ujAKs0E=TFc*%I-7A|si^cne=- z`}P4Iuu-$txQF;oPBDyple`8Vi!*BEW*X>_AG*sz+%VVe`Rt{=*4x3U*@9Tl|MZ*S znC~MtnXUHBd`4b34`)Uj6}SKYHkvUFKj@Tf^lSE8oR(i%>KWv-7Zdr|sJxJLxCZ?> zN681-v9I?G{NGdqndB8P6y}(_H&4wEJOKZ~$9xVP6)Q&m;Esy529B?GgL#o}tZ~l6 zQMNGR=sn3WPk($?eDm`}M*5<+(GN{Mj(H?sfsf9ZhqXJVslW@4lA zLeD`yi;VnG4B;1ikw4QP4o^N`2S@QSm>}NMqvh8yM&9P@*n)gSuS&m@4&kSmC=T*L z&&U@%gFYb}op3;QN{9S=o(`Y%I313?23!q~k(=;AvhyzApB=%wsceM)$cD?RlakFE zF zN#_Upk;#SAv9b}vs=C!5rJ*g2iio>_c4gkkUtcFSix zx4Z|Ykm6mLv3(Y*zb_U|Fox{*U#zzHA(_c&CR%PS9`HH*jQ`Q0*yud0*>paQ z2l0P4Di)fvwP1{V@cI^h+#?TqpVgk>M`9oRw6F*}C|{ZvC;mO`9mys*N{9AKFP>+4 zUU6OQRhq(GZj}DUS^*!VQ})j<#<^IvQSWLP-#s45N+yF$=vU9ePvd#RET`_#hwm zxt<>v((4~>bj-tG*#9fvcz+Iigq`ejv{Cw-%yEx*u;B%CIIj5y-SI(kL6xHE0!NIm3GcN*tq=3$H)+gKYF2gm%5eE1jpg#R#-K4FbJqQr*B+bDh83$+71 z2r*$|qxRU`qZxTNOy6d6d{23USSW8IpSm_5WLLPOy@QWr;LBq@i-g_+GUh2{$06vN zZHb@k-~RcWc{$UV_fGgFer<` zYU6YlDIbrcBUhtsZCexYuFqy0^gQ+m&4s9qvQg1qk7CkC8*^U!Ao{UO`^QG1 zsqe)`{XJi_zZN_4=e}OPKn^mll1$=-XLBP6d{tNTwfsv?qsB{TI5s;aA0K32Vu^S> z_65c}C+TgpP&(Xjh_fS)U!w2s-UoB8V|{y^MYuK_9eeI-!hC=16^^rOWSWOGqaJPd^T-P`si|@l2Iv*``v{Erl?Snj{_DDC@8U49uk-wQm7Mta9wCHEQx6k6S ze=i=hQFR3}k&!R5S9ikWSN7YUim&1*ZZxTdsE17AgugSxVUO*(y2Xg2B7`-mJ>4;U zU-6ZnO=985xk)SDkGaK&r@m^O{~{k7<%7-?;-u_Se^%T#qu|fQN;Zw>*=HH4Sct!j zGw{y!g7i?cs$l+O5}|L_<%Eq{@xkdJM^uTefzt>df(%z~r1ny;D8vq+q(d^ADHgwQ zW}hz>ixX^gUcGMPfotQszK6YogPw)n$GIgoI!3}V=N;$r!~psc{m3@r=xC#~=*Pql zVU}n(V$H~3$NMps%;Vg>H)@a$asJ2KsN8yjGxKzK*-*zY^JnTB*4k71BHzM_@H6;g zsT<;O-WvsL;fCiQb6&BY4k7XwC)5-lpA*_^bGMJzq0hj@;Sh}TpII3;O3$MXml*bZ zg=Auru)zsfHtPAvI3f)BOt8;M#!-j(=u`TRZr#%}g8_c# zM{JEf(7fs+J&6hQMn?aQJ~+-ydlt9`BiT7#1Y5|*M(I-=vY%qCeSUoHkc`*2{Oo(t zA-m_>WPmg5Zp;Wr`RLV;QAXZ6J?IZ}wTEz2A4%_=AM!mv<2UTcr`Q`lDAtLEY8P@} zzBtajlke{XSL1{J-H4;B4>IvXi~d##W1OdlwZ3-r!Mg|lrnj-GW-f${I$uBbvGFN5 zLx*r|VyE<)K!eUk5A?LAvB&dWv^}|Jh+H_E1y|L_Sb`t=$#Por6#6h^Qzuog;Da!R zj_sd4^Y6v0sqm1?sBH_KG4!v!T4#)rGG*9kX`L%zgCkaRSiJl-CM;%_3+&2zfN8H91 z<%IA`eUx16bkyNkbCplXjV>_w0v+Nr{LbEw`dcbXBj0GFd;#yr7jbUbVyR=WESS#T_#oe9>vX6NqlU=; z#0{Jfm!pG;59+m(XM&@6k=i!gVxzFgk5Py7>M~=zpKuxeH|marqyF4avuHN@`Q(7~XH9C#K7WjZY;?SPg^l{` z>jw*+$G0c-dpa3$)LkB;+jw6I9G&oP5_;AVL&tYm!ASEvcs08b|Kw{hhn>MXIK@U_ zwi>jYja+1Op9ddgQ})}}!6o}89^hu9jZSLHY}Ea)?nqr|z&<*f)DBsw1#kF+zRx@z zI&;Sl>CnF(`3xHyv2>iHp=-FoH{qzgpeypw8~gG7`K7<}nS2oMSEGeJDc>|pGV)w!$j2FFHejE~24nmlj#2RVXXbzYPd|Jf z4=2~?fukqRv(bfn9-Lb&Bp**Cqc>TK6B8R%!*u3voSlQEdWLFkZ~<2p)7U8AWeM&s zCm$V>QB7+SC*0cP8Sq^Bg#Hd+W~KI!t&Ci4atFkCW)d5<@9cEMQTHW`x&3IJqJ)zq z<9rkw_SN>BO!PO(w{*U__^{9Li0zG>V?66%&Ue({RXx#lJ>BgC&f-aS)_$oA(AkJH z^KMw;bMyD{u>z=riFnWb-rJ z!FBnAeSqxZ#Hd5_G7xmEJBhpeUM6RQ~q_2U#e1RRZQJo<1;pzcH$8#tAMI7YsK5vw7)j=*j5C6#}aNT*irZe&r zAH02#O-v;t9~|SvII}j9Z=ydw3}?g&Hp&OdH6kg#O^0I+IpT~r3eet&G=8l|>N9*c z&Y`ZvSKu7ojVHg%4P4*T=p~rfd~B#4vIY59UCY<)!o^8ahe+_$wf7(C) z`86Gm_Xo)7#~F41W<*e)HOfc_>}>LbY@S(69(B0zpesH{E{nagTb~6BWXqm^)ZsXX zEMBPfc_J}V?uyH^A@(iS%b-Gvbe}E`8^%m2X^Rr z;V3i2U+P4>iSBt+4m&dBu3}~+an%44-4SvQJ}eZ!lX6meLy0%^Ki0|FsnK{p6qgn1SuUK|M|b`1*<2!H-{Qoh}@LBld!y1xJH@`=dE z$ULXY<#!~%e_=MCpbtF=PHw;9lZDj@8kHBVJ6$hRzimDOCyZtoR}Vj<2(j0o6@JMZ z_#b`xZVdPld*k4vY7+(37pqy)Cc)=`?CR`TMuGh@<(u{zi=yV`|g;>s9pI z6xvy_W+(sj;;bB0CupeNq)Ja)k4{yCR7#y+HCpc@-d+`%E7;Q?_aLsqa1X7ncgFCy$r21r|%dO9py1)rDl z`9K$)gQiYg42>3x*UQw+h_SexN+Gp6Wjy5|FO@wM=H1M$L;HtsR%q{Y9PrVpTr?)0 z&hLy@|L6I9)cmg_Wk z)FNZUwK?JWC@nyEF*IMooBiri)brvYB40IXoIDdIH{&>s;vimR#R7mz1Qp*(|^5V zDDJ$ShvKNdv}=^X^Ldk#r%`%_PIV{;yAG}WxiyZiXUD_UEHSLF>bxCiteB1AOC3Fp z{_s*~8Ti-l+Nj@^+Xr>x z%=bIDS$#E6!Sl_3sPne-nri(iR0h&%*HfThF~=rwsUzf>1wpzViO{Ny12X}zZ$ zRDWnRWcCQ3H48cDT!cL4(OUjuym;a}G%9*Dq0VzrHyp-GwE{AEC=)%Oc6k?#>X~>Y z|2}-Y=4zJsswc*QBWoaz28f<|@4Gdp>cnqedi#TyKkH@m+iA4@hEcEP?{eFIjh`pT zn~O!YzC850#wu>GrP0nm5vTGu_x1d={aizlmhh=&$(OX`$jSL#?>#XNYUiW$XkPgJ zYy08#1+Udt@uiRIgdU>Lx)C>V#2I{YQ=OzAQ89js6gQjKaj&0#axgFb)obtK2Y0;m zXwetPCwIF>WcYkm#N+2`gsgea8BhnEkLt6O{^)=4!Df?>dQ{jk>GjQpF1OXw(D})n zzR#qn4#L;E8ccOE;iR+b;8Q0qhRu7gpDFhArApWf>?)>X8?mnV2u-{d+!$VXkZFO}ljHN$9$pX1qUn-k`vY1BDl>PE-re)HCvOflbkcuS$~ zPosKV*NSnIWsNgz;k%x+wF??@gU-$P@p3(osC%C8^3p!}QX0MY2gkK>gwJ*Dx`u(h z(vUoZg^!A%%^cX8%&jXw8m&$|IcUFKN1cAXHlO>{s4*0EXd;R7$%0tJ8 z({}jIo4lW<^T7F?dalpEvCxw9SH(b`;05BYAIe94p3+~v&~Z@5j~)Byv!jfM_MK^# zkLm(#Po403Vr)IjSc^k7EvL9O;7^TmuS3X3IZzrsXUe10LF;l|ug3VlYE&ljJD-iw zc{}E?_>#reUaT>}XA56-@N!UGtShBa*IKicgLs6`d;$;U;MIwzn>npj3vcENV)%jU0lw2Z207EbdJPowlAU%d9=qgQ`ROFkQ;e!G6u z=VAHu`L;Z!nVV}GcM*A)Y`<%O*PjHKlG4SZv*NBAgA7sIRbY1EpXb@Tst>Eg$qG^z`f zf9kwCalKme31dlT^(5C*o<^(n@KNT)k3z3jTnvlf)j=`lV{**=o2S4fPh=x}<)HJD z{`;qM!oPX>jPt~tgHsHh=cf*uFUcYrwdRR8-i0mLY`DXt{qpaQPv~WuFNs}s@SAr$ zXiqK7XP|3F0jVtXcY4fc(rNh0LAhdHmPYxEtI-ud!hdfcVZr+qiAD>b6FjN-0*W*C% zk!kebUomtQ;%dbql!Mo+*&hX18?Xk-XT%Ub9z(a*-R$2;TJJGWc|K<&d{1uc$=!Gb zJzgKv%8D4)H~T*xE`s>;v%ggD@$I|8cp=3*SQI&a^f zIVd)`!_A}7Z(qOZD_eiS8I3{)U*Bcn)e3o-PRrVQHIH_jPG6|@I&L5jVdOb{Uau<7 z_@F>zzO{qIXRe0^U=;%ms4pp zbX1x~^U^X=He&0JpYl;_Yij+EZ@$AQdjIfnB^x9 zu>Et5KJ~TZ^j_~-cWUjICUcmlUrVE02EOwd7**T)8S#ZGbVcy;)|`+Z@O0N7;VU?& zRlkX=9Hlw_Pd7BmQ^XKP5%jx0)&Ipq%=u)szW(ScEOm&j{ico9Wlp2z;c3)(KYN*0 zNogc}*4V`GG#WlJq&bhn^=VYjzy=|#<{AE{UW$vXe>56G_vVP|qwB)s(SDn2^5$yK z#n8UtrVXzxF2<8a%fjk}h_*I!IS5nHD}H|0bJi=IKGSG*qU#MAOB(I-f+>`T@&d8F zdSwq*Ak{(|4Pp4?ptU<1^{SpzFZ1&r@IG7XS$8r%&pRJYr}d*W3O^ifxVxL*dDPVk zkE2xg`EJ*$vAzX|cR#BY;S;|+##r4vj}JIfWsTb$B8QQK@Tr4+{+D?QjnV|qQr}(a zr}{(teRekOtAD@Y#&7qf)Y|$J@X08w-5KLz{hSa600L zoY_A3+G&(7VdSCa^XmNNp#91*IZTt+1HxDRN&DvXoC5F7%O8BOdOhPdUa_jeV>>U+ zN1?B0Yo*cSZ;thO9f@k;VT4wlKQF)(9nq+K6GIqndK=!OlcW$MpbHws*L4qYmV>AL zt|RwVqcG;9dKs}5ow~Imh(8D)jaDlzj=rbSdoP>oE70gg5lUBxc0G`KMx7C!@v0uE z3wNHMe1sWx9H_siQ9LzIxjsJs(&xy1W5vHdq#V3%=9v@X?0o-Rl%`<3TKK8cBJO-X zy+POFQ477M@%YL?U0Ged>OGBAkVe0Iq3K*kJ(`V1X%~L4rT584^$#>Eislk&^te-p zX%BaN)br0{{EV;W2lb<(7B)VbVylK1!&7vc#(`R7EY(6?w=X!ucN(P;-Cnicd45j} z{mgr)i`RN>yjZuWw&pXR8l@TePiHjMeBvv<)2NtSFH^5p{9eOc;%OTQ{?DWKI(6%3*S6ljl&tO=QCxZpZ)E6BqL3u9Vw z48>PYJDqtgy2wYX z^|aY61wQkza`0Ij?fAxa`5IU9V5)Yu9vA!@GE$WVCTq+HB@OdjCpBJnleT2$w55u z5Oa!Zp({rnx~{b#79K~})%tIL(x`eLJ|1H}$oK63>I5xT>o11SHPh6l)}3gy^FX1x zN(iI6#M|=G-dkua_77(__#T~>fBnV(aSelcLq20vqL;_O?lH$Re@mmOls@6B4#Fn~ z%~R9~z0Bh?A_y;yRDbek&uKpKIj_Itgon>MQuB$=82X$15w*S`EQWH_V`hW{_DnEg#^KIS3rx*R^orAPwpEL?f^JwU9p3-&wIzI8d&#oL4IV{QssAc{$ zN2f{WABItct`;7~lnNo-l*~uXujLy|;S<9j-#i8hm#K#@4-a8|JU*=vnAgNKM=z->Qz&zn&CIOX{`3mf%%$w1E0A(^xYhT zws_v*tCxAMIZ35?OzUd66N}TvXAZ(?ei^>z6Gm1KmOlyteBj1fD zgfPM<2VGC1_v#y37xO$*f73$inu{{2<1UJ z*nA@Yx_&ft=Q7uCms`cen9pa5U~|KZ;HeaDkIQG&dh0V6MHv`Ab;4uQXy=2g3q?;h zQfTu*`9l5nNf8%AIcRG=((xtpr9RKc*i{4ZqH_q{(`>HS}{cXRK2=D`S`amg9urJ{V)wU^a;QEb!i(y0H}%d|G?x#Cux z2xS_j;O6M!bqdXEE(^u5tqc^+Duvf*4c`hAW@VpyihZu>BJOz3N4>u-d>6mgEI!ZI zbgbT*@?BH&>bx9mT}_-hBk!ffe5Uy2p?3~K4$6qfXUaekq@(5&=c5?bua$k>U!5-pJMKZ>9GP#P%Rnin zysSRHIek8=GMvZUe4_J7a1cIq;#>x{Cl8C^#SgyY0|GI8t_@iP^O)*j=c1}}+*`cl z9si_Jc#TXy^5o#113;r8w6^@2gT`mvY4qwuD4`Woc~PAxCgN2LWmg!*RkVuW-N%Lh zh48MWBopOd@r&oH6IZV~&sP1jeR_@pQ+Bncjs2} z#_IfO^x}6;b1{T4HlBDtc_{M^9}hJz?LDdH%DliB%>Tp_H{IyM?w$P(PQ0;qzMdXFpa5T2T&V^Cd^QZ{4XJq{Yu( ztr=mp{wuyGCS~FI4D`+K524@l(dHDN5ezAon@@Nwo^Ko}RP@9zeE7aPK^1f$-}t83 zK?q-UP#@p1D>e2sdNK69`O-7z6&2j&qtN+!YDGTtON<^-t)S5KX>5Lj&;Q(L@5Z4P z=A?8ApB(JmkMmJ{(P;Rf3*ULn)d`Qs3x3p~vM>*o^IlW_=N!c^YRu@SLU? zwl*VT4@US}lPL!~mpF|=6hc|(XPomwJm4dZo{w_UHtSltC9h1rHgsgj*?Nc2T z=kplZclyj{?s!GHclXATC+XMfXUe=33ZcJyjQl+x6)Tu%vk1c1{M%S)#q;b--4AEBLKFrBNMDYop@qhU?rVgn0}k?|;AU&SCo9f9N#fc{@BM;Ob$)X2dKvSRau7xvyN3=hNn?6v>E;R=;`yY z?)w-R17lzejDayQ2FAb`7z1Nq42*#>Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%U<{0bF)#+kz!(?Fb2lJ7#IU%;P+?X?|=J`|M1(_ZhZaf_uSp~ M^?xJq|C6u(0no9T(f|Me literal 0 HcmV?d00001 diff --git a/PythonClient/multirotor/speaker.py b/PythonClient/multirotor/speaker.py new file mode 100644 index 0000000000..c3beccefb0 --- /dev/null +++ b/PythonClient/multirotor/speaker.py @@ -0,0 +1,37 @@ +################################################################################################### +# +# Project: Embedded Learning Library (ELL) +# File: speaker.py +# Authors: Chris Lovett +# +# Requires: Python 3.x +# +################################################################################################### + +import pyaudio + + +class Speaker: + def __init__(self): + self.output_stream = None + self.audio = pyaudio.PyAudio() + + def open(self, audio_format, num_channels, rate): + + # open speakers so we can hear what it is processing... + self.output_stream = self.audio.open(format=audio_format, + channels=num_channels, + rate=rate, + output=True) + + def write(self, data): + if self.output_stream: + self.output_stream.write(data) + + def close(self): + if self.output_stream: + self.output_stream.close() + self.output_stream = None + + def is_closed(self): + return self.output_stream is None diff --git a/PythonClient/multirotor/stability_test.py b/PythonClient/multirotor/stability_test.py index 9612892dff..ad1da803f9 100644 --- a/PythonClient/multirotor/stability_test.py +++ b/PythonClient/multirotor/stability_test.py @@ -55,7 +55,7 @@ def is_unstable(self, amount): # fly for 2 minutes start = time.time() - while time.time() < start + 120: + while time.time() < start + 300: state = client.getMultirotorState() x_val = state.kinematics_estimated.position.x_val y_val = state.kinematics_estimated.position.y_val diff --git a/PythonClient/multirotor/wav_reader.py b/PythonClient/multirotor/wav_reader.py new file mode 100644 index 0000000000..74e3bce185 --- /dev/null +++ b/PythonClient/multirotor/wav_reader.py @@ -0,0 +1,158 @@ +################################################################################################### +# +# Project: Embedded Learning Library (ELL) +# File: wav_reader.py +# Authors: Chris Lovett +# +# Requires: Python 3.x +# +################################################################################################### +import audioop +import math +import wave + +import numpy as np +import pyaudio + + +class WavReader: + def __init__(self, sample_rate=16000, channels=1, auto_scale=True): + """ Initialize the wav reader with the type of audio you want returned. + sample_rate Rate you want audio converted to (default 16 kHz) + channels Number of channels you want output (default 1) + auto_scale Whether to scale numbers to the range -1 to 1. + """ + self.input_stream = None + self.audio = pyaudio.PyAudio() + self.wav_file = None + self.requested_channels = int(channels) + self.requested_rate = int(sample_rate) + self.buffer_size = 0 + self.sample_width = 0 + self.read_size = None + self.dtype = None + self.auto_scale = auto_scale + self.audio_scale_factor = 1 + self.tail = None + + def open(self, filename, buffer_size, speaker=None): + """ open a wav file for reading + buffersize Number of audio samples to return on each read() call + speaker Optional output speaker to send converted audio to so you can hear it. + """ + self.speaker = speaker + # open a stream on the audio input file. + self.wav_file = wave.open(filename, "rb") + self.cvstate = None + self.read_size = int(buffer_size) + self.actual_channels = self.wav_file.getnchannels() + self.actual_rate = self.wav_file.getframerate() + self.sample_width = self.wav_file.getsampwidth() + # assumes signed integer used in raw audio, so for example, the max for 16bit is 2^15 (32768) + if self.auto_scale: + self.audio_scale_factor = 1 / pow(2, (8 * self.sample_width) - 1) + + if self.requested_rate == 0: + raise Exception("Requested rate cannot be zero") + self.buffer_size = int(math.ceil((self.read_size * self.actual_rate) / self.requested_rate)) + + # convert int16 data to scaled floats + if self.sample_width == 1: + self.dtype = np.int8 + elif self.sample_width == 2: + self.dtype = np.int16 + elif self.sample_width == 4: + self.dtype = np.int32 + else: + msg = "Unexpected sample width {}, can only handle 1, 2 or 4 byte audio" + raise Exception(msg.format(self.sample_width)) + + if speaker: + # configure output stream to match what we are resampling to... + audio_format = self.audio.get_format_from_width(self.sample_width) + speaker.open(audio_format, self.requested_channels, self.requested_rate) + + def read_raw(self): + """ Reads the next chunk of audio (returns buffer_size provided to open) + It returns the raw data buffers converted to the target rate without any scaling. + """ + if self.wav_file is None: + return None + + data = self.wav_file.readframes(self.buffer_size) + if len(data) == 0: + return None + + if self.actual_rate != self.requested_rate: + # convert the audio to the desired recording rate + data, self.cvstate = audioop.ratecv(data, self.sample_width, self.actual_channels, self.actual_rate, + self.requested_rate, self.cvstate) + + return self.get_requested_channels(data) + + def get_requested_channels(self, data): + if self.requested_channels > self.actual_channels: + raise Exception("Cannot add channels, actual is {}, requested is {}".format( + self.actual_channels, self.requested_channels)) + + if self.requested_channels < self.actual_channels: + data = np.frombuffer(data, dtype=np.int16) + channels = [] + # split into separate channels + for i in range(self.actual_channels): + channels += [data[i::self.actual_channels]] + # drop the channels we don't want + channels = channels[0:self.requested_channels] + # zip the resulting channels back up. + data = np.array(list(zip(*channels))).flatten() + # convert back to packed bytes in PCM 16 format + data = bytes(np.array(data, dtype=np.int16)) + + return data + + def read(self): + """ Reads the next chunk of audio (returns buffer_size provided to open) + It returns the data converted to floating point numbers between -1 and 1, scaled by the range of + values possible for the given audio format. + """ + + # deal with any accumulation of tails, if the tail grows to a full + # buffer then return it! + if self.tail is not None and len(self.tail) >= self.read_size: + data = self.tail[0:self.read_size] + self.tail = self.tail[self.read_size:] + return data + + data = self.read_raw() + if data is None: + return None + + if self.speaker: + self.speaker.write(data) + + data = np.frombuffer(data, dtype=self.dtype).astype(float) + if self.tail is not None: + # we have a tail from previous frame, so prepend it + data = np.concatenate((self.tail, data)) + + # now the caller needs us to stick to our sample_size contract, but when + # rate conversion happens we can't be sure that 'data' is exactly that size. + if len(data) > self.read_size: + # usually one byte extra so add this to our accumulating tail + self.tail = data[self.read_size:] + data = data[0:self.read_size] + + if len(data) < self.read_size: + # might have reached the end of a file, so pad with zeros. + zeros = np.zeros(self.read_size - len(data)) + data = np.concatenate((data, zeros)) + + return data * self.audio_scale_factor + + def close(self): + if self.wav_file: + self.wav_file.close() + self.wav_file = None + + def is_closed(self): + return self.wav_file is None From cb46217122b98892dd769e990993bc3fab0470a4 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sun, 18 Apr 2021 10:51:56 -0700 Subject: [PATCH 14/37] fix pwsh support --- build.cmd | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/build.cmd b/build.cmd index 61f798ce7f..2476ebbb02 100644 --- a/build.cmd +++ b/build.cmd @@ -42,6 +42,7 @@ echo found Powershell && goto start set powershell=pwsh where pwsh > nul 2>&1 if ERRORLEVEL 1 goto :nopwsh +set PWSHV7=1 echo found pwsh && goto start :nopwsh echo Powershell or pwsh not found, please install it. @@ -72,13 +73,17 @@ IF NOT EXIST external\rpclib\rpclib-2.2.1 ( ECHO Downloading rpclib ECHO ***************************************************************************************** @echo on - %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip }" + if "%PWSHV7%" == "" ( + %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip }" + ) else ( + %powershell% -command "iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip" + ) @echo off REM //remove any previous versions rmdir external\rpclib /q /s - %powershell% -command "& { Expand-Archive -Path external\rpclib.zip -DestinationPath external\rpclib }" + %powershell% -command "Expand-Archive -Path external\rpclib.zip -DestinationPath external\rpclib" del external\rpclib.zip /q REM //Don't fail the build if the high-poly car is unable to be downloaded @@ -137,10 +142,14 @@ IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv\SUV\v1.2.0 ( @echo on REM %powershell% -command "& { Start-BitsTransfer -Source https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -Destination suv_download_tmp\car_assets.zip }" REM %powershell% -command "& { (New-Object System.Net.WebClient).DownloadFile('https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip', 'suv_download_tmp\car_assets.zip') }" - %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -OutFile suv_download_tmp\car_assets.zip }" + if "%PWSHV7%" == "" ( + %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -OutFile suv_download_tmp\car_assets.zip }" + ) else ( + %powershell% -command "iwr https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -OutFile suv_download_tmp\car_assets.zip" + ) @echo off rmdir /S /Q Unreal\Plugins\AirSim\Content\VehicleAdv\SUV - %powershell% -command "& { Expand-Archive -Path suv_download_tmp\car_assets.zip -DestinationPath Unreal\Plugins\AirSim\Content\VehicleAdv }" + %powershell% -command "Expand-Archive -Path suv_download_tmp\car_assets.zip -DestinationPath Unreal\Plugins\AirSim\Content\VehicleAdv" rmdir suv_download_tmp /q /s REM //Don't fail the build if the high-poly car is unable to be downloaded @@ -154,9 +163,13 @@ IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv\SUV\v1.2.0 ( REM //---------- get Eigen library ---------- IF NOT EXIST AirLib\deps mkdir AirLib\deps IF NOT EXIST AirLib\deps\eigen3 ( - %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip -OutFile eigen3.zip }" - %powershell% -command "& { Expand-Archive -Path eigen3.zip -DestinationPath AirLib\deps }" - %powershell% -command "& { Move-Item -Path AirLib\deps\eigen* -Destination AirLib\deps\del_eigen }" + if "%PWSHV7%" == "" ( + %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip -OutFile eigen3.zip }" + ) else ( + %powershell% -command "iwr https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip -OutFile eigen3.zip" + ) + %powershell% -command "Expand-Archive -Path eigen3.zip -DestinationPath AirLib\deps" + %powershell% -command "Move-Item -Path AirLib\deps\eigen* -Destination AirLib\deps\del_eigen" REM move AirLib\deps\eigen* AirLib\deps\del_eigen mkdir AirLib\deps\eigen3 move AirLib\deps\del_eigen\Eigen AirLib\deps\eigen3\Eigen From cfc7eec7cc8ec1c73e967a4b18fb4ffcac37a352 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sun, 18 Apr 2021 12:30:56 -0700 Subject: [PATCH 15/37] add update_time to mavlinktelemetry --- .../mavlink/MavLinkMultirotorApi.hpp | 20 +++++++++++++++++-- MavLinkCom/include/MavLinkMessageBase.hpp | 4 +++- MavLinkCom/src/MavLinkMessageBase.cpp | 3 ++- 3 files changed, 23 insertions(+), 4 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index ae39c32fc5..d2be5f7183 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -112,6 +112,7 @@ namespace msr { namespace airlib { virtual void update() override { try { + auto now = clock()->nowNanos() / 1000; MultirotorApiBase::update(); if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) @@ -122,7 +123,6 @@ namespace msr { namespace airlib { update_count_++; } - auto now = clock()->nowNanos() / 1000; if (lock_step_enabled_) { if (last_update_time_ + 100000 < now) { // if 100 ms passes then something is terribly wrong, reset lockstep mode @@ -194,6 +194,11 @@ namespace msr { namespace airlib { } } + auto end = clock()->nowNanos() / 1000; + { + std::lock_guard guard(telemetry_mutex_); + update_time_ += (end - now); + } } catch (std::exception& e) { addStatusMessage("Exception sending messages to vehicle"); @@ -202,6 +207,7 @@ namespace msr { namespace airlib { connect(); // re-start a new connection so PX4 can be restarted and AirSim will happily continue on. } + //must be done at the end if (was_reset_) was_reset_ = false; @@ -630,14 +636,23 @@ namespace msr { namespace airlib { { std::lock_guard guard(telemetry_mutex_); + uint32_t average_delay = 0; + uint32_t average_update = 0; + if (hil_sensor_count_ != 0) { + average_delay = actuator_delay_ / hil_sensor_count_; + average_update = static_cast(update_time_ / hil_sensor_count_); + } + data.udpate_rate = update_count_; data.sensor_rate = hil_sensor_count_; - data.actuation_delay = hil_sensor_count_ == 0 ? actuator_delay_ : actuator_delay_ / hil_sensor_count_; + data.actuation_delay = average_delay; data.lock_step_resets = lock_step_resets_; + data.update_time = average_update; // reset the counters we just captured. update_count_ = 0; hil_sensor_count_ = 0; actuator_delay_ = 0; + update_time_ = 0; } if (proxy != nullptr) { @@ -1926,6 +1941,7 @@ namespace msr { namespace airlib { uint64_t last_hil_sensor_time_ = 0; // variables accumulated for MavLinkTelemetry messages. + uint64_t update_time_ = 0; uint32_t update_count_ = 0; uint32_t hil_sensor_count_ = 0; uint32_t lock_step_resets_ = 0; diff --git a/MavLinkCom/include/MavLinkMessageBase.hpp b/MavLinkCom/include/MavLinkMessageBase.hpp index 734594ae9d..570e0b654f 100644 --- a/MavLinkCom/include/MavLinkMessageBase.hpp +++ b/MavLinkCom/include/MavLinkMessageBase.hpp @@ -135,7 +135,7 @@ namespace mavlinkcom class MavLinkTelemetry : public MavLinkMessageBase { public: const static uint8_t kMessageId = 204; // in the user range 180-229. - const static int MessageLength = 11 * 4; + const static int MessageLength = 12 * 4; MavLinkTelemetry() { msgid = kMessageId; } uint32_t messages_sent = 0; // number of messages sent since the last telemetry message uint32_t messages_received = 0; // number of messages received since the last telemetry message @@ -148,6 +148,7 @@ namespace mavlinkcom uint32_t actuation_delay = 0; // delay from HIL_SENSOR to HIL_ACTUATORCONTROLS response uint32_t sensor_rate = 0; // rate we are sending HIL_SENSOR messages uint32_t lock_step_resets = 0; // total number of lock_step resets + uint32_t update_time = 0; // time inside MavLinkMultiRotorApi::update() method // not serialized const char* wifiInterfaceName = nullptr; // the name of the wifi interface we are measuring RSSI on. @@ -166,6 +167,7 @@ namespace mavlinkcom result << "\"actuation_delay\":" << this->actuation_delay; result << "\"sensor_rate\":" << this->sensor_rate; result << "\"lock_step_resets\":" << this->lock_step_resets; + result << "\"udpate_time\":" << this->update_time; result << "}"; return result.str(); } diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 6a76ed9521..2e1d3a4dfe 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -316,6 +316,7 @@ int MavLinkTelemetry::pack(char* buffer) const { pack_int32_t(buffer, reinterpret_cast(&this->actuation_delay), 32); pack_int32_t(buffer, reinterpret_cast(&this->sensor_rate), 36); pack_int32_t(buffer, reinterpret_cast(&this->lock_step_resets), 40); + pack_int32_t(buffer, reinterpret_cast(&this->update_time), 44); return MavLinkTelemetry::MessageLength; } @@ -331,10 +332,10 @@ int MavLinkTelemetry::unpack(const char* buffer) { unpack_int32_t(buffer, reinterpret_cast(&this->actuation_delay), 32); unpack_int32_t(buffer, reinterpret_cast(&this->sensor_rate), 36); unpack_int32_t(buffer, reinterpret_cast(&this->lock_step_resets), 40); + unpack_int32_t(buffer, reinterpret_cast(&this->update_time), 44); return MavLinkTelemetry::MessageLength; } - std::string MavLinkMessageBase::char_array_tostring(int len, const char* field) { int i = 0; From f94377061c36013bd725a09d11a673e19bcddd5b Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Tue, 20 Apr 2021 11:14:33 -0700 Subject: [PATCH 16/37] add requirements.txt for pythonclient. --- PythonClient/requirements.txt | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 PythonClient/requirements.txt diff --git a/PythonClient/requirements.txt b/PythonClient/requirements.txt new file mode 100644 index 0000000000..e329ca18d3 --- /dev/null +++ b/PythonClient/requirements.txt @@ -0,0 +1,3 @@ +msgpack-rpc-python +numpy +pyaudio From 92f3f3f67f5bfcedc936a93f43128789d553d7c0 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Tue, 20 Apr 2021 12:00:28 -0700 Subject: [PATCH 17/37] add info on how to use mavlink logs and px4 log viewer to debug a bad flight. --- PythonClient/multirotor/stability_test.py | 9 ++-- docs/images/px4_debugging.png | Bin 0 -> 246137 bytes docs/images/px4_nice.png | Bin 0 -> 110696 bytes docs/log_viewer.md | 2 +- docs/px4_logging.md | 52 ++++++++++++++++------ 5 files changed, 46 insertions(+), 17 deletions(-) create mode 100644 docs/images/px4_debugging.png create mode 100644 docs/images/px4_nice.png diff --git a/PythonClient/multirotor/stability_test.py b/PythonClient/multirotor/stability_test.py index ad1da803f9..98d80a0e26 100644 --- a/PythonClient/multirotor/stability_test.py +++ b/PythonClient/multirotor/stability_test.py @@ -38,8 +38,11 @@ def is_unstable(self, amount): print("{}: min={}, max={}, mean={}, stddev={}".format(self.name, minimum, maximum, mean, stddev)) return (maximum - minimum) > amount +print("### TEST STARTED ###") +print("This test takes 20 minutes.") + iteration = 0 -while True: +while iteration < 10: iteration += 1 x = Numbers("x") y = Numbers("y") @@ -55,7 +58,7 @@ def is_unstable(self, amount): # fly for 2 minutes start = time.time() - while time.time() < start + 300: + while time.time() < start + 120: state = client.getMultirotorState() x_val = state.kinematics_estimated.position.x_val y_val = state.kinematics_estimated.position.y_val @@ -84,4 +87,4 @@ def is_unstable(self, amount): time.sleep(5) - +print("### Test Passed ###") diff --git a/docs/images/px4_debugging.png b/docs/images/px4_debugging.png new file mode 100644 index 0000000000000000000000000000000000000000..d4309ce5c6d863112083c9a180042efc2f908395 GIT binary patch literal 246137 zcmeFZWmFtnw>FAv@Bj%OG&lrz2o{0`cL@pZfdIi8f+kpSw*+h48*iKh5AKb-TVvgQ z+50{3IdAsa+2j7a_Z#0BH3n5hb@g1&nscrx&+1RF)D-b>C~%OFknogV$Y~-WVd^3w zp><=S+~3hVbn&|XgY2fM_#CNxm}&569*U=@*R4>Qaj~(ZDAxgh8@qglrRNzL>q8U6UQR}-jDpE#;K$3Yg4c!N-sWXk@6(ACw6qFC_hZeL1D8cn`S&!`!gfYq^1!iE`-!0FaJ#kM8!y;#Fnj8*k| z1ycHk3DR3mA^+_({4qV!w8-?xl!ish-6mge*qCbxaX2_brjni;+2i^c;l{Rx)CA?1 zd`oPOPfSd-)IJJ_K(p=~r+NL5mnDBcclXL6Ek?|vjlyh2K!vWaCp{_f{>M(E46=-w zy?WE8G2WN0r)NVe7x-%B0`{5;9A46U)3E$x+s;D9kGq6BS+T=R^Yh z6Iw`tV)B2yz>}1x1VLPZWq~Q~xKODxB6+tN5u=(ae4=I<@?Pfm8mbZce2Q5?}*$n|913&V(J0KUoeb4C0_+G zG`OsEhR1$$FKJ)r+L8695HBI3#!CvwC$5q!ZD3>Djf+L^u+Fz&H20$RgE9nhLa1`PHnNjb5^L*pc_Lvf zC?}_&zMhx6!n-e;vKu|6kwsOV`|N@g9Zgu7vDaB=hR+DNe@k{N`C$_9lS~0A`g&U) z?}@<08YsMT?lBh)UdlJ5FbOvWw#jdH9-%4;ygcZGEvLZ4W zK`j!*K1MVSq<5fhb~9xue$)#1hW_uhecJ-9wz!=-2SLGttjxIjrmtEbPgqjYXQC*e zrG8b0}x^tXQJ!IPW<6wgSwG74VkC;rw! z2Zh-R``7-i2Rj;{n)mDdg_yRk29|yp*bB`$K};`urW#lCoB*`cI^G5xx-_)bSSSXx zcBt)*1^$hC%qUu!LRsoa(E#5KzTTox3S?j!@tH8;z@6=@nU$Y znC+*2PyQ>p#v|rT=c9Pp8fblL0krf?HY%k;bC=U z?!b@KcUkC{GRvzvANaK$BQ`*_5>#`JfJO<+Y`21msyAhenr~dba{tCFN*fU^7q=hm zA_nkgUSX$TwRc}m=QoPJ9?75RN?wR?lE=pNnSMJ-D>2zj$2ttkalOU=Q2{o9ot~i% zB?qU2BO4pKisg0MBYg`kQrSrYyFL*igOOVFR!~Pj9^`n>)iUNYoGkSTsjsmWXeXxE z8`!EhpBf6Ed|L+d^P4Lmw^=te`SJ3hzIn_3g>(37=Gja7Oa}P0#Ocea2?;Q zqs{8!PI12Ps}TS}-##k4QhT;35`I47+B;$4wM6?+od}cUA5%3gDPOmS#ucI&$-YnP zzB8IhbANX*f4nDwLu-FCQQ7g#r*Kv7iTN8tpa!`7k}$Sq4b5n_?ov_>-s4%hTsu_D zF|S=;i*6Qw?;8ImGBKw^ZVa^;MNkT}G}W;qhu|#uZ-Ie5&P8a0H&Xh3r$5ta&ay$7 zneZ{OIBubGT(k4>1oAd&#Pc<%QSz-sToZg?gc*FfCwrs=yEHnrma5Cc@PZK2pG%gP zZ>jmk3eb(x=kn%vP@qQ6G467!obyL#^is(cP8@H`xa9?DzO^DK9(UzMW*-S2&qW$o zP39hcWLByBy_kaMr#vkp9F58IdyZB$8w=t=HIk8H-_r!gu@Ae+8S%@HsI@&Lb6(f* z#e5NLw&@Dh>chQOs}W>8k;~R|)OdQP1zwjFc=^-R5%GhW2z@3eMVR}YjY=o8G#cPy zYqEWC6z}g0rkx7gCHNsMJBfgpD~O-2>zCxpm}J{9C(7egBg%E?7089I|IJ*WC1wF9^=E)(9Cs>x!H9cx z5eIX=S-I7Zl6M%)(kAsy#gZ5btYsK7POv*U0%ire(=%ips>k1zjdlg9RYX8(S%9D*9~7*a^gJ6!q?jT4t$_D3oztVp)t>5b4k3?76lqn#AmVAzRhS^4?Hz{ z10sd}{Q{k%MYw!}h+|uh)(FH)3;>c;%F#dkY+}N+wB(VLB)6Ox8q!EIJ3XQNbzF7vI(3TY(Zmh35>|9aPNayL&+w&Z&sHgk9L(Q2 zid({0VhGg(_l8S@_+h&uG>+I8Jrnr)8#n}>pxTFVAI-)@U2?V{fGskzDKrex%1jQ! zb@bAtVilxZpaSpkJz5R}_mKjxxLb-be-?Pt>M!MQ_j{TiT63xr;XkB`yip0@4 zo76QIc9t%ezh8=w0;3so3J}%Go{=~Xm1u)W$R(ykL^PL|Q~v(Zd9zDdyD4gFf+#X1 z^U558qgWql1r(7AGWDHx4VWqoWuE$Ylb_%gco*|-l-g~TS9Q1?kfyL{Z*({e`W5f) zG`^)cCZ=ZTh>a8uB}qHu^^A{`va%1@@gv5?wj2?##H&1fe2#950!=L&-LUFN3W|>c zcO7EwR#1GWDfN?M75t7dlhbM*$@_herk6I(dh~o7?eE;reYP}8gI2o>-hWP=gF?xH ztXzaqs#`|!aQ&^b^JG~%13Uck@Ze_+%lklc?vg28-X?`2l?C2M&(Oze!l6j%XJyvrP+4hJ9lC%Si)C*r7lwy80 zxsi&wHx1I35Q~g{^(J7y@_A8vnc}C%f1h>bFko$u0%kYnjnD;+QFJ{6>2wJ+Z5?B1 zxT2%U*4->fsEAg?%>ydN*q)CSvzhB^jeof;Dpxq5HQc_)SxsXfhucWF_A7q0?%IfM z*$o?u9aGkPUHXWEW#;9`({UeO3LcRdRj7!$iU|u#sqM$am#y)!zH8|HkKei#XBZT? zVYF&^wBalDXA(X$dM*8ddzw(LEsE1u?g2)pP1R|pPYHp5?W@+A#Rz9yO7p}|KTwr* z3s__BW|nP!68)WHL_$*uLfV?(Fv(6+c&3sNgh{~60w&7TQyeVCQMr#mO*;#-yido~ zg?2M z=(akEVyB-!t*ov!?=joGQ${E|#cHkP5mzPHbbILHMGIbRvLb7tr%V)5yvnlcAHlTv z`^4bSY=OrXMGi%90_&@%zPX=HR-UBU+!yDc+BTEMFW|~>RtJts2d>(rhx6DksW@I{ zl)f}^>|Zz-kf3G@hl>@NsmEh{~h7`6=Pzp>^&zHywz+=jGr z$9nGbgK&(}cT;)~b^%5*B(nbigJ^gFkxo1HLyaxt&@A%4)@8(~2ozf*@OSkBB&;G5 zo(U|J^}pBJe`jba(MXKu@$=8n9{k2?|15Ka65rPzp0b{!{%vygUpM0!kg#Xg>mMNh zV;LhCjSiXeB@XPL#A;v1l1341n`R`?~5IwanGgx0cb)V5tJ_hs!juh zJil2M{>1OmOC;jT+`LhOzc+|~$@>2mD#AYsL@a6pc~s0n`SQMLQU`*14zC+{4mULbj*Y(>Suz99TpiHfRwU2QH#ho-&Kt}&ghVy_wCwGejU>2hD7>Kjt(7#9 zA%8`Po>RRhfA)$k_C-GNR|HO(L(in;Si#LD64AqlPkncREb1A;<1{s%2O{zWz948% z;PCUnJm$60H2I2sZk?4U?vxj+TlPnLdv>gZpVw$0-cTKv7|stpeaQAdQh#zayRZ`<`mC+jY@dF)&fNWnd{E-o_2hN5Nu z)+t#jw72=F8&%Lu(JVTOH{k}8;e{AP{tN-L}(n%s=hl>*47VjT&gDoUykXgy}wKrGFx(goOrA7N?z}8oFb1IiY~og zj0SWL^E~!*k0vXr+v5;D6$EQ6|3gUe-B!gWn;lw-EW%RZQx7RRo{(C78IB60IThwK zzIygv5Gv}66?3hr*vWUWWU2?y!(kEt3!`a^i|=iy&w5z<7xesjzC$@3_&Y7A=qh)yGA9+A= zBw@)|9lB2bPH$*EuqZ8PMN=x^$&-K|VWU46MSb(ypI>IJ*P~!CgxAvpGZfF4Ju%Jp zj~IuSM0}>$3aY1z5ouE3tjR8gr9u&(Ex#Jws!Ku|dk@-7(x*kra}R5dBkBn-_&!SS zVGFApLc5B2C8xZt;wH!}jh8Mub~%&TjKEfXBXs8}XDjuIRsNqVv|Rm^mWJ$;o%4-F zzO3+i=$nIbko|maM2&DQtCZ}u0A^$$LFCDHYOsMm5t^Y=fUEb12Ee#8H(aPKQR}tv zuhuH9$FfW;@$-HATTT7~1B9|6Bk`vI-Vd+5C2g*xo*s=E#cj?Db$<{-duvWFF z;Y;zjSNZ&V_a<=dAw;!{#$4W{K4e@u&eP>&ot)SvVjE72-!=*Xifn{EITNZ?7C#UM z!fInY+IWZca#MGVi-E^i{XYg&mrnJ!1uqwAA=H+x*Xh>DzGaIW1}qo@PHS0SOk7h; zx6R~whindgL$=L8SQ6}RzFLwVmBoQe{qCltVWj%O{*pn{>;u5JPrS5be$xzk$s=xKCJ<(||+go)+Oi-PYaba(VgBanvv#v;0w zd1v4R7n}f&lx=GT*IYloh0uJs)D!mitlC1^`6Z5!X2))ji*h@ZioHU-gVBn9f-7qV z5y`PbK^t9V`wNDW4QG)Lqat};A((iLnmuFo#dASC#OW)}u!h%~0j;u7B6XPiY8W|& z@FVfq5X52$c;0RG&Wt?_a&r{qTJRMScgIo2In$}<`o_e>vFt|ikLcW^Io8)|gW_VF zz$knFHBZX$sD?XY6Hm(krf2ARdnLwK$o2CpLK977UXL^58KS0yRAu;iSf!8TEaCWL zP3Z>;B$eAISDOsv#Ka^!eLY>->{Q;7SwG}3vE=Eyz=5eY(P^)7seM}|9>bFT(IdQ7 z0Xm1kWO z3_w8lza8yKJ|65uWO+&%dgwKTIl>Oy%p}gb$w=5KF3jM2+z~z^SZSyD9NCu^i;7`j z$~DLK8fI4UtM%aIkw>FvYMxc;jUPsgx)yiHiyE#5(`E-ewl6#gy`@eMF0F5xM|p=p z9!pYh5_kLxo5p93CT^Y|$(teSeFM^`#^Hu!33)fYF;K`^8!&U5wFz-65pkg2*1Ud! zYEra0X}8RB3y#+D$BmyNFJv}tJ8^D;1&6VGU&5584cgpabRE|-wx1;l)cA`pH;E6> zg8Yp3>#K|=%g`% z-es45F1j9LXRkNqDz)ClNFN{uNwSXv&{2{xzcmv9tX*BFu;Z1ri7NBf2TL?GP_HBv z92zt&n|`>`gK+Mbx^KH(7CU3m+#!J9*;7b|c@o?cPT{r1vABwHaE4)U59K>8IVh zBM8tN$S1dxtpr*Y{G+-04cG>*cYjRXe(hr$g26Q@+&OIoQ;EKCD1N%N#iJCLkg0Ns ztrnm2g+uP4rfr@4g~n@LRR+(BV2`X7S(ZWLb74IMlM@dUYjZ9lZB;fZ<(Fh{S&g{p z2KrWKl~>74wr~t!Ku_k0A9-=?+2&6_XP`k*!bGebgRJg*9tdn5FibnUZXC3-@Ff&| z-=%G!t4c0u%>Q~@nk^2W3fkUx`cWo5rLKm4AMInozFW3&lbg}cVfN{}gy}i6 zRcxu7B}a>V-b=k_&v?!J$LD;GNgxNtVhRV2UC*bRO>ZDSO)69$cvL4$yxsSHJ;lIz zg7367#Or^fJfik0@wU*h@yEjk6khL1DGv6t+vEWy)W;SG{1M3$n1)^td|byJ{H0{}R_slq zPRQa=ZJiDU8bO5Va|N|JEvrW9gkN z(j(a8+Wg*L+Ou4w;nwOzdirPe%W_LqivVAmuZ&r*h$;IX`AUn@yZE~xadxxl0P>Z< zaGOD9B{wONI9>HH9C--^)tw0g3JNM-&e_Vdb+h~UfWKXSGpS!{qO(`R>&j0B4~X4n zBI{#1wDEY$-)}EBwQFaODu{Ur(W}Rz`Eo|c+xH(w6Rk=>s0^v$r(?yaYTPBpdl9N%U}D=7YV^3Q}E7QRxy=shO8!f3H6 zOP}~o(%R^u=MJaR*#YHHDml95AtcK&rq-k-ATt?W2{6d}1_xI^_|eCY_x4j?&wU`7 zD=@4YLf+=9S#vi&hFDT>^FHBvmy%X{xfuiHxEh@>W=w63|A0)Qx?Wc`a7kI6X*I66 zEx6k=GQBiCooIB+!UgwPTvYZ9zO&xLghDOL6ndDjvn7bEKPF9OWIh|lZMfWJ={iE_ z(tU|3Zoa%uxdodij17CSM#|*BS4y`a^M67pEOmK3#p*BmCNU|~Z!Z?Aw9?i$2aX=b zr-SUKY57wLBZ7uga#nZ^FeKp{Nqu47tfr~){7H*#N$xl6S*@6ACc{>fuDNcw>#JSr>2bHkCE4*h{gik^n5;cnYc;sD5YdTwc%Z7bpP*ZK09)Ow zv2^-odUJXZ((2x7-NQ(W^b;mU<(mtR$GF)%O>Z9RrqiE+B}#cLQ5GLeS}8fMT;TRa z?~AyWJvS%yo`%)15MX(NwC`Nu>@`ag7^i#(TZ(<6h64L}*_{Jt7lx8?M#RKvt8ZPng=EF%m+2fEB9Og_|@J zti}d7hJssR@j!_LfXW_D9&ow4|I^+0FoC8YK9%(80vAEbK2ISYVO7#r^ zz?(}kZFlM_0UQhznR$ZHBhC@d>n3A(an|LRp_eFDnt7j`O|G+5n?{;iNGNT((*(as z-R!NoN>VUWuTza=CrRDNeC)4bb8p@Y;f6F;kh^_nV4@?#<>Z`o-T-+Fr&skeniUCr zBy0L5Dnr8BW;ADdcW@u6g> zre|UgQ0ItML0$In;81Afo2W z4tPB&-z?kbN+MHqap?)&FQFY$pdgF6?a{jAJLI2$e2c1qcHnSqRhqJX^R?>*WOv}! zzMKZw>Z;&$n{$ZBDSF6E*4}yOhu&FVrL{Z&!~cNHw?eoUAqa^Z7I?iDLaRl(xg2MblAmHsLaE8fKg`>BE-tnPwipFzFpDC2Oo0+9WACEowjL)%IL4|5S zyu|HdDg9RPNrY!KQAWIo(vzd|EoOU-J}-uQpR{y*EWzEcEto5NC6NuVdRPBFt`jVE z`@G>eNb$D$#pjXIRME4O_u%gAC@I)x3DYeF|EP(G+FJ5Dcon_LWpu45HIXPt)A$!nEh4IPJ=!FEq;zfu z)aD>G6joIC*eCrqRVccn@39l_R#3w_5_Xt`}?Q-{C!1 zIp5WZpN$vk={Y%qnc)s|=CRE$4nQ|~CgYP#8Ik}waJNb~DeSnh^yc9vanYK>_`K!r zy#Z~%58=!WyV`B-Tvz3NC{E6*T>A^aT6K5batZ4SDc^mN5KH=|jB8vegpYmQCheJ8 z`5H+;YW8UIbarEYE;8=HUD(37q&x3@MdCk8z5%R+mC&Q1UGOtrJvNWe6i4^X5yO1} z1WkoSw)!{8wm*AnCvX_+`=EX|mtXAQH=AL(J|vzTo^cEKhtd z{Gjp$x0sUrO;rtrLplkd!GN*S1@{pXry9qz`027pz{hZW@vX&gTONQ$j=2OuJqZmZ z%hz#PVJ*AMoQHcgalK>dVUnhTM?cM?!a|AuvQlk6Z}0C(zh{~CBz?#FD)~)LLa`|S zMF#E6joIO(`>n$GLAoaO4R@pEcpJcB5g9vW7pzP>+nKQP0yh^WeLzokdMM~j(iIvi79i8)Mv*V6AEH~6|E9iq-+Y)E#wHR98GqHT9arE(Ke73ce@erZ*q_Evctb*oR z$+L4I&PlbSrwp&#+4+3(vCdMT20tscm>cMfy%czdaLfnUzCJdm}nJKv!N-855&4b!CTI&VKR z#DnA%p*X!nST0n~pmY0CJ6|5n@lp|b|6+yG$qeSN9jy;m^NSGqq|JG8$q9!zoK)Vu z!odXN%H3n^-#aIhLGa|4UG9Q`A-%R!-i3k#;{~OVz$bT^hsMWL$63<#Y|)_ z+NHO}n9X%5oUBN2yDt7qzw>q5a@FhWz#p_`z%Rgd-N13FXH`Nypp@Vr_zr3_mAA|c z%Q*6WYl4(dQRW|*on6WS3Vd}ny?1V-3V=wrQbd!PRq4)6q=?roNu0Hhn@(d|DYL0a zR(9SVEt?-L?~_R0A(j@;`sUx%76n9E3uU|=dRK<3z+r7Hpt4%+a=_cRa+LSg8#nn& z)oukOu6VNu)5jZ|(Q>vhBum3oW!5vfg|V)2OOP{7`27!ZZ06J2`DnAVld~GkP_NIW zq+x7W)W+wnqATKJFW~g|Y6+#Pg>YRrFxdXGLcC&<-t~NpiaAvkcpd!cDvnKh6?dPI zcR|v<65m1&QMbFKXzp0JhzOhn?A#sryfqAa+5QqXUEs{<=Fswrk^VV~wz;ou>Qm(V z;)vg^9DqEvg|19>v2k^gG6cerR`DvZ?5?-1szcZ(P;K~m7jDWPu8O1-6fB=9j(TyN zcbyIPOS#~oqd$&YG+X#Kax!6c4Desz5eOiKGciqjWbjudSgtfl&dew41n{YYM;a(g zOfUHa+l08a^Zc2CepZV(;jeJHs}oLkp+gi-c3V&yL;nVB7s2h6SFFw;UL>RjNUdAycAc#dJG z+THnMyh)K?50R)#`tuB;FJJ&fyhK}7C}suCPsS3vxZRlUBIw*BOu(>#$r>9q{4>GB zJ9|zb3j^CR?#YLPBxYueKo2@|zPke<<{$3T1t?cgL?z~sGA{VTz7zyvZhw!ig;OOO^ZK~UnY6EA&b`kxBU;<|`sC~YA{p%dDz8NH<3G3`_zWYC9NM_Gb3GSs&`ZI% zXOC_p=>?8jAb2Wn%0vRct_ae&Sp11wC6kEa22re#`i>xnpsxbf1#p7rxbm=yJRXw_ zcntqhXc}Dk;cFRLRa_K4-xrE6+Xv0eXlf+k*R8A)4jWA$N1xc-r=ou4p#9Tn5?%~CUt1$A#HUoa^$-qcMjhGc^%Vp1&nQz->)lZqPp$j$HTxkf?Yld{1m|aaS z!tSe;eIaF*NR#6mb9>*|tnl7#9AtBh-ihXev+pW73{Q5WSDQPU#Q@#~ z_EUiL;b|Uv^#AOE2YN7%e#sub04(o<9hfSlpH|{Me!B)ywaaYUgHNc9PgR4w z|LxP-szQLBV8)$9>K!#_nTq6#5mNFw{UY6I1Mi-ehEE`VU}pAulA0L^I;+%`P#7q$ zu3uk~ua!C{{1Y{s>+v!NMAp`?cPVlAD9>3GwEA;|TaWnDtEanuN0?eFoIPA*6}5LW z5obwGt-8!U(;*>2p4q%HElt-ThCyWkast@-k25z644=wf?i01AO_ldafNKpzSSLqV z>@!geWVR;0t)>I5e9okT8*pESV@Z-cnVUB3tiyJxo{kN9Rif-SbeX8Wmr^sX`6Nte z>2`7Wy{sDena@PS2X1G$A2e&R+0(D)a>=#Jnq%=0cFGNwASt`@KB_gS)iKAJhp4OG zJ><7N6oLRQev~LDbD8isohlA`zS%6S_Jhvo;nN^CU_J3E$zB}3H$&bx<7P33MrGHx z*szV#s$&Q&P4k`6&tCDrxG-kvoGSi8t}W3$LNA$;tR9ji&0IuT>Rwk&QwIjVTTaU=Cu+$!*Xm!PW1FYS->x;yc>BY*U)& zC<{ZPUy~fMoCs!IN#rLyZO8OyKvdF_uN@U71?O82Mi>ni>ep&HX&9k1H6d!4G7PIW z@3i(HRvdKN+!k0>SNW~8d9@Rre#^3=cu(iqsxPw@v&k!4>iwn}a_bLhRp-m4?LbGg zLT3lEk9C?BJQ<_%g*@B%UB?)V;?T$9sM%v6ns)8lYV>ON>%&ifbHn-2`MKG=#K+_# zy?ytofudQ~Sc4t+L)}yECuJpLR*T=Pho?dpvetg|s+t0>W`?=5sZv0DFj98CQhnHX zlqr&-&M#0lokLf|C;hnLm5oz3`Wb$czlgYb)S_#pM+|4}&W^V+T(m z`;|3aXyTg1`DB(MHcUG|i$}z9tYSU+^0KtQ`UhZMU?(~u0G-S(q~ajWAWWU>+|O=p z?Q?vG@Bl7#7Yi37!b!Larr_O=Y>4V0!eBuD9VYB;$+u)^K^0sfaMyq@4&@D-pYqGXrCQu9kg zZhbY+-f4$=@(2}Wv-yR8h>hW8NAo*OY;?J=%)@s!kfVwi!B2MPS*^~(b?o`UN8*}F zwyWIpgU7j5@9=2+NBWOEGv6qKClh7(2K7_pl;+_SwR~jtQ*&m)x{pX8M{595t zh+>q1Q>ut!`iS030TkvA_aZch7pDbteO5DKW>TZd%}WgK`x1_7SzYjW(QK$%-XqF=ee3WTZB%RJHJA!5-F&;b? zvFpqTGrijMs-LUUSKTtrlmM(r$=lV>Bn=aJ0=$+Bw^aASg%6V^5By)Y!akze2Fx(LOrSTYBz<9h|i2ZR8d5=wnZH(@gO*$d|0L z{rlE(BGT;2RM&KAMv)!zV5Xi8IkB<{5~I9)t^4S8?#@cfD$93G~HFZhzPk=VI=C;NrJ4&z^{~)#kRXjNC976ToPHwx*Trq&oT~(Bww)cqow8 zj7Q^fig0T8kWrnKRu8$XX1d#5Yjg5}Hc6+dwblSAvk5r9({-htrc45#bGWM<=IL~B z09SmfIIFj%Y;A8+j@A)BbN$>hP=|)-dhOE=?m)Q4ye;gxSZ6)zV z+d%I0i{4hfLOA>MN6tHXj+T#jK^;(h<1PitDdnpPE%hv6*WSwE(92U}(B8KDVsG0J ztJH&3une8|adVKjos6Xfp2@A+If=ya5S(137irGo%TxjUA!vCq9VHjqWd!2Z6LT~6 z3;wUxR7!ELMLTNy4}Hydn>t!zio?&2Pq@K`;@$J*B6~57Zn}H10k+kHZBmPTw*#+n zRn^!||7?OOeQM4t7iOvW`lG#q_g#izKz4k74(n0-sV#T?3G@-_o9$yK!JuqN(@J1l z`RGAaA;tYurX(Ho|;qFpz+3bLVuX$jVL%;fe z^%R=yAlI^xav^C1Q)ym^k=YHWJca07@LmAtz67f5b6LDQtgkoDdd(EvzAliwzIs!3 zEjRSaOB#6ij=v0UH@cqxjC8c3QR6AYHrVQ1MW`_A=-CZ7jM>=ZH0rvF4T_ zqWU18)XD~i#A`C$8XKGG>R37}_(W>|g>h!6oU?JmEkUiu_WtOJ3xSOzp(AgbNpZkD zJr7B$?2Ka%EdXxz6uOu%N>8q*Hx-c~k3(sYsr1rb%Rf3DOtbYR{rfj_>6CTbYd<&8 zh_(3p?ttM;U<4u_;_SmeHrZdvqQ~^k7FO1ZNUf@lc!)fpMc%Y{(YfWkI6tk*`ce6_ znuL^pBk;i2+8c)m7ps;Wxf$r}n86Z-fNW+9WVFrOD-HgI9AQq3W|)t7*`vuTLajzm zDuk`OJ555(JWHUd^m{7C`Ma64-~SL1`zW_+Z-tdaMZ%<4Iu7iQic zGxX;c91LQu4NSZgM{ASGkExX~BL1inNN>^8m8mR(c7{kR01sdwH^&EGk^eJB{jYNq zwD7>7#FC09Ti{R1)#+{(%1jpCaLSU)>ObiBAM}0?oY#~r$6ZztmxthF+GyVZ<-bp? zCDf-U;@8G4`OG=+&H*Q$lfwScA?{1S5eK03FBbc6VgG=3bO(!&v_bH-nVUh@;F!#} zKS(i_iS&vLk!HE0V$#7Ke>;SErTj;5>kRGV%CR7cbyyKV3-+xvC z@6X$*S?CJpU-Q!clvmoCj?Pw41D4!gQwj3ie(-<@_4g0|p{?onI6i7r<1?%tJ&A&A~GX#lodAOP+9QB`on9B%AL*sBbLl=bwzi1qH)}TZSH*rD@ z&-BOHe^&_kDu_kcynsO{2774Yk}L+xqLcnb;CmV_OAa%#vZ{C{S#V5(5z^3lsCn`| z!`hIL$DK!^8=h>B0ZEZn5nF`PX04 z?Z3J;hCdk3DF3Uw_KS4|*b@E8$bQqS##@#{#QBfv8DNUS5`B=Y)V?*`!vbl@^+Xc= zZwUcl#9{j2VB|2Z5Ix#oCH)1%QDwTPPp@*rXrB=Cv;O4Askg?xy5eog2=-W(4*!tY`?!V~ZU!~Bxe`rSA6W{f>tkC-b-ed43;DY}D zn?i-*Gc7}x4!Z}!B-0)4zWVQ7GG!rPAJ#A}f-wToA(<+7x6ovUNX44vJ-$zhZI7() zq$6Lkm{)o0JzoV@Y(7%&wYZ4x?v{e^+%NDpgek`xC&2)ZR^E0meiE>FnwR&0_`lvo z4sS?s*}M(G@BQ{+Ck8+aZ991V=eu~W))+o*K`Urqi>JzD(IY+fMe-S?0Sb*;B!p@M{ zu;XQco4Bo8z7X35G%l&f{qq|KJqc>137nLkY5VC$*-eXWmOj;L)O94U1%hhldtgVs zwP?1=eXsBgY36$*_Qc!|l6n_9UA4<~=FuH@IS)K8x0ob3jeEjhS0NSwO0cbmQI&6W zh3H?o|ECe({{VqBcEcN1g|_;$I|AH~2cjN2rBfYfj6H>>(Vr>k5Rbf}m}7DmzPURqk1{dzuJO0&DVKZi%_Js-HKjYuRVI*d#FMz^5p1)f0)Pv!pkJiklTE zxM-w^mh!9TblHO@<8A5f6Xb}x&(1_E3p-gqN-Wjo&!ah#JDl&^Wcs5ndn3ZbT#<%% zinoU-W!#dmA!Agso$FnapNAOdd|_NVdQ${j`<=DZFXx2Vi;oW{3wJj6v)ZqjMcm}Y z`X<^QQ}XzXAD}8HN~K{w0GO8`2O0hhv1_*W_tl?%5IAz@dzen7dYk>lu{&pny9Z<; zul4A@Lmu%d!zAT=A?h+JZHoM8t%O(-p3RCX(lKf>kX!jDA2#X7!)+cN=At zOjVSEjowf5hoN`#N$CzvZX2zl0(PSfECe1Z7{jhcN;><2KobSH0O6ieFmgyTMtK2J(mkLvO-WMuzGW#RfOGf*LFRbN>1_Ld;s{V~9atV;I;p+Sf zIjEpzOy=4CatzpyKhGDzr)4S{;kQh9b&3eZe{=%ylnXXFJ^Q+}YA?2AZ*4*`|DV5j zFj|i$nu~Yb@i1h8yMR zDc=)2*P!+#pBK0)pN>@SHXDlhs~S3~&Ys0)*kD&qhDePhrM+meBHNrW7m6rewSRAw zlw_OFCtMEFJBZ58MR;U68VNFY<1@8qT1ydP|BqvR^fE`4(Y(N2&xxeK_ObYz0p6a) zcq7wkOZJTO%l+Ig>k8Fp{J!UW&L|Y7?GCwIx56fpH$6sDSrf+|F3}884zxX0?;S=R=#{ZYBgWBg3gfv9dhk~PHLHf)fRmwTc{h7+TO8XT4hC?d1Il; zoTaSXs7H|~d}zYzcRH}CF;?-U$Kzhks(^pcZNuI2@VkR&Zwa(ed$+1k%u0TKv+-ze z1&?6?eK^Rh5Ok#;wRf>A<_5!!@tu>IOk%DQxF435Aa(OoNJu=S0=7D1iRT;!%#QuH zfLCxH_CQ2r*EyM56raVdKuZ8>GQva6cH(ySCVRxzOY9XN<}3mJpCB9yeQQO-*BJS^ zV(1sPcH=c!Kyy7De%$mz?_R(e0({oek`egPqH1@$-r{`V+HQ%kZgdrm>D0X1ve=4V z6Yh;#6y+J@!-~f>!bt(!h5WAl}x zc*7f4QfFT3g2REcmObiCZ6Uj-9TS(&0!NhNG+Wb&SQ z&-w|T2j%zA*qduAe3?S#!MKk4Kk1^rP-_zv7*|S8T}RGc&uVL>J%*tH8lsy^z+AZr29^l4x=*xY zMuxs&sERkA)B2tD#Lv=w$l#RkJhyGQ?DKxw?%3dyg7ZJ&uV|<=JJa%a zof!F9%RBh@eUN2Hb6zBL2+(ixjmC&ni6o`U*TQA-T4<|(&l}3&kAhD?T~m_@AjKVN zUee0?PzKEr+zJznJY|=x)AYA9-k8EX{K@ZN^AfIcNS%SW9QmX(CBsmJ5g8E^;5P#U zvw6z&$vEz#1xN{qtq4{^u8l$Tx#Qwf;sie;-?yBHtL{uFdM)ZO6PmMAKlE*ZcGcY|pd@-fS)Q?2v%b`^2ZlGxt9%C@Q)xIq5>024!z@O>EZ+uWkEO1f9y0#A>P1T`kF=4HACrEYQ zayw`tn#hMA(QI&aOS)=X7X@uTIIaV---X?O#@oZ-+iuPnC74F5)>wtZV&Atb%0jx8 zxh<1a-|uqr!(OvAHqTGD*E)Ewcvbg#fkhRfbGQompWq`(7Bk=j*x8#F@&fsgnak zU+Fz*p*9UAA*95UG9sU7pBBz$YcLZvxM$CyJWk#osOU`&zu`8vEecrh&zO6^Sul^8 z#MVYFALY9&mRW*6Oij8xs_mO;udA72SbXm&KF4>J@m&j`*pDpnVif*#zuiuM#=X2B zlZ^;@`n?r#WYQHz*`mg>tN%yX)Nhi)mhAC?J~ESZ=e5rJTRG${_(cm&U9#+HeEm~p z&lr|ue%y?vs1shU9i|D46tNiBuAl$8?e3mrZ! z0RjoZA-KDHaCZpqZo%CL_u%gC?(XjH7Tn$4;hXHa=i5E^+}(dOFGF>8Rln8M)lWYS zek%l7dDj-BZcbu0Q?o>b4DJ+vcHrUvv2kfO&S0n33O;l}kk{eGPWFlD@GdMT2AC~g z*&-->)jmwTATl#V#D(OW{8?e-IO;=E{hc>5MN>c(Ak5*%VKZY!h*hlvlJ&_dHv)>S z^mIL(qtpVI5bs&q(%WlAN_sdgBVOqcF~=X^UQ}L0W>X;dqy2XO@I=jQ!IG6kq3OBp zRio7Od(86d?BK8W@i4qEbmm^?FQ_;Ke=hL64%WK7Us0HH*+;Pb^@K`voe=c9?R6)yPyoySEN3Z$Bbox&|FF^ET z6C6%JIp3CV+U*$iOmW|o4^8uLIEM4Ci74AqueeTZHL|l#B%zf8uvXGSD$Gh>meXS? zo-KR!Y&EbU#z@xSE#hB&NC&`!<=;_B8xSpPg2s#qhEh;#{zyg1>=4J(aLPTfG?ooU zsLb!>1H<9t>PD-U{iZ+91fTqjU6?uLg+b@g)oxz$-C8ohjiX)?RNgWdV4i>n_C;pAQV(XAl27~U4s(Wf1R7d zWrX46jkY}!`<&VOG@0DHpRDt6ahF{xK%I_jrRe5L_?qXvOmP`cwdR%|oQ>~Hdhyb- zyGi@qD3bmQo&5ZWD|>3+ktT4(NEji*dY^)1=c1tTurZZZ_GRe=0{7|M`)zD+y!G|?rfaF!lRN~R{ui|v1(~d4`^KV_ zH<|P|=Gz)QsGd?=sn>lGvd)#Umd4GB6vAsc_n^+}tO9EKbCZX+O_baB8nD;^E=M;K?-IdZXhK&5QI_O-xrc2E*})DsaF` zDHFu0YjdZWjY0F!E<{NZTuLGDA|95P={B&gfHCT7{pJCw!W(LT?1Fq->M$as_qT^ zM;!EbjpYn9xOXH0o0liMS5T*FU zA<|(ld{=j&C9%2&DLbPz<1VO)Nn%7Hzxwp>e)jm3k9VYsGMgdKxc>Zw7Aq9E7ve6g@) z+|-74%?Yrh)FH?CLea9bp@p6p<#j)`RgOmDHm$eo=O(4+`0kQTSW6$T*`xB~gx9y& z0GSfk{d)Y1qzq5@!NZ*yc+>M0oX;PD1&#O3i|8@Cv-j)`DSz*}zt*nLSiLhdHv(`x zc6x#E0|k%<$;nW8YgHws4!l*w=e0Ztzf4Yt2obNzd~Qno6xsgNBVc z>rX6volYPuUp1TDNPQ2k%ow#gk=dR@$@ovNMwhTYY=f^T*uwZVTZGRCLZZ`d6t`|q zdWL!Vm;af?=a?1f|;~>_G2@5@-*+N9>^npv?wA>vQ zDlk5)m+UX|AqQwFLhn?MtDkrR6*`ZJaEn-{p$IJGKQVvs7Lay+?*ty=se%9Em&UF3 z@gK|jc$0|0f~-0}jNU)&-0)^zBjF);MtX6)Gvoi`j)O5IaEpUF%b)%~O#SaYg#UR6 z+%v@kN$F+A7yYxReidcQT>K)vt#uSL&KD_JJb0Qm0hAY zI9Mgy&U~}3Xi@;DMWZCOh0J7PABc2qbr-LE^K&XIytqW6AdSj$D8*id9 zxcSa#o~LYZc?Voi5F=Xvj&BgDP9Nf#fpU17WSLS=Uq5fb*y*@yx8P znR%q0poBS(mDy9paIBsPk~kBI9c&9FbM&cfleN{3pN4WK{eIZY)HkzC8OaIMJKfI7vQuPICR9q{Q|@g z?SOO*XugUQLTFqjj^ThuM~9~(upqxH^))b(wLW1&vc~FH^WweQwO7)0}Oj&%yWk+wV6{%)yDZvRWHDY zRP)$RM?oH0R6(>k7Ma2{LYG07mbpx~4y=uyRQ33#FK3DrtI4tWfAm9N)a1Pv53$z0 z2mf&V3Oq{UAA!9wawp2;K*qP`TcL@bLdI%n?zy;fc=^0b$ObkPIt-Z0W%Xu4A;F1| z#z(LtQ3z8?O5>eMN(yHYjqpIy6F|q21P>yWo>@!^sYoM5C1fEm?oB&DVlw?D0j8Ir`fb`cIEd>*(HeL5bMbOt(W_hWh#l5oJ#p45_^95;hg z@2Iyqna|Sb10m}5PL*-~S5EVB-VV846}ZzWTNF9*pDdz=h9sZo&>ohYZRsshQ=daq z&^Cn!zM%q_y}e;y7Oh)4b+Ea9W2lDG#*9M0k@E; zgn9!mJ87&oH5#|!ni2Th&%v~mq_L|cucUYOil^!s4wmoW)pS<1!k>yX@|t$mkqRsa zeYedDreM#;t)oBbtw7MVfk8}Q9ZkISt2iFNRC!io8rU`7;&9{_a9m5oYVbI{B=1d# zHE`>R+ydLKdVhdE19o|@Z3dJGBRCRHGA2O?sdJ`~$h1KClm^H}Yag#-W;$YA@ zsLiTg4lZi!0SCpXQSQR;`?+!=>VgXU9+M*)LFzP4QA|&!tZcDAln2h?jsIuF(SiNw z$=xa6s~CyIEG) z;}Pl6zcC@L;Cd34yjm<#G!UN6K|isjtg#tSd`(JWBq~et9f#ZcZus^`z?#6*GxOSb z{)TaN#2J*|@Ph=d4Y6J;*>;ej`!as}%0JFQ8uRgDg!@FQQ!^^VTzMV&p6I_zG!e4 zW=V<#n3(s$w)x-M<`S7fO|x=1wf!RTvec~x$h>Hi3+|`EpGMmJc)tu`nFfC&gm{`? z9nG7_u;?wkHd&)jD4Vf-E_*I>@$f(zhWOX7WG?vtN&*?S_Xs z533A|nGnUR9J zj6Osrhj`+!xpLKYSKV)L1BB3pC{m#xn1$@uWV>#I0>XPq*T|4>(dTEf@Y3+NkhlPW z@^@A41GKAy$j?F|j%LF{)ba?Lt)D`%cVgXtOk9pE*rl|H+@G)6a|GONm?;ZyGwO`O z7o_UBN@+ExQ=YByG`reKNwJ|HA|X(Bj!T@a5>^ID#)>FXXf6@6O!@;q1jZzHBrJRzsz}z3?G&v5+*<9KvIFhj~|M zb|!>?oWyAc+Op45@6Xa)Q6C%DtOsU+NG{YArAvKWByYp0Fz0dGdkRBrSrd5Xh|fi~ z)<(&RK8Q^ZQwCtM+HJc8S!86rrhcEk7W*A{k_GM4f0bMw-GLcFTC{NcK6AuPT219G zuAEP>B(J)Ld_jEMq)`KeJnwqu4Ef$QilQh+0CJ^gZm}rNTm$^nG&nllv=xVZSVXh; zVF4rDH6hSVQ#&lS*1R)e=7t36!1y1!1O^f%FXA6!g~bN%`RJ0RIf3u4`CXp;ySK=! zCLt$O(rVM(#;O%B9N!xC+&KW}^@oVl*VHA~n{JqCLQ~$%Z?q}DO%1Up3_gwNpr9H`WyImzi;koss})`ZpoCCG+- zqrghF_ZXNlJxf-SHS1uDdzKACzkR?q4Fr(byqw5KILl z6xl!xmQ4tj*X&E=Vrh;$k}?3B{=G5E44Z*-x-A+KIL&UX7=6pDd>&k9VK7~Nf`P81 zYE&$J%8_{YfFHB}seR}t5HRuT+O}jdIjK{kt}1jRQu#g^Bs*X9={~L1g-aWalWe$z zz zISus%WyYGo^!tukidP|^VX9i=R7YPOG8tI>TA=2n@XwH0X!NUf5mueI4!E`MP#pS- z%)dyW2nZDggr|uUXn!VZ>%v!RU`TRx1HPS(f(_MB&xi1q&~B%KybI|e9ybRdf0kfQEvD&n2yl>zF$n5(I~ZH28wfmGkLg zL4&QNaDBQuSWi^Y3y&kIYz?_7@D~QyZOG@S9x&5#EY`IC*VT2(*w6h76_t7+w4}K# zjn5C!!OVu^wIAz6n@Hkb2+WRG(;!7{oc;V76V@8LwC+3l zy=q9PYbyy!eKTuJxfupbcY$YTnLb8_LF#)7^~Ys54)UB{Vxrbhj)v2OzfSLv>#rKv zXvuSCnTWmxq8HU^GEyvS3Aiq!e5DXKDs6q`w78m1(n+?`Zc1J}I2AYC(WuwW@(wde zFxbp5Fl2u6yCdFYUT?P-)$$z`Jl5N8mEM#{3Jh7E{eIFj>0XVn5m05a-6E<#swX9h_ng!J35yn}vZ=f*?7J8v#uvBtQe z%Yj{{L5bQOR}lFGO>0%v?;4T9Pp;21R8GD(_?*ENnz|(sP(vRAIzJElR;(tmpn`3T zw0ssItvN0DcvkQ5s)yn_kPk850;!e4t-){pD(OPGPe66o$xAR*y$yQ&zb@PtAV zib;Cg z(eQjWe;^}L8If_S+4-4)P@L7EmDmK`S!r$c@Ovwt%TEZ`*!9+KrMLLpyj|6(^EZ8x zcEFm(jkj_WE|zd?CS}6n@cL-%&G(57Q8kcbboB4v%_pkkI*5Zz9szt=x}(o*#$}Xp+=K6AK=@v3hWQ>k`i;P!l+o3+7RSD98 z!_mRyoH)ke2%G!bsRUX%4F7&R7`UiKCb>fA7ng1i7JJU-e?NPhzb!SLh@3oI2|5LJy{{Z; z2KH~>NV7w67adF3<)W@692=k<_^_@QFgxOzMyLnj@-=nc4qv$=aF{AK<$Hll$lZ6j z^2z0dpn0~*+Z6`5d`^iJ61CY?inXuIw}57-_ofsGkQY zWAS!&Io>;~`aWnd-uf7OzU=AgkH>YhoFkp^Pa&AV@XgS`t?Qwjw||46h`@z7W5U{Km@jU;p&pb+0X`x4;JWayoBc;P|h zW#r2Wxu}MzORJHa;JM~PUXn6mO1E}0rNX0r%*e-uBQ8xL8UPk(`hC3Y*qQ^)F-dyF~KkkYVJYjso4og=D8V5dhnrh#GVr{4PG0Ce~wvJX7v}kMcE}H zDpA-r!4*Hs+?U1_^L$p?R*;B=SC6VmCiD*%8KGon&)n@6s;E#-lJxvIQ^4x~<{;&idFGbLT0qZA$4ldv$b7KPl z5NUtewMC2r2RHc0?99=^wVGxsWH9*UsgVBj)K_C`Y6sM!ll?nrn0 zYxW{S2$E?Y#aH48nI@7NUAn$?dAD3VY?VR586QC+CC=3UDpMm=FF+5zWw%hS7b!ckG zfjTQhwD&YhO@_?+tMhez%xem(=i6t3(dZ}&yMpK@q3~i@_|hF90gNj@4kD#i0Udj_ zTCESk6?T$v$?lJsT_`PHXN3haXPLRgs|_<2BGk5tPme`9%L?-N@AYy5?aN|G8D9Y5 z1o-=;8e*1w#E;%vf@AP|(zrrGKc;)K)gBouV{a-^*f=ihV~$pft_yBRD^Ibof6g%l zXQUH13F#9hEqjf4w{ECPY30ymmWaH zCxFuWHQ%d3ny72CCQX%HJOa*#C721J0Ri28l4`T!B8miuBHBS(6O^DqT6$(Ff|6v6 zzH_d)hA$(fLQ>_qOU!_`lNOhzXq@oePmkRRnsID?21*2^sA~YZH4gXj+OAMeHP7R7 zu9moPq~Q;gG2v&Ed#qW+;KHrrq6W3fb;iddrbmg!&a~|try4?cW57X98T!=yvSo6GZ@B&8J9XZj1? z_5Be=jFk?7wNSiF|5(oJ!gw`NhMv0GxcD3ySgj+Ti-ovS#AG z-q&YvX2V>4TSs2W#64$2bKllB*5-PKZ?rsCN(*~XTACe7(26mkY>UOB{mmUJPUpo% zRly#n)0MVvnvyWj33&^mBC$mc`CMg8ms!lSlh&1RHw` z137MP%hK{O%-rN}rD($omcWeSPFS)_0iYb?kIa&*c$FZECR?j^&GfAuAe>-8!^Ebj z9@q4N?ru_9BcVF^irX+&gE`IyA)7WfGQGWOC#Md_0YbE04$#lmoitmUHk zETJK6jhQ?|B}zwYSIO~0@Zl_xo=^*4)4?K`1Gs$CZ86ZU$^8_IX5NCF_4|PXD^Y68 z;J3TOsJu6R2A%F|YwB8&+T-@bvQ@)%SJm0W)YLnYgjR(*#|deKpG1D`=0|%2Wt5qem}6^6~^Sw`2SagO>73DlqA(>b81t2E{p zhpQQL^hJzdt}iKGC?!ijVI#@MbDiS3Xr(6d@=1_tHa79G)**z@8T3G+sITod#>KwJ zO(45Orid?^$QP2kW=U93~SmEqXM^GC8#5#<~-lq8F5zQrw}Vu^P&pkmtbhfWSM zj*NAfGN)~JQxSgP{ZZsPtMV9b45x+35I1a~m;mV>c)M;?>|UpVQo9zP>Ik@y-i0(N zUKOP-oYyp5#*CJ>Oh_Xap~frS^?+Sr!-(E~FTaQ&US`qz>FEr*&cA{$aaeUlVA!?& zL`Fr$%3|))2Q8m0YP>gq+RAGI(kHqG$PaCxI3A5`HqRMD-LB? z7oK|xo^Wrq0LaI}<`rfjHKAARR{+9Yqg)d!YL32`ZX(uf=<~aj8R2sS{ zS;qO(Wn{S>+Eb8wMgy1Xcd|X73Q=rg1lELqQUdLB>3kD{z9H+eUA$$_Qup=I2lYac z?7FUG|HoH1gJRCxn$SYERQrbrU$=tVpxEk?;c0W%{zc8@I-n0)f_Fe^${6z3qaf6^ zmy2FMu>SzD(KIB;QpshlsGMfB{YXtuqI?nPQBAlz$iwiqhW~8iNs-4!XPB)4KCjaQ zbcm}TL)FcsTGQxIp25SSteavfu)U1iiS)E#q-lkPsG)L%NeGzy-k z^7hP36|`R&)bxhHm>z=w`2eikZQ2_R_yt!Cn6b@ z6Aug}KQO1RR4Kp4GCzLH4T!5JU%X4bZUGo`$cKkl8hwu#5-JHLr{CIe^{QYz?0-vT0}Rw9$H{bgwxxv3VKNBGa3L$5`6V>8Ia*5rxy zy1MUY2ojvmF?JYk0^PB3odnvr4gTHBOOklOh)C1LK}E&$jtC=7sM_HL>?HCt?DV;N zhHA*_wc@!u*Csyj!eMEQ8nLci8ME3)9K<2V^gxxqVVy!wehyS9wEmF?wVHo7x_JSd>B#l#jHtNnY`4| zWGwKln4%12P;kDevxEM213uxIv0a-vE!Gpyrxy$n-UfD0qTNyrci5$*fI@O&r2UcN zked&fp^ze3HgZqNlL#*vrn6H0mP*`wQJQ#$tQ_0knH+NkQB;L$$0GNpv@(rZ&Rx>)a}OK z>nlj}Yu_oCAeoQ;U=@j#10AR9cKTGqq+|74pswU^JIs8uJ;84Ly;^ox@StcEkxc#8 z`FKZu>S81B&ELQ4bXzU&EEtx;&`Ewji{C_BX%3zZH4z9?y8QrZM$(B1JWct-KOml8 zZ>jteY5c=pvgU8mTAcOJsgS0ucd#qYk3h+$JNZbqeRurw8H)@9kmC|vJ;Dx@@=xHD z=dnaM?Y7Hp6I6RbAcp9NWxV?q$_Mj=ZVY^X z%U2)6>H#~wzP_F0nI3dHb#vp&^?MA3{Ah<@6eK@%%jM6|y=xqieayD=iO3!Gr`=8? zTh2-JVnR8m&|K&>>S-Nw)}cp#Qr3ohczH< zsy1p(@AgtZCjP^ zExd+WMr8{{vptnWhKo%ygt)3c)tF@t@T30NEaze%ab7blB`)9aUow?SeQGpEOq_(-ms_wvF1Vv^0S!AT zo8Saz->=H^rc9`NW(8*`&1{FOpm*Zlm(7YD6qF@H33YcA%Jo)?LJm3gF1o;tg)g%R zJ{8j{QzZk zo?xEefdvr(VDMAye~IaD$(ZVoq7rS&=9C2{RHUVeiU4a+UQOECnj=oD#o9YYBEFWM zT3e#hr+Z9Ce!yW(DFZxK%cQbQ{3SezzFFOd)2fY5RwWJv?u#8H1M)3K_^FbuX-o5) zxWi^U3JaX=Z(9&?qav!ElzLp&9gp^9VrQlmo0_tQLk{cq_11Y;49A`J?KhOH2PClb z)0KBMmv8mvkjf{!4u%KmxlS{#P$8GYUgwAvRVeS+&ub^*5H|?i)m6U#i1F1+Ly7r< zkutsk8DZ*bkvHmg3bC7Q#e((;yq})$mcX+4wwcS~@da@Ed~p;a_U_JMr7g{;i({vd zwpH8;P*AdKdlrn(8;rJL1>D^OD8!`WZc8Pa?Q7C;&igTmoW%qwf$N+j%Pv;DhNI%5 za>G{3IohM8PUYRSd=ZvEP+dwTA%M>bxnE)o;Z;4Ytg02^)k(36%tfYa2i@Op>Y@ zy`=#G$+IJYmEe!6xz@^x=5>&FfC{S7gp3|xBSm>33*R;_3Mi|Di~12llU5tKa_Okk z* zh{3^Ecur;&WHT(al!*Nv>rO=Tf{Trn`}6WSkdCz|w@57pal?RZBNcg8P><%7k8@Aa zBW&fmW2_;}qWT8NCLOWgL2!i@=s(j9|-o3N`4VLs8DMU+WQIg9DK z?s%xLvf?vSk+PsxjycIZiUMZ2?u4HnZNwQjzySPlg$28?D7&|Lp}jOSGdO&wxG)%C zz-!vfSanuMNvXdFhzLH^v$-Dhs3Xwon@sk3k)zBw`vRkF(szu&)LJ1l%ootJsZ#=as}=?drd76I3oYrXQp0KLt`NDijs>GCK}VqpRw3X*Vy@rD zh|zF$NucUNo=|Hffy)uGW}F=_pDmwIlK#O&LUqceIVO8wyG`MIl3R)rv$++ApzCsZ z=d4lZgfw1BCy4tzL2R`4RkRG$!!N1)->$dtH|8DH|@Xu5`(0q_{~1Yj^3$Y@-LUG zNks6L5N#a2_{c3sf}9*$XxOPBS7>b+Qu5%3-Q^ThKEg=$rFGHkAILm{80_5C$fUg7 zd;{Zx5IsD*kl_Q^Ha}JA3r?S&D^a8bEMWuZ7KQY?)42@lTw;UzGXn{b3Nos0Z9r(s z5y|wlPP^|?V)|E~PEsNXz)x%@yn12=kRnMabhenXUu8qIWHm5h`Eypq+=IOuJ{GZT z7%YP?QEh`_E>EjOwNX2S641E9!*IJf0ZWhH^b2y8u0PR|jZ>T7oMI#Qf9;TqYWv2e z*iNkQLus8q2j{gvv|DbWl5F0pigVti-=qp?-5bo}v9I+v(2ls~OB7SCp$JgrgjA0U~==yZXnL z&@+jmY#PB?GPj-}-Jw>Jw#ptnGhOhd@=oen|ALgl68ZJO6eK0om*JD1Pr?j#972Nj zR_$@4WVLHx!qs6CuJ7qrI)!`}9}V#dyqF!2=d^Jw1I2AzC=g1UVhZ&~heY$zSO!76 zdn%+olktK`fg4t2Txr0{4d>>zHfj z4qHspIYzEXomEFv={wE9?+Ag0LwK!=r!6?g{VL*LO{l2p4zA#!SR)4?9mBpqh>}eh z2=%dJ5%kb4Ve1zQ;#r_^lhTmW#}O+3N1xbyM4TO?FV_~bXc!0tlHysngKnp}chVv> z{%3-~QfM2?V^QbqPIG|2OKd@&{IAeo7z~v>G2Q~A(w-x!3dPye6sw0h-D3AkJ}(R< zk#D8Q6=XyNlMJLuzzT5z4a{}HB&1oOO`GBc@8aM_y1hO{nmSvM=>yIy$#}+~y>bd? zafFDFnkjzJclw|sQ7K^x7AIe-A?o7$!^I2|(Vte`zDXHq=-0K^yFbW0>$QdXyfq`< zrrISWEoGbn6_vhY%tFoSE;+Du-@OH<71+uA1NnCB}yZ2Z0Hg$3bX6!+b43OnZlR0=8*FJKtZ6v6?OME zIG!ZfI*>{DaTmz8hR1jXb?TFyy{NbC)5BkCnU^bv<96EGgjNF+*YJ7x;;k)_U1>j3 zW*wv6P^nLIfu_#wQUO{PW1dCAow3L zs+p~KTp5E^CT*$Mf5E(q&GtdZ5@ierU$<0*F3CtoTB!h7p5t{=aJ>u7hMdlDz;B;J zFH$huGphhra1rhTF{pAfw`9znq8FY0;=SFUKhf2}gJfmhHO$BzMhsQAW`9}G5_qEH z$ysp;a3~pX6;@Pe;Lh2Xz!Ypr*hN)nyuq0cc?3_ea{=z+cqwd;2jwBf?; zFv}etiJ!PE3LEx&Ap9QL)>JLX#F<|h*A=N7 zjq`|e4qsg{)c=5behG@Ng+tD>bCr8k;f6evDmG&hx0w@0h*_b3U1Z!4)jg@I5ggN} zB}fm4HCV5iNDF}2)+BR$AolN=9r9idV9fI2S9}`s4RRndki#BT^-=X7<)tFrv9aA& z?iIjvg)ARo$U6v(@ipyCHC7~>0x)nTFwTX~5ljh3Llo3$Henxe*?86Dplzyc#XpuBpBoh{&5G-eo`acd!hf@CwS|PvqI6 zkc+^U$_^&ALooCE<*}v!YVsRC%91mU2gz~k$zJt-*_}%B6g@xEh>4-p8&Oe<1ose zo&kqkLmjwkC~G<(D&NhgbDK3^d^CAfZpe^jr*nc!bV9|H`~x|v@G}R|I@GZXeKE-T zUzkz1juI&jhs3GCByn|)D6f4Xv5G;dpE=i+v@MDSLq<98*ata+qrI9L8ZA zp9nJvVJ$YOTd!(z|}BvV9&e4R^gEhF+B)wkA z3JLu#PP8%A8-D-Ul_1q327k8vAu^wCj0tbxI}FN33^OAaX>rN?fp1mX1zye ziQ?iZ<33(_g9<)U`xm-Y{ycMU%Tqc{XIzUA@#4X_r55QV$ok(nQ;)5Wb3m_{0lhK+ zu9Ut$!WJ23+@i;I#R`VJ9T0j>+1`4OhzWJbOka7GdXk}^K84d@a5-p~7jv&a;Z@Q? zd_L5lJ?O(O{z@65A#yQl%caRwuw_;t0pV!GYO~K`iwXKKCrCWqCm>dTOcyok zA8C+`fjlf|a1eje4*VH4|IILyNDYMP8@AMmLjQT1`M>f1cp%&8|BcK4%afYlj4$R5 zC_#T#760ABU)m(n;RO5BI{)h|0Pw3${l}jp3A7z%qrG|( z5OiC-JgAK5_V^nZ8agN$K-+lpD&y;zn233#N4-}=E;FJ&vsrpWq{FzeZKQy;<8Bpz zdEjj=fc>|$Kbp`#u@W>e$a8jX@`ZrO6^1VaJ)@u?ygDiUIEYI0=srF!mH!Bsr$a#f z8`F3V!Q%xZJvyCK^`Vd;F@S=DToXse*p*~wce`B+82+6Luq8Xk#?tDdyg#l?9aQ0b zHby*HtcfTnKpp&x5C5}CAkUT;@ES)^di>95lAZni!n$S#H#*RN85#d;6vKdqg@x_F zvrR)oqDlWFM^+*x$d8Y}BN|^If34ghKPHlSr?6BYqoO7mUwr=SY1_XtdSxOZdZAjA zu6+GD>i`)j7~Tt&eY_Vj`qxube;wRQ$seLp0uKZY{SXAzbNbxybT~mg-+7IUP`3wk zKmKP=|1z8p@F(vOD`m(kE8*4D)FR=oARqCl8~-Z!zdy5w@-DlAAQdeP4|k7`FD)%a zyZtZ`Q_xxB=N5%BAq}<;$P4h}?X3MANjv!T#6A;@KJ|CpV2K|=Hm`O^BCt6YlU2|! z7v%6FU7Vakae26zndjHnJJcI2_5WxgIywZE7Ra=@b+TCVqpGn9c-fb@S`8Kuq4J2( z=yF@#&`=Q(QSq4PANt?={_DvZ9!T~=y%H$N6D|3bgM))+v;AQzn;jK(5K8GQf!alX z80P)SA|d=|Obm>?X^uqJcnI%tq0FkPD7VvthpR)4O#+PnH30tqS0sF1q79`aMpia9 z#EbxXz5bJxCcC$n$7XOUIl`BIOe?q7+XemDv@{qjAITkjzC>(3uhfapuMLE}dNBWA z%71(~VE8CHr7J1PB-XHtNOyT>VO;2X(e-KF^WFW^r%zy0x5o?T1sNVkYi%uMWys+{ zjPMxE{}iyiWIw98Vqv*HERQBJW;pMm=b(_JwY9Z%JZwRUh=@cDuKlVyfCDuY+t?d3 z>+2ITOu~o;{r9P*|MdQ6RaDNc+0ogap;8|_w#_fWD5}A?Iok65xI$xIYWZ8-cR{5kExZkLBgs_jT((%bA&LcpkdUiOBDJr z8W{BS-Q6`4B(TN)j!&$X79^*{OKhsVuI_d+OMq#6cyv^w!4ms2P^LvlZN601?(xcC z3?GR^0x!I?SECWTJh!eUKqSn=&5=VQjGQmi0&-_(rMR%rc$p1I2=sr4J6>gy$*b)R zbMw;YyVK*1jZFWDgAVa{s>OEq=U`;YMhd#e)Y_A!IC-DC>7V-h}!kd`Y$JV*Hd z38Sq4w_IRk@$%u-)6;WyR<*Iw<>T`J-f`uO>ntGP4)uVh2`(|a6d4IW7DuDisv;-H zzZ8MRmM!D0`kGK1c?S$6HAWK{$OI0qq7tI9?y1W|Puzk)$}6|-dT>4ffDfuZswLMQ zo!(j0%_y*>)8T-lmPhX)^9D4%YFFjQmb$>sNlrGM9y5kaENt$D zQnB-Xyx!-zU$HaiC;^RO`uap`qS0u*S#2;f3jy)*VDf8v!%aZfW7T1a&fEEW6x$cUy ztu1=oFp}e=V&r-dg;6{nE@cei9wLIOvn=sbSz+}$>Tov_w0nT8Hymw97{?_JC6O)!68ymB6bR;Bcmgc`|ETvK4I@3-zJ z5?X}0?$kv37Sfya&R|J-wWi5wXpSxns__19w38C>273m*nVFdh%+3zrxSG!v%C4=g z0f3M`L4u*^i6KY}8ylMl&a1$d7FR<X((wSO%wXbWu#`G>h9+0n2>Zh6W7K$G~HN3t- z9Mi9++s{Xd50$~rzhmK}mMVRPU=+;XsOtp)%{5N=`tBbPfJEsR82A}G5flt8h?moP zgZBq~mH;@3EfPZ7Ag3@U-?wkyOw*70VMHY_=CaIC&`6Vg^xRSZ#HdVF-20pVX}QmFqYPpFZE``eWFfJjDJ+4UJ9 zWo&%#{<{8-E=O*xt4nV-UwUw0oDF*H@RLprl*ATj#VT)#O3T*-{WiyQEe;M>3vT$R zlC^YnjrWP*!m5y_yhe-rQhmd?>x_(qSQ&)^GxB@_l|8CaCy)_tXj^p47A!iXzcI`2 z*m8(8I5Og3YpYhN12P2=V+M}NolK@O6B{c8>5DF5hIebwVeWUh2}2A z%li@94h0o3vr`GFc*5)1`FV_Lktn-Q&$0_4%xxzcZ2d44lrrAGnA~95)+BAl60tXn zA3oK&TZbi%wXNqz=~kBudAae;FC4qgWtm;_*8kr*=cM0f1tlf;nxB{312y#>J5O67 zwA?QjKz?t_B3Zn;rVO{MArV~n-Y>m^wCU^)rUC-K-OSn%mdKc9BEIXWwFEr;R z_0NrYPBKkB^NDnKPOi3Q;qpPm|9eHbxeXe#hPY_P6fe^?EO_g8}C}XP$ZHzUQ79 z5)@cz`@4(1?yv-Q5a+vhQ8Jo-a09!olarHK4=VxqH5C;y=j3zN>gwvcy3aJH+Bf>+ z@HrjElqh0jF=Aueua-P{fxvgBJd3y7%W1_AQzDILVTNML149j-tP}Y^LL4AU^DYt5 zx+jhhQ?6ML$?hMc)nFui{wEql;y#xW7KULn^V<}a2uNZzpIiA6fPPz=n@e76Xl(q} zIsgV{du4aG%bXm}MpkyMNSR4R2a2DJXtgRV?7+0N+2LY$5(DDl$P*~RoygB2W18@6 zz1gJ7F;TiHcfHc2;q(1Rk?Q|Jss5-|r&erDwp%-&_A!L%O$uni?+e^#RhDr%9gcTe zv&dCni3M9sMw#4LTkQ+T7`#rA0;5&6y(^A*g_N|MbZdGr;To_i;oz3sf?fm<-53 zcB*KFG^_(&=gQ({MHlpavDvjg_s3hMn3$Nz;o{=r$?aG5L4guk<$glQ`*xvl^8)Ad zOCERTL&+T2Y!*!p2Z@_Jkv6(ppje%HK#otybjHJezSGbLheOS~hq zv)NRreE;Ba{`rPRL_oBQi^a(+;Rv)yQ`0uXp5t7&;nM?^l5T*i3yA;vuKWf{ITDItnHvCMKr1ha}(UBnV^UyqLz?CU}la zj|Ad&y*xQTXN*w$0{#2FV8;d7sce;nQ@5sQxe+WOF_hI5mz<-ZtlTT_U4Kgl9%|sD zxMgN#J)Er!n0Nw$$d3r-YS8n2W(+t`4P=luJek?XE%F(rhnN-5e+Ln_&7kJ*?`OX3 zbatV- zy11DS^2tA8v=%v^wI6cl#7oG_1ALat)#1WX;}MSxS`jBS(b41M-BE9E?*h=yrP0;o zKuzk4rc(UVe&z6c5NqcaBtsJRPrm}#{CD{FpS;aK-&*_|$fUNmL(5ik)YnqBk8TIN zPl1I6Vl>Y>;6bmxJKM!b5GWtX{KOsL9EF_49Lp4*>Q$&O5ujqN31=Clh-}gL34A zy8L|WsUoa)!4M4fx-VWIVW9YyU!o9bf`^7^*VkTld1e30^|+YL>22&p-ktU%Vqv8N zRh;QbUL#{;&U1EYTWS58R~DU*4{gvO+)rLkJVn>00V>r;&yJcVE$7+cMMcMpL9u%^ zi1qaxlauli5)y#-LxhL7b#yeWUIy^cz`#JEVkyc=Tu%ou5wO;AMAQSI58)Z(7CnBB zk{Kz1x_@|<@l->lE%qzIc7bK@3N70k=R6u@%Xr$=_j^ge2P53M8m#Uqe+WLh=wO6^ z^d91C8(ql!R#wI&FxL0l%*@Qk=Y!AZ_rC8#&bEesMjC$vRRb3fS4(N{>;W6%AV~jc zWaLYDONWgR?qj-9vM2G1v!0KG5IVC>Mm3uMWK?K8w9@NlaM zrXV3jyk7GgeYQHG`SZwAexf_z@?vK^0;Z#+#KNBo z4j?%J^7V@sqP8Co!N}oXNWYQJ2l`)}$2IKC^_?hXA(YHp0)Vl3Es_3~O%aHuH!Qxq z(Z8 zT+WZ(pCafk;gO~zc_M>~&CMx82E{=Z8{w!c@n|ojKLKs@qe%RH_^|)N{)*UQzHk5a zOn-gZ)&yfz?Jgxc+WRA=N-pMWqT;T3EF#G=>xZBqzVuEg;0;pKR5$r$bfW6~2Uv@L z0a;vwM8cx_;)UR62|T>@v*32nnQ(n^g%QA30A8Y!A7nw5760P*5!ufhN%w(audAa} zusJ)^C0TBNsR9;={cdeVRv`^jX^LFue5PV;Ej`_XuKX`n(h9bt?!ksc2TVzoncs1P z!+zMx*t2bI&fMm3L8slwi#p1tvDa*r_Z=HEksmQ}E$7)Qe}iI7_@ChUwTKthMTM@? z_c+&b`8N8`Qa?a+S|9Kk&!2e%hCO6UqJfNCh8+7pUg{6ONuLZcc^AGnLW^~Ad2MlY zhcL#Es2sOj(Culnr!B0B>#jmgRcoU@bX+H%VJ?z$K*W@ipfd%vKY~2_c4lq8JPW@` zhuImz!GtGv|7^f*+sPeb}i6NP+jw7&NGb2L;^_F7p^EQ)0g~Aur-n&%!^?+ zr^5+Re+CzNkW5amN^lvpO^~-=gB~Bf0S|&(iJ|bX`2+O9UiRx^n8k@^^FD_>>|;MD zVpDRM&}G0vCYHIo2DdtGoVxpy!9PCDgs6$G=|t=HcGsd$xi@;2X1tQ^yu_uuAdhaL z9HAj#al~V~1e@iOE}6RTv^!idldHy3{(x zR=3T6r(NXHcXk#Mo9=9Q4?5Jr4!8T4djnoM0=bm>D8(fz_vBL6jsNh0U-75SSz7+Svm8dojxyk(SAQ`gvy=_1&#Ke4i8Trzz?ByHd zB?G^s6su>*GKM5t=7mow;~23{;u8If-{I?+ct!&A`vLF#<>JC#oz

S1*_n&nICo zmk`oYGqR=ux?PIn=u<)ljR zVm|2zjgSceE>+gD0|@-GYo(zF`txZDz5L#LXJ?N9T>j!>*VI&BR~NwOTUwgx>uYNh zPBh8`o?JclFJwrY#DntBHtP`HLt^QNIt?bpq=-`|-&Zc}m066%3nH2H9GW zU^qkCGLl+7{@@mn@VLc^D>JE3i&j%7LmEH`aZ!c4Z>kw%uExnX^tz+@5OhnU^pQux zx_SZ2x(db3ze#O6k1q6@t)d%S-uXZe_ecI_nDUx?T%OIeVZ+{BvAY@#+?O+J5xgx{EA73}jG4!uU1x^&S#lj>8v$-?Sv>H@zAE^J9*9P8WLOfDrgpQ=1 z4lk!;k1ClK_{}u2Y*YFP@7;Yk?w!MvuE^Tj zfLyZM1!?w0OM$ZaeyzCUpo26^Hag6Gvqv;t_t*@jqIdo$3qJI>UizmE#f9Parr-5; zjj1r!(HV?4o3dNr!;yqo^BR^MRI#!!n006Qb&%Oe%_T@fOfb#mCmsCu7li@}u8 zv7;bi5-z@NVpkfM#spWwyDJ1fOY# z3nsj8*nXv^5hBtl3&cckWsmw1Hm_+QI2NoyhYR=TT@Z9y#er|Iu}w`1dW$jKQKKb4 ziMXVs2o4U43+yhG>vrGYoB>osb;)$DWZG7$s|An@_yCLxscv&{xK&TSu%P)JFU}X}l=77gDfi{yE3zNlCyOMey zOZtn}=i99yNZBU0gBLLI7Xgup~NA7UHd|z?}!<5QV;VY zmO>M61RE>g{jsJ!QO=wR1D}dZlucdXkV-yUFy={>l#^OQw_;a6TL1l}w*_~P72+9k zbAKif0zyDe!7CBvM6j-FK_9cSzYO1Qt*PnQoqjAVZE*oIZ=bL-7Y`6%V6FkUjpu$Y z9V8$|`T64V;|t_%A}EW+CIvOM3Bf4A#9wGLt`&<%hoTC?u&B~^AS-{gD++AwQQ6$#U%(6P&2GM9499BzRDQ`tEEVT3%FCAaZXP2Nlh8r7OmIYcJIZu7-iE>L7P_F*;fbKwDB8*5)<)XIYom{gt))@6e>{Ybn%bl z0CldtK1X+hHftrh-3??dM87+BZq9k>qzEffWzw$;jeT0^@$bmXQjz*X8f26z4v`bP zrx;SvagQ+;ujlqUQ9uDKeOjgLAd#5hL?lL3RauXwg0$y*n)^nmyYn(x1#2pT>0!-Y z%BZ{F>h2Iuo+e{>SlnZkKhtl`^%nY|Pwq`VZ4Rw5P`@PK_%Rt~9AoZ-S?T4a4OPV4 z^rFaIejbLpc-xV33K|rr0HTTX3bGL8!JyN?!NpzBDO%rW$H&Ky2i3kNc>b^O7l>l* zNW6FPhbCtmXC~f8;L0keX*m|KB6QR2QzGnX+}7cE?gmE<>r8A3XxM9)0~D^|paFLEZS~IOHV)j$VJcK9 zM-U>=aR1`5nn>B64%K;~RX=UK$6V3!MCR**%z;vx&?h$0&HnEK-`SrSmGX+q_^d@! zyi6=k#Ipx!cp-<4B!rTQ@)#VGhaKTE^(MuqQH7F+FNfC$5-MNdGtRKIZ$mLaK!p;d zD_{;NKvvQs*VRD*q@EZ8PEWbz)qde+`dKd+s#+DnORf(2Rk&|>X zP4Z3n(UJ$}Ht(tb#jMYwh@s?OmyLK`y4Kf{iVLk4gComKLLQIwqiz8Nvm*5rtvhVrY^{} z`dvi&PaF?$=<^4%4J*o1n`#O@VPC5yUwwIhX1>+Q(EJ_B4D`&W<%#Dm!O)aWlhq0N z-DfXrD24m#AA`e30O!+M6zLuUjGdl-F&tlFM3@#G>u50ew!a^IJiPRR&64AMQn9O8 zd#brRB7$WO<}=M4F0V(E0^{uLtO|I1Y^-DMo}ElQQDDfA7{5y+vhb11^Kn>yK6oB0 zNsXP;bhPn;bcSF<(K zrol+Kb7_2kCKTp8af|**!~SvIg*2`%iie$HA7`5G|P5hw=s8)t8 zd%PHV2Bjhf$W4Tcq*b_Zp8Xp=rPILVy=g@WP%DwO+QTG}sQAdfh-MQFXVS@M@sLhm zXpTCpEYs>Hu;Y_K-ywBNP|Jfq@RQl$hoU|=CJR4IB|&q7G(G$XB>e%kiZPoCsHVCa zC;=HuK50B^0oRzTnw!&D$1WGNt=o?Mk?}wM{sKP_v8s0ZaATBT5;^u?Ht{D${_;xL z*z7Qy*@L@e6K&o^Y$AxAl|$jdM}->*2wZFjLcnddvDa@Rrq%kjkmeQ0Ltp_MI2R7# zI){BFWBYQcXBo$w@uumm)naWwK6y7KG<#1jX! zNVoQn|EKUESV*1<)_?;Y_${5 znB0JxRO!uj7L#LVN6q%^gJEga=VSaU1AGrS>(QD#O*b@*_h|<>)6bPX4I~(og9djp z@FmDnol9Dy{kHP1gzq*ov2%?UJkuO6Ny%^$r_{C3@je<#CDb3Zyl05c_$wmOGqOB? z_AiRo+kr5hHpyZ6yXHDOJGyavHH3m1V&RdvJl^9JZLh8jV0WlQ%gd{MVN<<7o{_ex z)D900a+8pR&NDW^0W(CWCnk&}M9>!LTJNI(MZ-6(n#VZ1&BcxIi&LEk$?8N%Nl%9= zt?711Y3Xy_&YOm1=rozarL0;*B;2y&+JW2Kfu-$*mC9)g6)qRPiD1t@=#4GKk)ce? zqm_~h*OQsNyqK+>gBUwjpLxQ(&-W5?9F=TUZMN)_T;t6FY&U!Gg%K%EC6P#X_D1` z>*lW3+`TDYadib_odbesEL)!N`nr`7rD zPZgYvyuiF+%Oe&qR|qxNiqyZx@1R5OE8lkFR#KKNeldiow|qmq;R{E?z{m5FMdMt-S#kl3bp z_0;*Ia!0M>QO547C$}907Cs%$+lJ!rYO>ix&FU-#5RJ zyDfledD+aJLb3sUdTV&`DTU0@G1m3EZ{YKAQ(JYAks)h*3+|t)$p(k`*RuaNK>Hbz zcqRPIsg_c{WjG^IjY}0YGRl)?Lawg?as(r~-6V%EauJkK6n3Gv@w#4_o261rIQc_ZeVtKdx-q^Jsp>UEpx^;WUs~x{R z)&%$Wb=BlU%D1WDJ>RglT3J~U;-*FklA}O7oGJfsMbUiGs^-hDdDUlofhY7nI-NGy|MW&G~ zb^H7|qI6xQ?kcgf{L(&=lR=5$^Bj*7bT^mf_2=!`S=jUa+3xXZ?l=FfH4gPk$qb(B zubJb_r!dU}P2JUPSFTR7^4nHkxBJ28N~DZ&HXgpjW;G))VI2KhZLhm)g-&F)ZfZG< zuu9ps?$DgFv|OJ&KFwI!x2sOPDYm67r(Pv~d-h(Vd2b|+wUW_dy`Y+jL*nHp(^`_) z#+U97!}1mAIhM}GfrU1^S=E}6cONvC^0}VOyJB%w*Q2Z?44j*7uS0M4A#yAf3FqE% zU*DiCv>-xTK7CbM<2X$@7%pE+!JDhgYCY{OxqZwAW>2ml;VGm(ZJrHjo(_F3@Tre6 zfva#J`4Xji15vwTr4#V}rHa`PSO)Z8^CEn%$X4@q1UgrSL|2#bjWM=eKdJE5YwMwI zfR~QvTVwSrsOrBnQ`PS*$)Dx74yl){j2%3VPKtfzvg-DdVk(BN51~r^K{VdY_$h{e z9-+Q=rq_p!cAWxk-mZ#vPDJge!cvO|$_y7rm~k)+aWh&5tUoq0qa-UUzG)f+MU4^t zUMmEMY5>$-(@FRWnuCX@rMz4@2_7oN{%SSXv%d`g_NA`l-QY6(o?Nq+qo)nU2jr&Z zfQ}AZPUQsF9rJ>|m+m3wy!C>zFtI^3M_*SILH?kA|f=dT~n79z9klv0pBU^%v(--&u_5fD~qJq{NzE@&0V(~lb^ZN zYQkjFJOIyr(l(M@%JWr{NcPJ#Ihh(yL!_)oQHvtu+XSJDVTTE{+H2{qe~%2dCFQG@ zmL0=Siek;}>LTmsF#xD*5l4f)3TAy`TgT3zch>edCBum^*l~(zxvyU*HCYv}VvKq= zUeM|v8Q|6)&lC`y!U4$w9Od;d-;@+vD2Q>c0%N|GjhC~C zC%qHo2gl;LYo~XpfFATvLsi@ubKs&7(%HK$g-A)1BP3nsgTi8k&QQ06Y^DlakT^$pHR+z(gCK>JJq)5{`YX zbFZ+NIo<&r6`Q5T+41pb%nsZo7^uHb%Ac`i3@nt}ePmq~GmspNK@Nm!>ZxWvY^f+3 zLh|p+DG}5(eCsFI62Ac|e7`jrNha+y9Uh72%Dz=BX7H}MJnJ!Tw^aor``HT?GiPD4 z4@~IaA$>y5@LVeVN3$m%^HB<2xb6$>9?f?^ujZhhKX-p}zhoMo+T~&?fd9f5d?2WG z9J+JWa^j+_p|Nw&L>Eh|8>f6S{gREh6~6K6zG71x5XqC@_})j)&;1We9H4*sG$>l& zm6Z6#a4>N+ic%};t+l0*2}&BTr^jT0ydG_)jidz7P20{`R#x`IhiK_%;@{2ynx!-L zkdnvY=&^7z5}0EWHO9Q%S}ZinLH>tkT3{;_QTku9?s$;56}Do3&b^Z}A&qAbLo_b; zUL9#$&G*Ch-7%pdPRSUbAI;{}h1lbi8#Dl9P99sSTM4gm-oQqiZ0xhHiFTP)QDEt0 zvZ1qO!D$-RTKd4OZ17F{V9i82VJW?-6laf}tK;;tnlgL8rJAhy`#Ym7cf<1~dcTj) z7y!9Fiq**_>(crh8PiX}cF@4&d)W9;5=txE%5^}l9D+eZNlnd6UqbvboC{FD#l*-9 zJjI+k^Sx$Q%-z47GcE1zdHg!K$QE! zlRfj>$IA9|Qa|gma@230cgV+ANOlfWj}HEq%E*=fIvBUf+OEO0yXJ3?&*nr@Oq5Zd zq0?z4i2IJg#@Sa+ZY1~HFUVhj56T{_+^p){)fEOI%~uNzkpF)sLrSvaZOD!RK{+Lwu zSC;jUDv>$=wyDp(<-JQ9nDBaJ^)}>C)w6&^H2cJQio6zJVzrmUi8WS>LkW+9zkw`E zhrb$jk3Jj0fR=OTh&b7OsA<=AgDHg@;MNLrZBG&lnu^j93k-{C({6XHumxWa6@@6T zVQ8zmT0Gn9YSXA9mx$jB38DH zceFi1u2mcc8r4*mF7!fIK+nq%*$Ygv#8MLuCMIlvF!ZJsX&WrX?rnNsegBmkB(XOs zrCPXVq3Dx$45}djS(rwVi_qq8nHw3+H`woW1ff2ir9JJ>l&`IJhSVm6I6b0N28t)K z(kPW_t+e~a(P?6YkcvH6noco4m9MkcMXD{ZzQJfSXxUkZuV`r*8i*Ef`6W)#3WqX5 zYVCUm%~rIiI=O75YoB>+KlPfh#mur|Mq1k)dFx&K$Kd+S>5!z*KZ zHZ3TlYNq*k&r^y~y=ox8MCI?Msx3~UPV+HO+S9+mv!7>p-9qr9qBpoY@QXRy3TI7n zLUWJ$CLb#$G7}KIBuD07_}Z_pwWM;++Ja}w8KIr`kg}mKOGJ5et988zh71+h%9YB^ z+-95C&_fnmEDjphkuH9$PNZST^Uva>k*-4l;te0KI^`Q&sB{&+w$FK0G_SjG-=C|k z!tfV)2elsWjOQ-7>=l!W#t!I|xE?iM1(By--|m%;k249U-QJRwzuvW^a@MWGLh0$P zmzS2-_75T?{gvjl1v#_u>h;Nr8B=4zJKdW@C)U&hY?QfhFh$Rj0`ql!OP-uf!mKWi zi)%2`@We?HA2X0=O^Rh2wv!gFeG%Tjm#7=9NW$r1n@oiaU+@$ox+nnkRF}oKPk%4? zDyBN9r!jbnpJ~pz4aB1!ALD$m%MnNext-P#`rXx4q~jH3PMVPWF&y;HgGoLpQIG&OnvHOxP&sJuw| zBGjV6aQ#hh7O`|onT3pOCFCM%9FXK0JVRYa7IJ?kDi%I=S##syu+i8V%LF%NP1PNv zDH32X=fm`!R8NO+`PIR< z-dgp!;#1Jno994|%7pIfSq+kTt!8{L7wnfaEShTN_$0%co_|bQ1#Ywf4^l`mW){vC z7tbjaH}nd`3h@?QrVx<_CS0P2{jy++g$;1g1P0t#Rrv#YQufA~HMXB$Bf))8m}aE0 zr`k-I@@g7|h60MMV3Bn-b&d*&U%W7MQPOj_uQuMAB99;&KiNXAk;;7I_~h{Kp4seGzLnS>wvK+3DCd zMX?w)(Wz+f{F{TR?oS3-{QhI4)K#k5^a?#qcxVG{;OTu<=alQz0PD82!; zeO?JDR;NM)pKH@o(?>-TmTns&5t79)qV_LJ`7icPqWkAeAt9`bMrojD2%Nc+@SaF>UE>G z5uQzcxAsY)D@J`~ku{b}p-Ccg;YsTS-q9H=B_5>0uI15O~ID(qfkOT`uBX@JfGQVR%Z^xd=0J?};uk@7dk zSlj5~ffs0uY-MF#44}?1B~Hz+e=-=Nb#6DOKPymMU|zlY6;J>`6#}M;6B1lTKP-sE z8U994!K5K2>1hgVKV4FNR{$&vuw>#|S|e9WhP-EH2OIsHQK+ZeYEZEr*qV)KK5)`cz94f&hhhnYINEG)Xnc-Adx(v4G8m3za5zJU6c%ke8E-mlqNK^#Fgz25EjI{ly)taKQTit8(nMFrVo|DIWp)-0UN-t04$k{-Orx9e*Vb zrHn52%F#yL_O0l=%s92`Kwptrt<4@)90rZ*pqRPhooar*enO(Cab0>K8ATyQ9}xkV z-pgZnz)#ytJ09J@f6L?SqC3HM@ho*IMcet%HEp_G#HE`-UW?_E&1={hKi~PHyu5*4 zQaBVN2GD1gj<8*m6?nW|WGzm1dkSlyDmKenlI>a1dyntQXJMY@&W1mThZdoo;l_NP&Q*sH9&t1 zy(i58R&$$^)A!(7ecf(i?Tn|S<(J-u4G}muZ55A{hGO`?U>iwmC zeFZ&DO71kR=x6I=BwAHa)Ho^0x;kbc&?%c)51>RcI@8n15p825x!xFj0$ph z;uByRZRfDmi&weLl_7OmPAdn*Qd?AUUVarzU)RXFz;~I~aq?}0sV2g0v4byHA^x{) zf3F`sFNjS{yKAYD(@+ADQGhsusN}>d@GYUdN1>*1*kB<@H_X71V=pa><0;y?efO3M9HcY2wEIi;AC}9MI z98NAT35kAvcJC=dDRuXoFgB*tWOa{QyFHRN`Jc<_1@-0?`w7_6vq;(X?OUu;v<$*|9^A*{g(f}7zyWlHdyOTRHQCuo047YU^U_?y}q}y@(6&-2O!k7-5LrD z3Nl`5X@(dY9W4h0Eoo@fl0>-S7+zu$J@QVsp22h324cNJE2uBESZFYxuVWw}fXG2c z^PcqW(l(GJpr`MdoE+S*?M00Gr?vg#x{3>uhEyx#1{}|zo9ce4EFOJ%aiQMqQe9bD z86EADW6P2H%U=K0Cx@ZtQBYONHj-5jR*dz+zn*N|KA5VvH9U774=0dYM&i9MD<}wF zSgCr}qii7bbNAHE53qI~{Lk?JaVuZE7GY;*W)&2KMc_kl7Mwm-H`rC@gM?tM?CmdX zhq-g-?iKCftbAXyn0&3SmXH4NZPPM@v%*~aYlG?vI|?u^TUj|lP*9L8i3gSZw|3x- zLA1QOA#X#|>W9H}qHkyN!cbQ?48y9~^=j%BNQ^`Zdf>elE`v=27II+d{_4Sj?sM!F zj9(u4?;|Ol6jn)Dbuq8Rq8DA*Jpu}h0*lS(8Dt=S6 z!yImj1==3Y6BT#wC+U^{{cW_(z|`H`qHnCfR#gy+iVz@rOGCrY_(rsiVy?QpJP0u8 zrs#8Eh|Ho3Jl-orjdmu>rjsr}k%%pc#h?R)3Q@UMgR?m~v_c_TAQ&XiEIgz6y%o&<~iy z%QqDj6+Z%yOcN=(x=R+~z97?ay>aF2(G&>;6IF#rhiRg$(b_~P6S-fsCC$UV6fn!j#{{k#skX&TJ`>r5+8Rihk<;mtS*0RrM~zNf<de`%MiD6z&VjMkz}v zBAXl<&G=R{Fu+!nd%$n;dD~a(4K_dDq#vf$8Z((h@^w2r9n3I1CH(-|`Yl~*GEk8h zEy**hr4#TH_c%0|QfruVY6!hJF#Is6yJ~Rfl0kG=Zh3~IHmF82x)}|(nLq-E(Rnga zDblEW0G$0qjfUPu^QFZOyjF-I85oq>!cqJ_`7+baZNRrPNJ*jKj5dUJo=Y4-4 z$ExX&c-nVk_2PI*cyDlU9~_#PZ*g{(!D+FZ?LXpS00OqYp#e)) zXu$9H{wXxlD>KQ}SUZxzz@US}m>M$ESYCD`7}*(JUaKk;b=T9Hq9se1n3EIx39w@W z)WH4y67w`}+uUQ5)m2!_F7$?v!)OKWf}D8x92WU<{V{l)yfZ1ZHCH?N9*wm#9K;_4 zjlr0G>srQDj_5ui0+$ZZo&%*}t!tSJ#@|LFZ3!6q!}DO>?+@UIEf)w;{Ggm?&`BQd z8;{%b*$$H$&dpH49IT$_3yd^ME;uPq3kfN5fpChmMAP6Pm73E>0mNhxfyGm zCzX=y*#mz6m_NM&u+@x?pb@GsfyN8s2g=gB=x&5o%s@LPQuGWxS*nT%^Fnmz>?es~ z3N&!zi-3t@y4s)_dXA2kN6`XFvHfd_G0Md^kV?u{))sCHb3v-%`XLLPVVKOzdDiat zg2s)!pFz|j!_;}l+gF>zWu8)dUpTmW5OA_K5yCwfs=HpA43=QoF*B65XN;c@D=y^p zQiroBfUfz1J2$!#anFc;>x&^#=(Ry_6d@Jmgx@&Y%R-It9m{7t=_mlTrH^1c^fJl{ zX~xV&{a0IClXC*XxUVO;zq#D92hQKo%35v41oyy=cS2+Bz&)WcF9)7vo+MX2SNiI1 z79vK-Q|)B7G##PfD=`ZtuV?@@zfNd-q|T;x|AQm}(|017AN*|bRfKu#w#*i8kvYK- z)AK*ijV8bEuO*;u|Be@ay#R95?wssB)qs-Qq@bdOn{yC0~JTK=H&l=jiyZ+0ji+ikfZ+$xB&$7F33E3Q^ELX#ex8NBzp0tS6Xw9Lf zjizcoZry*?SXl;((ntp8XTED-uC(G#3MA{oPvJEXbPKA`5-j|KbA#xo-qSR_Lv z337BhHcX_@JN3WzW#_+K;5e( z!cDS2BL@M!uKx(=&xoZIoLnZfpQCvYpdj(jN&3{;Gqs|?@gp@{=n8-h#qwT#yFmHMKgR`Gy8l~Lq-b?x!(?a=l$V&)qdtn zK~C>>EoB}`K>q}^h^nb^07?&e-EXTf_!LXjoR62k_lcm6dkTIV9S%cyrH>DmF@5H? zmEt%t@ic|DK81$ndHnrOMQi0Nt0)k~2i{sHao^3e|3?`0)hia|crfYP*jNR?008Cf zr=_irGQ5KE$aE@IM&mi+$DUFLpdya}3~a1wD}yT63?1S+_q#`z?F_6i{G+DIrp}5e zx(UafOWlhYqXaIRi}Ypw|G+hTATp8kiua!f%=gX2nV+UaRLSYI2#xcA0zwont)1h; z#-nfLs+CC`KtX3_1kWwlvQ=Jjsi>e~bl(Z+p!XC|=X;G9y@0y8z$5$p`RibZrV8K? zZrq3tn6^sWP8~(WCpN%0x>2k9W&m~UjTX|+lJsNrZ?Eyo#Rx0RSG8!k2wDw|Yr1<+ zQFwT8SIb3>=+DZe3w=r}()0PjB(?~A-bWx(;&8n*TbmfUF&|FlmgK&eK$YaOe!O?S z=9N=Sih2yeC8bS8CXP|q+i7*-ghiOxgl&Vb%gf6f)csFm@CQ^Mx`J5nI}kf2-bzU3#|RxgXJ^0O8{Ry@ zuRg+jFF=uz>P^k=b}()EzdYdI*m48|mc5QWL^K$@I>a(tiASPE9blvNno~|rZl$%p z-nkp7+>v+K2iG2T1UbpUtvQz~snCT+asko78{{&e1iqqz2;)~8;C~J%>}T2ISIjsg z=IjFm{{VC2e6;Xvpv4znZ5W(pUUN)L-et@( zSO@rN?yrPJ-X+Dw6_y%>e)vywx;+Pxi39%{7ZzxP_5=QXH$n0r6w3cyiB0jg&VE#E z>iSs2MexM*Apsk|-FxN-C&)c2nl3``noob?-D2~@lt!}uJ>Nf{n*~-0Jg2Rv?^rT32`YLArK8e0b@l-ZLOqeQ3uQK zm$^+3whl<)UqzYT2y$>-w+~KF&yE*Xm5u1JO}r1Pgsb!8v&BM@;)i&^0tlJF!2gIF z(-|P^m#I8=gzQ;bYAR~pt6K?TEwIG2n*Mq6YGgtUM4K)J0@LtpDc6NF3$x56nLQXv#rIF7 zq@wqh_WkddD@O!kvsJj6owqd~@vAyrxuXNajIOt=jKiio(;$@T6v0sV*HQ#W2W$X0f?-3EOo@H@VTR)QRggN6bA zv#^C;h(BVaKk=ag)PWIcCDYb_JzF{%WCrIvz`e6{*H&wz1Z7oKK{Zb0LYZk30$>}+ zn^{|x0W6Szo*x|!&VErb4e)F3jm}}*e;Cvs+g~NbD;4~mf5mUpRM+RdP=8*Yg(J|> zM;9oE1j_CulUNUiIFF7`PW<7_OijZS2~p2}9;BlZJmqcDYaEfjj2KM|WyD#9b{}Jgvpa5yX5(=v5?y8DdlcdiqP!U~Fz7AFg z&p_3YUK!w32H?2F<90DZ#B5%>zrQzvD`Mf3U?%_Ts2niprBCZlUGn+^24u98on0y6MGq%f@?VU()`I$ ztLmnZ3BET|*k_2Ms*@o4V7Yjx-~XI1UdqT{gh{fqNoRtApJ3*e@zhXPw;i||&Uwg3 zSXRvvLx;<6^X@%rJ7iK3)+C(r9v$-Z=xLK$CsI5Esw~sV<+7qOanw zH!`kU6_8BxH|oMwprWFN03lET3lKN_dEWlt-}w*$2S@+hL=74NmYslrfP^ILgz~8M z>G5ar$LV_SbGns;k9f{{i%rg9^2>xD{O6mT$3MR*d$Se#VIclbKRn>%GymrIx4tdW zR@v;y?@)7SJtqwH)B9FMdL8VWWoBk#>)!4bma>}7NGT|=0`+l%=&v=`u(( zT}!_Uym%47`aT&<0*MXcsC+Ix|y5P@u*+JStKEZVf%&CzGNo=K&cyzn>uFl*e>Mr5< z;uV=WjhBaoTx;&}6@YyXX;JJ%#*(ZE@lv&4%+UR=+wE>LkYAi&XW8k2+w;gUqMl35 zOU&0`XBu&LOO!N*vtjh&9K#HrF2*;RbUT#wb|}ivwDd$JtX8-?50kEV@^o z{FaK5TV7XL@DJ4@^(g_gX-q@^Oxyk9e!LZkq`umsQvutwX6&}By692^KQcoe@gG(ugE>2D&A7tyX=&L3WqaP~SBqM(EeNA;l+9h(r3-rCj z+TO=*=S`X4;z=+3RIcLn>4FwxTHcx4Hc;3N7`}+0KE1I`w7WkaG=9ktQbR5G#s1&} zdGplP48l$!{3_gnF2;ks)kEMso9X9}59GyBq65-r`0zZul1hr7C>lq4mjH@U>bAg) z^APsTWYYo@@im5t;>RD_-_J*E&rFGsW*kNzraF0tOWm<{4;0tjD_F%|)!c8MtP15q z+#Y>iWPOWGh7^D7P%%~uj)*`A3fHi?Z`hvWr4w00NNMh_TZ}bl!*(O+Ts^I6^gK-d z{ZS)_lK20Jd&{sY*eqNakZzFf5GfImZlnci=@tZ}yBp~e0V(NjP`VqWrMtVk<2=k8 zGjrzkd_O-ferze(>?hW`YZZQ;octxK*y|Vs)&|(ml7w}7cd&F!h2Ba#O>tim5`rIE zQB~humzl12a%P$*b6HrYA8v=ouNdt&KZJW&7zA=!w3xFvj`vL;U7F<$@GNsVhm}ga z!>bZvSBBFgvns0GjowO~9<#fr z=LKDUP3y1Vk5(W5zO(-80h0_A)x@z@eLa!pw+<@%m`EQQO*MJFZ(LO_%F|W81-YLy zb8B=VfaHle1~jJ-sWrb#IwjnQOaK z4e_UCuh38*#7It#M)_yXZ#(P(vel6u>=TNNO`SI|sHdjm80jl3Ta%y}>29Vm$GwFQ z^PVSSQTJ1D!cdpas4ma<_H9zskSYXi^e)^}n+mJ5$eNe31arSCZjYNZq9@LSMH*%I z;^<=nK?d11oYc%8#Saqp(PIPikMGe>OC23(>$E96`==C5eyD%*46A?lbf_8;52j8{ zO%1fzAL)wI*9+7iL_dL;z$Zyt(MpiwXQ$S3`7_HfH_E&P3K>h6C;$M+8JiTr%8z|3 zQChcMZoaSONJD$YtH|+-A^tx0-ju_~}{$D#*ZtRmw4o@4D7GlksB? zZ_R-?JL``)&DAQ| z@Ar>CyuSu9bs$%**a+dgc zHgnBhoFW&4ww8_8)*8i zhME4qR_xzLArmarSHvp0*q;e>Tr~xGefYxHMW21aStwDNpMO1BrVockGRk}eVh@F- z8?A-a7&$-ImHW+%5WWApr=d{*1vnwPJ8tW(+r3BP1GTWo{yt3Whsi5~_Az#=5oQLZ zk*xg&d!gcTy`<>_mX8`-@|&v>rd3ZXthVChYB)sJ!bAKhdOtUwd?=Wit#grKtbuyL zUAFn)(Q8LiYBRX4j_ouYtFfkobaj8(ZL7gjG@1+JpZwxzmpAVt-;~!SUM=k({4E*j zKR-b-@9amOZaK?mw^t9N5hf2 zm45#&`Qoc_Eo;~BehTOd%4wlaJf>XsY#f{pv<2#q*2{>8C5P6;9~im^&JQni*d2Hq z(Tz`oi22seM1u#*X(dtEkr;J(L27R{yHax?%!PkX&vtcnwI330dc`*}ny9EKptx58 zr-i(H-Y*drl6s@T{e)n{v|_cTGLJi4!+L8AX)-U_4AsK=2Xc(a|EaJ4Y*xHpLYEgp z;e5q1@usApP%hToqGwq#KA-$yg!XP_dzAdcQw&6=X|GOLB6uq@(>>Pt5N0 z4&Jtf>u{}b2v+?k)9jcWGbg9knV;LROVv2ftgcVr=qxyRcj5I8MBAlS$4FyCdJNw^eFYbgF!%r{hLI#E}jnC07^3exiNi>N#0T0-c+5GOshp%%PS|7P({WRD3YM8$@AYdJZ~RiMxq78F<^@ zG!aqMUg>Sa!Ckbzz3{DOQ2Ao`+eWIERjdoF;6HdtC3 zejV+#rXeiPG^*VJXHFWrUeAI-Nwv7Tip&U42{f($yzsn!p$l@A{#t#%8zczGVgqy_ zov0ePm1w^FiyGC@?)x3~)4YnX*@85=if{GgpMTXqUS?fw=vD3JzqYUQUU(fjiQ_q4SgCX~_+{S~gW1{c*O?`jJOWJ)<_1l(&;Pj@F&5Ds zjgm!9VWzwr&0~}0(^4aEnavq5M%bFaJDqP>s6S5NeJ5zp9%af8B*ddM)y`=1XWR7A zUi~*%wvO4afzn9zC+dhqtlB@LED#8B@ZR9oA4ZxK8NeQ4HT`2v77j9Ti2w7ZWRQjs z4amw;5Jr}4W(Z5(`RAAKkHf?(4FLeh@=)xoCY{vY>wgL+%sq(2f4erlT%dV*dD~jK z-@l;JJ@c~0LcjyLC66Kle$qwyuDw8_(8EmlBd7z z^|c;xtU24RzJGp=|0v7^xd1+TlJpu%Oym!BPax)dy5Fs-bs;aM=5?FrHE4>@KgYzV zy?bZS!=tYkJuLoR-7UV z{|yd|2`*#=iDzHH;ZZMx5NG-HH`n&RfDk4QC|EN%BY=y6`|JDn_9r@v-bPN~CCVlH zW7Ee5{&F4)_PY;8Xw9ZaM9aXj0Fkkt7!QpWt_vtK#55QCL7=OT1{|~?f z6UaRuUqf=p5H8#G-5E#0*mnlYjAm~wU7Vd!Ncr71htj;gz4vCS#QOk#2Otw5qd8b; zdH~s2AV*qBi6g(ja`QXU#_tyTA4@J*7{aBf7?bH#2kWY~u5K`a&Gh#2h)!MoHPSsu zFml+RMVPBe7qU6Y=Ek={{^w2k=i>G1gkFRR?b46vAN~2QrK1C%A5GXFc?u}ufHy~J zvq=J-trhT8*TAg9)H^@_6}5#Rg;j=02kMd)C6tK z;26Dfp_QH8J6kvaZOs4=m7t(kQWD!tdmchqTVL{@Sk#nd6ya~k#77x&ZKdzigr+cj zmUVC+jj?{z(ODQPP~ib@TwKQ7u`6$yUm*OUr)2IevR3@vnk|wNOr+C&cQ8FQWw$@; z+~NZ>{Q(X8vJFk3Fh5_2w#)&8GX%OX2;!P0|6HCqr{9M0cRz{YPZgvtxjB|eYJ^t=?>9-*3$xo0p}_@vF{+7rzxRsVhE|NGa~eFj~A0aaOA zT5Y`otLbIG5EL7$lEUx4NSo$LBQ}KOZEbo%MWo4-$Dm@kJOX*C7Pr&Qw!;9q_IJllHl|5Lv<{pt^}wW{*1m+L=E|G?8mhYX|A)zC-; zA^F_g-0TwY*9U+EJQ|S|04$-bJWS_=lOa$RfNJ$)Arz7YX6_62p>w>izgdI-I{&80 zAom))(#HM${Mf`Cz(%>fb$f)nNNNyYY&JQ;4#vjB5c9jKDvtjLHifO8vlRIM2B(l> zeLJm1hLg?kn9?lBr|1xm{I-sT$x)X%B(}OM{p6)zJnL203wiYC2v)t0}$#wGAs$e<;ltLU_$Bv{>w7DQZk z!`{ZNPrLpae<;8X${Id27<_7Zjx~OL)Om@JmQP<)#pj`6H|S^Wm!7`zT}_zesw^!H zPC(e7@{c?0)?PzL}lpVz4LZ}Az-oyz?einZNcvs*CDAW?Ft zt2mx;<#VO;dUZ!oYXOg8cuLKa2cGMiNb==sn5zC+H5SvZl^8=d!Ox@hu-1wK%N5A&V5ibI* z*~*^Ah7(>@zbNI6cD0hwx?V0PHJW&)>`89i^=oo~MM!y=wUfbrdAgn1Q%vU~6pSs= zE-Az>b!tto7OI*@V^E-h8JK*PuAHk?dvBaZQ@sJTH0Bp^YCkyp%FM7RxXx~tqQ0-q z>96B*{x%N(H}{0sPs~Ti#$>Mo3=W(wNgt)Z6k0TveCUv(6Y2;*SbaIbUzsKLP^7`^ zp!vyF?|5AOPUT!^`K$ia`-{LM8y@%$NPK)4Yzm-T%aAyZ3*LFwxe+Xi4TFzQH}Ekj zrR{s;J_TG#vJG1e#m!`8t^F_yV!H!LOA9y`BTzfp20U~rU7Pc$MnTtQny)&CoL*|_aSOoSy`7Q-{}@}llf64?KSFk7hD!a z{sEV|{uqJeFp>6peo_|=NnUT9oq#LX(FCxjzpFa>BD~J`7Re?6Q;?SjRWR=94OlWy z5VI|}{>1ye=Gt7Dfl_UeeW*51Rf+p_#K`;SqqT~;iEmuQ(yl-DO1d}$j`YnNqmyHs znIV5^y#jW22Mdx$Vj+vI*&@#>?JCD`5_FtjKiuU$#maj9D98ybx}LCmt5;?ILfjRO z8crN{kHj1qyXt>=Z{1dCXvW3f*zYgaLFk(00%Ta_dm|%05JA=1Fh>9lG$T$2^9@QO zVn#I}1d4})qaR_Uz1IhnzJd06?@ zLiL3-a^!Yjh-h#gJ90?#aM-8d2*jYN**c2_9};JQQ`mHR>#_ z`_32|y58J*<63aBP1zJ2R#-`-yna%xX9ZWx@qK^n^G+8on)|8|c1O!_P$aD-YD^-$ z>1pGl?jFLQ2Ab)B#kX_toZNL+l}JZu$R}rLM;~#A8-+iGB<7%lNgoO}d zts@CJ@GA=Z(NlA4G3t=&qI0Xwu>iohiNk`X$T{X?N!prq#e0k0>7tb?NuJi9&^mtM zRtokNB@**w174V=FQ^`N`&kT>n!nr6iDI+y?Yxs}_KDW4B3?>yNEiBmX%)6uFoYqK zf9P+}BdQmJSt`NmIg|G$Z6abKxaPa3dSGxuloz(Wf!4r_jW0j~>9x2+iZ@^EULE0S zRp({(;AO>2xr%Jf!okCLVbYn^w>rBU`i*{zYl>}P@m0}y??@Nvc2PkhZo4KgZ~dK? z=8^0mEL52TG#ROi5}O`Iv6jePf9w1jCSBZWPq)_>hxAg-L-WEKVZMOAeEVhWavfaVa0_gan(6Jo=!K?cz61VWw(QhCs&ay3-uR(Hs=6stF&)H|B#-W4M6YZL4mo*#2#_rx48eBIv>3VO$!d&=Xm@dhn%*^U++2Mng4@__*e5iHlda8pH>Z&Z^Iw(wY z%ehoueeiMRhQ8>cBu|vNerZPk&-vKQ3*U@{7tuwMm?w?Rgs!Tlrmm(|s9N?O^iJyN z-Z1S_j16|1L*zl3>HuP95V8q2fl?5iv@zu~LZDzF0gVYaCucM6jFZBv#J8(GmLl&w zH)EJgI6cpE$u5Q7({~TDCni<)h!F&~?m@M!iQ(uXwW70PhZLqE=`=(e+W1)hFe@{S zW~oBkhCbPB{;YA!W7kTE_5)fJ?|_@f74Ka&l6C62y4ufCZ65KfvA|BLRGF*oEG&ti zmyAA(P18y*ITCr{{udjFqleU@(#3)Ty~=VEn5(c42CHSqr4oZ6>b#Fg@X{;sx0igb z4mX#hao(*&&XKs;pkPB7Na6p~}ciNZ*tbalmJ9XL;?X=n^zYCW!zqnJdc^-yo)o*O;3h z-5pXm6TOZKWh080z{qdcF=2|>tjEBBH$WVL~+6kwadsT!U8ykbe%~=iYZ+Cux zj)6HZ{W<7pJEkzYFf;*EpRV;5`G5CD?i)cVN_cYaQym^BsF~^JL6tjo-5?R4BhW?C z-+IP4cq_8lvk>9{y~>u_h--d%`7^GodKp3yj+*$`fQYLmf)ErnTdoiSN?lRkz*^CS zDui)bav2MMi0cS0PA*(rNo)$OZG{H+CwkKKcO@#WmIAjE3nO(6!LNj!)qP<0D(ZI$ z$A)o?XxKkVdyk4&)Z;ZYy;2;E>!Hm&Hl;HPcFvcDK>S`P(sy8|I8!qO-q_5H5g6t7@MY3?9TLg)R-*_BRmo4qj zP@+~oa3gSxIwH8N3sG?>^!&TZxD`9wBaf+*uOU z6VtwpkeV$a!90pkFO`>B-+~rAcMp=b3DI}H!2Sc?fF}TnwIZZQz{9RA#i-js+=@H- zFLcDCCz`g+A7y7aOUm~y<75WhE1vgP8$i%c{$2fy4fm%M&C2 zf49AVwZqaF=pnr!!NEN}k_80?!1$#H-T)RKSj&&ALQPF=UkzMzRMZazFuj_(`XZz# z-dLj(iH)U_(pi7vFr(^KuOkxzt0);g{m9rD3L2#d^xV~0l}Arw^!p*9#SNW@N>D+% z-5k>ywx9?*X&<(uH{x6yw={7wTw(Fl<1fwl(^kBMjB7i^=Ol<#va*ID{idj+3p|IXe77#`VPwZKMKSbUYGg$ z%We(3e=aKGBM_CO>*@E3DDgaGn1e$habB2vniAaLDC4v-Z?ufIm<`D?N$`IIJVWE~ zi|j``6Cpsh9&oKQR?)zu2ku8^6(5Z4u&^|H2O3A~92q5>&G#DG z?+7R%-N-(i)8-dXmcO58!fue)n)BS`%lk>4O0&fgwN%DZYe!nW6e8*pQMka19|rw4 z7J|Q3g)t}j_9DU)&5XA8D~Xw9;MC zNF6SGpYD4)Z{}{v^93{u-uA4$!y^^Hz{eTeIbUsW`;avueG$!U``V6J$w9h}4RjF--v6Gu^v#Uqu!MRDg-gNiLplMKw0=-QG^) zGmwsMH=YkvE~nSWSiYUm|6+V_-lHKvMNM*LIA-dC+$#sphkS(8+$NPK`G)HVAGK1q zXSJO%nuFp|Kfixz-4VU&5S<7{EN=CxTfMH>5p}*aqF3;1d*T8Hv2K$L=ZVXyVl`5d zsTh#A*kELI&Ct-$ z$B}G=rz0aHdN(s!Qn8)Z3W|!qHj03)xmAkCai7;=S5-vBNJE1sD`Xf+HN&>0<(V!G z)a9)DPgG%s)QD;y%EO72KIzbfk_e|^yeQISG|I)blY{==pTjC|I{^bH7X{JtvEdF% zYqp-Z{x(T-R!g(~up%+1B%~m=ATg&wzYVF|>Zv~kvi)T<=|YvDEtdgI1#Ty5i=LLB zLnMvSfTTcdybD2rQD(A*WQ;#syRa<7#o_sb-dti%_`Y%!Y{37`l?Vde%g>sGL|6Os z-6=45RfwSXD}%50Xo*gfe1;h9b6BKBt-8#H==FglBuZU3$gD@8)y~F7%#<@rBNci! z*yyWNlvfaj;M5$FrA2gL@2L_z5jqyL(UQu;?p(e3isV!M7P~j8DCo`N^HXC;A6kd} zwB}M#U2B~$mv+vHDGu4bwRldI4+}O-ly1h++SXnWBlInQUygnT-xw6{l=&?Eof`3Z z_<%(&jF{+QF+;UTM08k^ zc++1&M}^(>a5dITt$Wy=x1a2>fqCyeRhD4O^*<23dYqStLS&Nrqs8U^{{A=%km5EU z#Fdr5s=ffZof+x(JRgUjiB>$KyZrp~Q&Sz|%G-(50>{Tpd`~G}Q7z)|=V*pQN23Gp zK!_1BaZ>2Fff%VgzMDCG%=x|Udj{@o0{k({)k$$j^Sj$t&n`RUjxDhL7~Vikm<=S| zQ(yH(mIfw2u}HxpnrGO%r48(;-5AP~TEMrRKfqvlwRI}6Bj9$__wz1`N>n|-Z#~gz znGtVS5Jqf;#|=!i$g^jCnh;2^m$OamEpy|NE z#noxjW_{ldPo2a45gze?p=y>w#aj;rxlKnz@Q(3RM@mYn!&pg4Nj!qY58BM~AoY?L zOOJ!2s=FIrvf1q>QgG*~psm~~6UUS=ncU9TW-1pGv6Vs{y40U>dO<1a++O0-!& z7=$l>unQCRpL0RGIT$5(_hZX6p*#p_xR{cEnvBP4vmJl=gsKC^MKkcf9Uy|lP*hYMPRM|D ze~nU-j;N`sIvIUW|KbS97X@Ei$ms-r$7@GMLP~=!90*#(!(;+bmG-(gz}?V|2ZNP3Eq3y+I?z#$L^3k*Z@J$|H?G;eU(ip;~o$dekrt z^Knj1f z2g%#=CM~HpgGWcs3Cjc>^{xg#r#Y3j0tp^1Vs~wYG?el7Nh>)dlEL9XU;jWisKTS; zLm6#~GdBz-)Mge~?v!r5G>#R_;!#nb72P~v+Wybl8hFb}OBa_rLUWQ`db+xDT5wkH zn+663sHhZ>_&fHkj#~~xE>A~fdFahT9{c$>2$LcUgl}gG;TK0X7Z-<` zi#y^RFK>4irl)ycrg)a%c(!Gnn>g);M#K(uzva{Kb2YF4|1SZCSD)iVd(Jgl5(Jea zD6246E(+rIm(~RK8#n6CiJ%}YcKp{i21&+@8TMd>h1{*qXI|^cH{G9Z-D@qF;%538 zy{_?(#>X0GsJCSld@9mccxt<~A)DTcyCB-z8=NSKu+p{gfLV{qw7X%s;J-Qb<){AH z5PWwdpHEwDC0cOvu(9yB_=L^XU0Ais>dol|SB@^?*^?9C@8|R)&V_*JnGzLamybn%I4+aGwQxG5#&PV5rKppcg$O zIvyH1Fp-BxmS0@Udf;(4JLs$^+4%}(1c-P%N=OOI$5Me7`g=M2TqK7u@A>bK5zB#D-W?;H(T+|S0UE4MUo9(|S>X|0@T zL4wPXg7S`ZE3O%Qc|8(~EtN0rqWJbd;!o6* z1?}za#l+|mnmRf=dsM_vs=zqn#gyZFOW?4+JnA9^t$ZH)9(K>%1w^^C!B$Yn*WT^JMPWv`)ort}@zIZ>6_-T% zioYdxT{w{&){9JA;dqN>+%?ZbZFs2KezlcYRc7r@h46-troNzjl!KQpQ<3#PsCx)f zelPKh9nphQ8bT|C!Q$ahci2#W;}Gt(C!S`bt;9lQySP5bdDU|P57%#EHQvgx-gSSw zu!_XAly{eZwZeHRBAarD!{5z$R(XC-$gcyxHWzx)TlDWr&g(UTfsu|-$NtHn09qTI zURr&9eM#dr9Sx1~aORt@V0v|w5270gNsWP@s^e}$*4?dvmx8A z#b>$$(B(AHVnstgkea41b~vh$X1@KhvIJY00z>j%9yQcOcGEhsNnM@%<?oMW}0Qv+n&4#&Rjo>tJOC@%Qo`DFYkh)rssOz{6{s*X~IQFDJYw+(YmC+>&M zH~{~RYO((I#Id)cvJU3cXPG&kIZWRuqyRXY`)+jB;V-hw<=M#sdGZDl0i_GXOlGez zN4kmAt)~uxDC^!$zR&ecSX5@rqq(sEbjnrxQs-Ts)#_M5L`*sMJr~d4iWtTT>Cj|xhMTJGPyl&*iE>0EV z2C|l(ZhPxnAvY|C^%WIKi)Lg3$SNX$)DCRAZ^J$9Mdb0p=Alcqep&f&kWua1lskxy zLkdtC;VZv;By3ftb7@K5&*=8Gk-4Z~^W5X1lkr}bCaWtC<9aI%9dE5!OhaekxUl*^$cJ26GM*b7 zZS4Vom?3Szof&=j@Sz0;52yL{Yw|Fof8#FV2&(Rx0C)3$6z7fi_IAzG>CK1>7v_@>K&C~mm4L}O_=TD4seK0pie)%jk{*@7!6j}WV zLMIYdg_bOJ1xjpw?1lQ1stOL+i@ymt5JtseIp5taA#7R=qF#HYN#2QzaRHIfC`^FA zLwRMT1uw{ZbKzn`7J|Aa2fX&y_O^e3M{9*HR$A#rkxFOYIMg97Wo`58H_n#7+^-o- zOj{akXu(m%@@#Q)cf3a9VR*SUpDu{(01<%P8h$0MzCRW^OV3CfQe8P%^lEU1JlAe~ zush>iH&mx4TfS|SEHr-gL=!J#NvQFDww#~a2_7I+g z$?esxk2SY$ZwQn@H2F@)Uey#!2&7erSj^5$iOlFPKeeQax2DJ*2`iW|^SR(I3>c{z zUOgJ9c{s`{hh;Bf={5UXzZM!G2*x?PxX{_nAUu68A}X3E^MZ}d9{A(&o?>De8X1+m zFHLR$IZh&9zk;dJ<2X1tpHnR7>uF6bKgg@81$i#%@e0NxfXY-Gevz?3jnVVGw=)LJ zFr-Me(m9DGZRi$bc4-+P1E*4_AOzGJrR}`q$?4Q-#{*U8!31;G*HKTucjTT6C(XTc zH{l}Whm8x378CrMr57DixfA>kI-1AvoTImuUy%_j(|$Zf{-v>tUT#ll==G^pUObIbcv7O z0_8c-9)l?qs7OerK$L~e!omV{<|zOi;Ns+jh6|XQoXnLGw!|!bdsX4H9&(nRQ3nSH zcXcC0FW%GJdvbE}c%9wis$1E!Me9klxdgO%foEAHmO3S*J8IkSYSi0tYHK?0T08cA zwH18k(FQ9gPwH&QB~nH#;FftU8Mob`q5TlE@kEN$u2Z;$(T#d|kh*!5oa-o1fmHj+ zAG%yY0IBd`X~lndi6Y(6fDsJgD%b$0af5k&=zoav;1+@TjafDa(B0ZWLHSq zbq1k{usLmOeC-!S{V-P~ljQLO-{wDb+ITFG5`}(#Fe)X68HG3$mQGI9IXO9G&^mPv zz|2}yU5!_X2F3+wYtQ503~wZIBO(?r9Zl-9oGrraZg0Q9iOoQp1C~o}w@WKW$BWK_ zWI&=!6l>AQh}B|af7v$aY3{t0(YFAS&lEAYOb`a6?xN>jIAKQ4#NCP9sJ|^9LYkeO ziZ=h~FV@wBCX@2`s%O60Wm^Bs6cNZ=#ZyL4{b2L|-!0vJt3sbouG{d3L%Y9mTpg@Xm< zL*X*do!?bNDX$iahRbi^%%xVE=EWC?lfuS;x%k*I{P_-~gy1_zUGH4Lvc^ZIkRwJ` z!-i=>rKzyB_DeKg*Y>st(6DS^=-B@CJ~(yL&N& zvX_^arw0q3qq*|<`1r9eKakJm=dXvIm-hz$kZ4|o*R1|*U~awwR4z90luLkrsAd&A zBMOGy4|^bK3md-RyNA7h$8$R|m|e}Y{x1bhKEmR)+j3CTq8r=l034JLWTtHu z+Csh~NmF!u<}aL=*-6qoq-ZEr52da)C7OLdWfX0>gTq0$Xt8{%A{Oq7Y~!YUT_aFg zbhS|10gs0_i{E22=-~+B-RfOvV-7UfB0+NLU%EzGOs`)ri9E>9(nlw{x&{YJl1fTa zVq+r`6M2H+kMg+_g*ws#0*q8u1J5y;aK8We;b(jXCLDwlaVZ$y%=9g-uRBa=IleCE zw_fJ_WK#Qt11_|r3LCJC%NdyiV}vWuzCpOe=%V3up|>!!Dn%)ZJAPqOBNR)d?e^)I%$5nX6L%v|)?Gs0K* z3Y|5x1@SJ(rs`?B^2dvcmRgK`4+c}AKK1nK&mwl(saG7t?Sfhk5H9t}*{(8miE>W8 z+@Y0;Sk|UMe>uzL0>RC?|FCk?ufx#Bwhn-!YUM~`eTy6l+)tjrC*Tv|5M4gTv|qOUTP!LVg5d>S2r>+BNy#8R&&E`Ux$TBn zS1gE^8HPlsEUn)S*oe9{^S7fvJhgWq%r>?|JaI5`*@K?L4M}lQh7+T+T#r&3}N9u*l=(Dq~c=APp8KDvf-?U^ID2vF#i2>@OfA& zh>6koLC-*TYfx4@osXtvkGC?hPWZgO<8evM2tSMZ=^ED@-KEkiovy4-CET3V&1eB36FP$Hfm zri0`F(|l6r$$7f*9I@rvWn*#s9uNlRswXaQn5SI|Tm?BhV@in=1*V&JTgz+@ldJnJ=}JCJ?jQzM#jGWofs6UyRo?c)($^)nlYRINDU}^1~ZU6*L9kD+!_)}pC>lY`=?KNaZ5Wsb+ zt3d(pGUzo!tv)lER+V;G0FPFL5DNM-r~At@4QkW}SPrx^QYM+8eHLVFh}@NN7kin% zMaDyvkE;OhL`+P~m=ZGMexj|7_(MGySfsuIJ)?LUIMd+Df!vaC4n4wMpZ2`7ctT?z6lqKoZ&E}Lf;SVOaek^QbuwYi5?atmt&U^ZRo7S~`R-XK&z~u&7;&_91 zva2y`jy!1xY#X{2}4zu0LO%{I6f7t`z zjDxA8EFApW8rKY+g%$z!Z5x>i)mX*9m21(Mf&#F)&0vDVC=@zD%N$6HcnRjk^eKI_ z=^}PaO(cf?K)hnbjS$EEDDky(Vm;Gp{&Dd3_I^f8#@fox8z(f8+w)2<>-xeb;rcvY z;BjSkBc!%oBr26G@o$o6?0Z_BYkVI26bn)lZ%K7uNxkosT^vdww3h$zFcj38lE06? z9L5a_DQ?G|hm$Hx!h!atTr#7vnFvPbkA2557wMO{52Jjxm@&<&%I4%D6eD3qraE;_NE$|_(U0W>Wb+kGJ5d~Dzwd)P-A!TSnS;hl7cAV=3KB;HS( zO*h%>F^u9;uobCwb=cw?)BQfTwG*yOpfG$VN~U2crG@vS_{Waiizlz?-k>tz5KB2oAUt}M4 zYj4W(nC=@z%HJWEf5Xu`>cxb1%w5Wb8Gm0(p1sK31^OI+#LxrvA*%{)sOh7ck$^M{ zQ)2I@f7js1uLboHCI<%Cxw&ht>AIP~tKSzke@djba=@fgOW9<3;%h>}yx4XWcX3Km7V)oi`;3^d~#b{>0NNKnOM=smh z!ZghyqhxNY$iY~)l` z{_j7>3Fb6y`$pp6T!&tgYFDm=JaeE%>Z-cszzt zOw46J@uCLd(N=SDOw9A5up$&3Hct&rx7o_8A6dS!?bRW(`d=k-h*TAMMB*sgxj??} zyS+YwiNIVxjpgWiIzsHabwP6|_{kg$*AMvPs0v(FHxK4~bP+@sBeyTpZyNdIhK92A zwkICiA8tlMh8Iw7UQRg|!ioyD3J9>Rtdk|th*w#Tk?CF6GJ98|5|hsQ#F|h_gb{2< zL}xQ5-m9Y-JtnMLeJ48Y0;cFN7U7YpAy3ACEJB35-#B^bs6f>7eW|Xk>~=UPoeS@;$h5EE zqC5U2HufHEoy5wSeY2L%r!8}`r_8G&KIm}S_kFz29Vx3vC|FC)WMY>yPPCs$f@Z2`hP zyo=D!KQm@nl+LsK&#xsnb`PF+!-_ZAf5-b3@e*$i?&*(bYq*W^UK?<4HNEL?-DCL| z9gk_rQML+R`p(A$^@7+~vLscC9)V}BXXjG^nRPze^)ktwD>ElPB(tflYSlqx*Dfas z@JJ8rsHnbNUkP0Ti}HH{(839qn*BeC}=~jnfdV z;!xquTD4#l;ZCyZ-|7{Ge?`R=Mcmy`+f=-8~YIE>#Yd z!$7y3{PekB$kPvu`%br7dHXzy%B^*_>viHCY5HH6Nr&~;tPc=PO1@B*2wi!# zcOX^e1PO@`L{6ZGAZ8s~_fwGG#y@w6z+<$FBD|aJMz6&^omCZqUSTj|4O z-|P^XW1Y_`fGVLeMl#|2+bY{GY4lYR=E3Y=#Nw9*rVVx$|AFAZD z+k^&^1nd*uHJdMQ60VtRB-=Zg_6LSVgknQ$Qg!{h$~Z_4yJXXA5>Q-T#9v={H=BiK zXFc%XDlc80aq?h!AzBcgp_4hL5|!h___w?(SeO}km=6DnrX34+>0)f?nHQ#Oi;DIKsk};zu z-Df8h^|bU=W%8k4?Yu$4IdB3xN(EFLC+9^c4o+D)Ke~S%D6b_O1Yf~pWFfKfHBt$% zK5tb1!`$_B0ea*wv(yhNtHZ&t$(cnA#eSQB!%mbftR%PfQnh`Vt!#yXB-Og(DYW^x zWV`ilFTE(-!b#>2o#{B6eGU_uQ!gz5G;_mlQ7H1>S>?x}Xx({{Asq4>m(Fh&a?2-U z)VB0=nHLt@JDij((bZH5F%;JnJ)DoFsvwl11O&f+S=2_VFob6QP;s*$&*)DiPI~&C zo)~)R581g_`Qx4#OA!M1%?yV<`Cb`+1pt@k&4Ku0ZM`vK7M1oOGI&yV$Lw^;8M2Z^ zT{NDXp*MtB%P$Iy)`y8`H|8qZNrH=i#VqdkRsg9 zb2L1C_#E{k)vM?=(lwkm1O$bjaRK|#z~XlFdWa8|^6y0qT&X?!)`_=8Rbgz#VgBT= zRHzM&MI0r(4abpWlET_@ZtBL6z795Bq%Y)!h)w}H9q9gY_nf3hxKTo_(_SRVLZ zQcBJrnWwRNSv(uaJ8!DezP_qZq{JA&x~a6h%v?nUz8-|zKLu5vvUz-^X|^Qw;IF+3%6>#t(UYZV3y+q#Z3?1 z4utOmIhuheDQZgf)5vg>)ho5n&Z8E*GO`Yl}TR$-c71fRByZ z=x%|L9L?_Mi`)Lt-`F5rR*s>W5z4`T+Ik-H<@p{cXau-D`&^F>FHp=&1_lo5enbW5 zYsWW<=sp}3Ig})DYXB|A-(>_7gm>ZTgIqnr2*i_ii?z=fS~tssXm{5T<;P!Hbx8c? zjr}WEv&ztYtf{l-m2^4pD$s%_ukV6kzv;CgKS6AuALxe?occw)V%SN13&TIrk2-GA z4AiB$FVVI}wd%IM{Y6l(OG7x^9`*~kN>0}y;jZ{KR$TIBYNY5L`U!SHxw93G%_HH( z1HlX_kHhX_%k=a2)5%f)3Vs2B&#Z#~a=h(>?5ghTrk~-HY)zwBx8Z;In9i@j)wnlD z^nSfKZ!9?LL(@LS%IfeDs-4qQzqi^{q-4SB)q09rL)kxMHLv|xef?%k;G}lK=XN>^ zdP-|*z-)jb+8gYkTG`F90g(AT>B*MHaqrRCUT|?Zlpto+`s2d=syAPqks*(|#C&SZ zGqJE?ug>5xPXeSK%!K%esV3F>wF}noYpFk<8k*k!UeIk&r8)R>oaj8 z|5WUUu`Tb4+n38vay+ir&E5CPtckF2Gh*HwsJOhw3umVM!%ZK@1Xi<0_kEM1XYU2s zEeRC)<-1vn*}^9w`Ef1!XHH3~!24;StQ97t+lx)F93As#?#4Xd$a4`^qQ{mh?tUOQbFJI z_OW=({y%KJWmJ`4*zGL{N=OLO-Q5k+64KILN_Tgck|NUG-3<~_N_Tg6NH_1|Z#>UA z?-_&P;M+#n`(Eq1=A6IT-Gt3vGUGHXv9WnGD9aGgYwDj}gHrL6MN%jK5Sq45{^tam zI|XC&pa#YMT0ChH*5}3sETm7Of>M`HP0PkAE0}@X`vrQ6&%ep;RNx6-i8V<}JQ`$> z(?I|~oqSZpF2v`0f6mLzoV&(m0#0*g?y4;V*$XMJ>V^va*{%y5u|``eG}-Ga_=#Sj z9Vo%K!$2g$h>doCxN=XYN%ld!#Y;@E&oC<`dKNrb_WP71)g6Iaii^;pT~1ll#c)Q+ zK`skyby(>}8uW5pR!MF+9XH55cC`M>>BuPuO+e=6Mc3#1H^7pR8B~-rsvs|q?|$^X zr-!;+HDi0OhOrs!5mLjDtrFPP@PZaLEuNXZ)TRRgbNs8*7sA{kUgzhiTY`t2+QQzvy)D<4tXb9l!And%VnZSEjl_H4J{g5nl#RAQES6W2g^5H5T{02_q`m?|6Bqw`F-l1wk$0;+EGItI7=>`p1_WI;j~;3-ly<2 zV>lw$Jy+Ou%E_#pjdM$te#@P%_#iTMT%kXO{2WTexXE7>^)Th~l_k&o?Ro`}J|p9F z-EAbR)Le3np_2Umynh6!Ae`6RL*bjR3a*w^B7xO*zWge)OlDpWITXH79TQ5p28dMO zh14Zl<6zP13U;~<<{JrI)*_RVaM@&cfEI=C30$g^A?Xhb<}*))`i;rC&F^nTka$@$ zf31Sfm8o~XM=F&Wn3C_Fhd0-0C{$OA{rzz#JE`i6**p(QU%H!RpY3|liT>MJ68b2U zJo!$4u*5#*AT(oEO?p~e7LsVx=zWwm8gzy+;!Z4x{$P3L3pPcl1ny{ToHG{Yb7L6h zd$@`imuVSuy%chdm)QMnH|Pd?k76uMxhQHizUJrDFi)r2xLA*x30BU?Ke?b+=KU^A(I7;@Wasx&zIn2(JG)eDfgCQwAOzu858kX`?aT}18n z>YmLy z<3O|Ke=1=WG^BBMzyU6u<7Ts9$}nVhETEj zUulsFi_YgVs!w-Og6#hM;aihnz8z1b4ToEO9 z$jOAmv^|+BFP~9?fbSLP7U8uL30T`LZNcZVT?0m%7KhylfcMae!8^JQQ0oBfTXvV@ zHDCZwe(h4xa2;55uaZnUJBMjfSq+ft!((2vbNNn>0Ngi;v+Nvyv+CsHPn5#ynmmp^ z-mn(5Fb;${Hjq8@dM)>$WaCJvS@Lky`K?e5*;km`QRU%v+bR;B=8>h~c=3)}{WKPG z!n?>~Pitwh4CA}yT$NXA23D8u={a@|xT*FVjB;;&CZs%~eSd#FfuO8+zNM&?9NF^5 zV5DCc;ygcwcQ?Fu9V5$Q!F%kq3LR5|6ouKUxAq4Brw{7@)la8Zu?9+LF==>mq~e*~ z&iBB7IXfpuFH}`iO-uSrB^kAY2~f6mbw3vta?Q!k)X3oc0c{T{!`@apu|V+@_d|pN zHDFUazxziR1;J_`)B!>zbR%+1nX?f9(*JWjpcEiDqm1HnYgaM7Tx_JByJ)#7(= z$5y>$*Co806DO-$cPdNuV=CIM#||14uaWRd2O|8P3wnaisfVT~V{e58d34o7H8?#lr&A@5MX)N zk1%%caGFF#MPHZXqJ4urGvE*DNxw|ca-NRPh`ja>|4fMDu+0Q>&47DS9T*vXzZl4X zZm841=&-R{yTC5vfD0-V7D#okTq)rKX9_RV_WdR(qETmIK&AuGIN2-IETjH>Zl#jF z>%Oh6wX`_xdhpyTNjov%YkP|0+tzGbrjxO>94(eVcw8AadY8H7v=q!#K_C(VTN)J| zJy4e(#=4L6XVk{JYmk_A(aLgby&ROtdg8~s#SY&;dbc^hX$V*wHHjGt{5=J@Ag#UN z4yN$f<+u&Q7p2&XJ({ZOj#9QuPYJjMlZ~%qy~ov}--BQ2t3R;qNZ`--Z2|DkN9H`g z7^wJ?LB*o|tX5iQ(kxi@Z*)WaJ(ka*hUn1guO5;oMxccvkq+e5 zD_6Gda*T}PhSRn9>B z7xHUoMsiMyt6rFrgrO_phK7(ab_m?q7L!>2eT_H-AB_g2wt4=ep2^;DWVn|2G}h&C z8F@aP`H?iYlEN=t;_^q4^n!AZUNbnfoNAK3FWhiM4?9g76{2I9=?WXa3MY0L5*E7){T)rXA~yj_rg z^4QvT!igpSkJj|1VgyB^bw^=c{LdTY_X8%6#9LxehrMKP!VR;BUMfTq1f0Y#+q{Y( zCpNwvRWNR(G9Kf zaXY#G^{=ifG?63+w(uegJP$7cq#P7_5n; zIS>6rrJCGU6r7pP7r12TErIc}ptCsHm(MIM+}aaD?<3O1&IE7J0~v1c-pt?{t%5oR zw#x5S6DUPZZaixr*Vja68)^o2>r&v4Gs3u-F7@=;sA{8rL|iSygBArCp7t-^&wgW~ zO~P{^m=OO$lrxFTKyoMUX=u}-iz)=BlDI zBYg!;6JeES#Gg;Cw+Slpi^wl14@{@*)>>Dq*(}GUhW*axciMMiu-dJvUs1}^yIJ^P zS!Ms@u6?_*!TtB7*DZpQ`*{T(8!QT_xxD3=WcXbPIjp5JTGv7k77j*F-iu~=T5=xB zJ#dtG;2G&)WNpE0?h<4;r9y$7^^~Ng`4iB%Q0LdO*3wOe5 z_m>#&9yN#m_udBqnOCn0d@>FWY_3c|z{Oq;Cuxw-TAqR*n34%g8`)_hNzxJEyodCE z8^E-Ofw%lQ@E1=u=2M!D|Mr%ox`t3gpDt*EXjOZ-r&^&VmwV{{M; zY1s}osEybS7yz+lCHnpr`>K0CnLAqU3(>Gs*DZb~nRYW)({J|o^(0_^H#?GH|9c2m z5`Feu9;+?XZkP5NHEPMez}Hb%@I@%BwOYEWv{4sZdei>$XY%99zI_i-^vx64|4xc+EnXa@f?*B=!^=|kZDn`1i zH<|5<-Wgz;s(WroC#ZJ}6hwp?$fstq0?visuG+N9q9*u)+xmd?5Rv?P^UUbbyVGAA za)%6tK6pvGZY`V1^-~uisjfOy(LS$7W~$Bcu9?ZIxq3W{#^W!;2Pc{=TP0$H)LoNI z`C{`7Y!yzBURcfRw7wwzuN?Tp^DTh+SGX+Q^K$vOoPPX9Ad!Uew`*u`>h>i!bM3*# z;^h(2+@}W+J<{MnC@J~sy%6FEvPfguH-zG?qR^U@B3@R*RWz~kq0~&|!jOUFx`zu) z)BLyBB3OK3B9oMT2oNrgP&3qwRi zJU>UwiDs|-dmcOnQxERjdA-3ggza>M!Irz_p(-HPVOQz}FA0aKu*J*ybVufiO#jKk zd~gfW!$PClh4IIuy|z*b$zb4$QDzuEMT0`@3|V-v0H^xJo@!}n9C*x-3$(UTU!D&Z z7g?}e@GH?#vHSQx-rEF5p^D74d;{IpwaB`sF8sF)t4$T#$h2=cWh7pYP|K~Olw}|E z3SWWRrJ9lnOns)??pSthV|*)u=I7E7ScBz5~4pd!SpT=(H^3fQtnZ z784D^83F?hYZ$>*6gsH;?@bm98LV25M}J&^EQ3?~}+=Clcr0o6V1AYfs~#iFLeR|$+El{%~s zrZKXO$W7*>ll+)YDcU_!6OycV&)!PBe!-&)z*2XC2COKIhLGXS9vzbdim$L&#YW=l znK*#^05Uo|wvbGuhQ9w{EIf24qPYkZxGOJ)$e@&kgs=pA1--zku$Zm+gi4{VmVfO4 z;sCpViltL)iD%fYsN2(8?0FvVUH;gXrF8d;DdtW5-(ApW?;5By$ad&9pe``3p#~sersW-5N;fR2 zZUvM%?yaR_h}A+CM^1N&5V;KG8LXmYNjqfQ%z`8v=GP}6vPX`4SBZA@7LZBh^RMcF zfAs$@dXE497d`)(M}A9c0s=#;GfrD$$8OumGo1_Huk>f8V{{T|3S@B=%GM?a$tBIK+qvw-3+$UI#OYkx>?kv+4+W*X?Nxp&6FO z6isHiL0h!iCPy!*;dp&h)U^-o?%|YXV*Kyq5;@!bWUz|5cNTNYXaSG z{9~yp%%9e4#)OtL=eBf*iy2lQfOEN#?L1U97g!86L>c-eWe3u@zh`RjFBn)0ye;-| z)u-SguS-GwjTT|(1FtjP#c}nVWCM<%^9{6KrHiO0bW*Z|;10APkM63M0<-WaIr8$1 zmrBRa^>ge){kV&dExwINlg`?^QlAZR_?D(~prR+<_IMZ8RNrAEXQvCVN*EcM>KCd& zm>oi!>*?97b|KU~*_8olghJU=zN4>0ykCJO=T86Oldz67yE?smlk*Q8Q<#xb3tkh| z^%?U4p8x9Frp<$J{?WsYgP(A>MQgT99HSg%_hp4_??D?uT1lmoB!z!!gTWl{=rV`$ zLCDb&hdG$)FZIX^Ph1D*|2xR@VGUyPJY;%!0}@)L(PM$F`ZfCgav$WMK+PDIC*J>n+J}0efXTxJqG(BKBo?fRQKzXOo+7W-J08egd7 zf=P8>LlxaxIw=%%yAGZj=eqnV`DHFODHYoCLXA2g(S5u8qVcS| z$>e~HNy$hdiPPNbNE&a{1!dw~XSYV61cBGBrui&~xG=Z|FTMUYgXIVB58M^z78VVT z`#W1(Q%`VD7Xh+;B{$VGfx{{#11_}mS08W>Z}!EHszRgBk;0FLyGW^& zw&D5r^pk*HLU&e#nB^IxVPnEA1h|k{X#Y{@Hf#Sg94x$LKy`DddKz=?+o=DoX$eZ7 z(YMuz$ltN`+T$rxg2~Izuila#$UsQkq64;aMO1Ua;GJUj>n{}s?%FAQ@0rnIF?k`> zn5^ChsQlER_I*G@$1BK^R$G|cQ*bkNRJne4P+w)bDKn7pYIyazrl6-|VWR+L3Sk%n zgK#kd2;I1cgC5G1)YOPav)}*SYJR=(xyDBFBL@ES33_!mLO#pc+dT4&pP;?sg^b(` z6}{|*;!pTmRKo*zal@$m2OKf0&$^O-IM(^eit=gzmb ztL$VD>f}wx2wHaXY=n5^qM$GC=q=BfE!ez3ec_Aa22rT0e?LfpT0`gfx#8^?ZC0B> zonzG5H*cjkpPOItll95JVm;T{rZ4+^97Qy{(KO<-dLNmS9%JL5bBK6?6>%Thz^cMZ zfIRni+Xl+a@*o4dCiS(EDIrP}2gz=W0kijVe<=;}d5{lW?);K`TX)95`RecHCULNFYuqmR=dWr=XXK zBP(9Bu$S(f>Hner#nIqmXw1JVF!0&gup-*JvI%7G$cTisPn~vLVfSml(CGh~xnPRR zpBwe@VI!Eiug z?pbJf*Ly+R4u8yx9Bc9CR&jeNjIx+>cG^jlhSQN2!PKQ59W<$DTW_^ZuJv%Z z)ko!NYcutu?76c)Xp1;%7b^D2Es|p%z9MhtYsJn7d8*|?O0vymGj+DSKpy#cPef-u z$8Y;y2PRYDn=Jh{UEiIKDaq$qg2pDd(>5=7;HoJv;^?BZ3zBQ{ryWhRd1y92*)C=) ziHO_Jo)h*)y4(8U1pK5?5W z*W=D_m`-f*6;=e4RG|0T&J~=77e$L}V9WV(ZR5uZ$(`JjL&=WV7 z1&qi!I4#mVQ`!Ea8C7OZB*Mwo*j!2fR?Rw~2s=OtU4k9I1oB+j6IEzkatsNdZ>_LZ z)JQNN&u*1v$~mshq%D5GSdY$!X*&N(tN9Vdf z+e*RbuILSW=iLsz;Joa!AD`a*$9q+O7(teW{(IO9z$1HO!=u$16nH0Vz4jGq z{E$=rQWHK&^^O*T%JQo&~%l!}vn`0x70j z?AEv^dg{+P8G;tu&V`eSXZvLzScqT{n|_GcvR100!hW|Lzp~HKO>J23H{-Z@MnzdR z#MGX_8;l57%9r9+nHs^|^4_KmYI{!qok&67Cx?q(W;~cL23kjB{^mcnkiOQQ`>weB z;H^>f4cT2)DY>e}$*5!4yLQP<+RQ4&4=uDlz+tr2uvT3lQyYkGoq@gyhybEidFcGy9bU`-X zYFfl3|7$=AeVJSYLBkvEw@z*CZE+;vAU(=J6Iw+u)ma)v(!8!>qLmvy1g;# zoPg_&g`>gaZTDa@^jt*l?YlHMYgV#)Aj3j2m(7Q2BxzbA$HlK{ z!N<2rv|6Er-|l>=I}FI*K_|sV1;9}$LnQV!Mt#Ee7dSpUfkhjbf1Op3bm~2}yOHsx zHNZV4dr3;&y1ccAO3qX_p|-GUYGL?rV21ya1lQwkd<-jHSG(jBm1O2SUfbk*jm-7} zAwoLsKzU6LTdRfT)DV$${AK3K_uuDrii1QR8d+tkX(Ny7xtyLmU>>@Wy`*^5>w=*eSeWG$;M-r0PAbz2HNLU`Zckhy zmuUT7ZoSYJfA8hSgT|ELbGJFe*dcPO0TYWqV@+`~^yFW!DT*=C<6YsUzs`-EaOrc{ zx~eQ73StQ}bX>ZUdJE}-zq9)g{DJAlnNWXE-)UTnX!=srNBMjp&9NqQ0&1Bu)Q(AA z0rXtM&AMM3?;Ey?1Vw$+tN8briQH zLSpS4$7yD1=9SbnU}*}a(N)l?sP)yp$g>?5T7{CS$*XHi3M}sv&U)JHG&Iy@e~LyU zHp6V22$i3!rWIFky5Jy?=$+Mc0DIJj1xQ$MtH*Ske%df36pSVKlJlv|l8|NXN z&Q`(kEv^?L3@toy{LF1mIh02rR!Ao)EPhNH_U+Z$2HJ?BSq**--1-n)VS$IC#wv?W zF6RTL8oZ+F~FVmN)_>Lg}LW~RUtUee#&tDpc44B^D3I$n3<3k!nzNdDwm zpog#8J^^hr#s4R6<9Rl4TJ?`!hZQ;`4}Eaho~kgT;v$YLTBwN^-Z-CSarM*`3@U#p z7|tsejQRyOfgK8O-F+wj0B z5n@ciIDdHmGA2a`4Yk=ci-xY7H7FED0!TRQlA^UrO11Q~3dcldL5nci{kyYxDrnm$ zN-8V8re-Q;?*6;5zUp5p;Qf{bw3aPc-epPGDk79S+SZPANK|_k325Z1ug-(iWIoKo zr8P`dbu_l-*wxEk^MGouDp<0Zui|%eW)V$fT+qt+ytr9su|1^68>7Kx4kP6Y?>4U7 ze#~dsRhpV(DJp84RT^yL7f4pVa?6M9tQ7RbfRaRxPM#R!tL(32UW37ed&rg>S(uYI zhT2?P@u6PYcvdsCJL3kiSZ9MeKZ{7fSH!LGu?66A>gTXkw{`7fgp(>Nm<>wVD{NZR zrfgmw^u$UJQWkAq5#s%al5fhm^2?xlBVF}aib(b{QCpmQs=U3`?L${f80}@C!z<*#^s&)e)V>Rl6w^FXB$V#q~4%rx@g@X zR9Pxf@}C%MEVcx2XB`HefiX=(Vce`4VuJTd`(M_ICWt>r-=~HZH|5GIaO|*0#YX4^ zjf`YWNNA5bj1HtW*iw-dOv*`9*uI91L-kQdxDbs0BzX5lRxfqo@H(JfL{C{_{_YI! z$xg6^nTP+lvDG+jYw+0FnU;alfU#!6%pN56i_a7AlbDCp+)r4W?{w6AX`kgi6NTuh z&zBJ(NY5HTAy#YT&xiN7_1h>I5fZtp@|3UOHYi3EjH!>8!t4^AL|c0I*R9qz#$ zr2PGdTJeevxO2Vm)#nj}j@I$J)+|=-A!nndP(kY+k^v*UgKHmn7aikSg zx3HU2($Xp>%Rl1bk*1n~@xV8oiUyB-w|fJ>(zv$`yK-UJZ1dc~idcVTNO6{?uA0{eCqA|! zc|9y7@6$xpFz^$37~G)JtYq;a@vK?4oOo%w(_nW}7Q=LEj;cxeM>1 zz0xXOH?1E}ctYCPx7v8J7boob1Z+eX4X$_VGQF>UsW^Ny9!JqI-Dd-DrI28$4UV&k zoX)eqrXXCHtQ3BlA>Y26d-Js39Vo1sAZ`bpKP%3b4-vPm9mU~(03?+&>y?VWh+DP1iTg2$YSsM*r zcC4JdgZA1M$9SefRduka^_e?L)&h)ttkE)r@|u0tZpraD{g3Sw-}CJx%V6v5J-(;#+>Nf(#*(?}dnmZ!L077ZDL@ zf;-Xl%boiZ*k(%TlY>?kk@#}t)od4K^wNzQqxZbB7RQjxZra~^;CqV0znb&>6}RGG`&Oz*>PZa#K@&P|X}5Lo zMK@V3|24mX%#!3J9*uQmnBvB(;XagxB($>)ORv3%DjdPp`%clC{5|v9)pGt3E2ywL z3|z-=f<&s&^FM#m1BCC+@+RfK8O)B*yGP7O1!<1LxUS#+kYz<(+p%GIF37kpIYDhL zIM|joz;3t)hB#xlIL(G>p7MGy&qbR)=Pn34lYahrK37V+IOrn!*&{MXyqtL|N^NHUKUldZje)?Z;dp>z4L-A!|w?jgyb{jLy-{I#!X^eP?#Bl9SmR9X#fn{^B3(I)5Qs?T{_1%I~;U*3x zUpsbqE4-C^s>iQ3z(g}^=$Ma6*CLvNm0q#7ws$#>9xrRT1Q~QGVmtnwnOYpL;m-)i zWQEU58|2uA4BlxOEtnsk6p|Dh!UG3WIgG(nYim6=LW=)RxN9^E2c3dgc1K$l@ zM4OAWc=7Nikeb3>_B1sXncz1FZ;%0}!_fBd%+$I76 zn`wQt7QfMzOS)I_j8~dCvNcX05LJPI0S^!64wCyu*Rvgn~<veAo-Y0peH}8e==!ZIMTjvU8NcTn`B((k<6`ku=D2(D45857k%hsB$6VR#`{r3? z8IFs;w0puQEt9<%gEvlF9|*DWgc?<6r?jPb%+fAjn8`r`2}hd`!qE|1Bme3WdR@Dl z)z~r+CM5y)a2*E|dwLZ4I~H&qwu-~%l@+m#gjT=p<#un-Kn+`}g8jkOCH(|rX?SmP z>UA9`l>z2xGb#u_F2$u_I9U8Ld*_RJr{SsMX;d3f%LTCdr?rcog(c0OP?ik4C{p^W zcN?YX87$-0BFhL3=SGxKy+txQI#@8^NI5LO>hPj2UW&``EzAQ1R{ zy?I#}UoaL|XVbT3V|($QZMEu`o{Y>uO${8oxCQR>TG>BV3=2O2!139Cia-g`Zh5KC zO{N>=&Z5=Zw6?diy^WLi?mT5-ziAeFU5kwumXnT)??OUU6^cwZOosD$l()%C%njZ* zmc}7{Y>X;w#U2xbj&W|rdEz1@oTF1XJJn7iQkR9xnFANotTn@sYR{ZPYpU&j)>$_| zPsn@0J{AjeI~^1?L1`93st66ve{(qjKskP}=&Uq~zK!`bU+Gxy3nsSM`HfBOHf1@OqTxXI8E8HN?8?b?qM{!* zzyt75$IV77F}^4IhITga+{gHVKcuO;j(Xb-cGjr{5@#z$qYVpla*elZ-_saXb? z!o-Z1P$M$ZeA|mQc??ZLOu-wsy7!SOgH3WpKhZ@F9FOuY&t{D5Npnh){RcW5irj`6=E4alb6_q$+oITh-S zb_Kd@W5nJBFpMqqNGRS&9C`1Bcx7D1Mz?gG$%g3DNLH4EbF?#eh~kD25q(Z+A$Ez_0ttO;#Qs!% z&dzc;{WYvxBnya|W|VrB`DKRS3knE^>~O8^<+q$+Mx_Hb=RveR!2@#G#2GwHiz}B> zCY31LBjy&+xdE3DOG#NO@Q;CcjA*D{qXh&jfdzEug=I9;S8oky9t<)cSE!-X;hx|# zM0b@xdM9wlcvpz+aaAce@gCs9VcWCjnYe~_%hAaaQt-@ob%ErcPJj0P9xmt%VK5*s za&1V({7r_&frH$o~Lm?wsJm$9I zN3nn83qY}fBG|Ud_OJgG^T(3~$_JDMeXrsGt7m+tSt9}3|Me4WN<2e9LsC>3JpP5$ zby*lIRR>oGMyDiaQsx4k-qDTV9GNGRk~zHhq5viwH0RQie;9BD#>qHhh~=Qk_{%%d zxNk#<2V?mPU%kVQ_87C-#eNI-mj62?V3G2Km0=3vd4R(x2J9B0mfO7JMhC>32>^vR zL4%xDqf(vh6`K#Y7Sa*ai`m8ppn?D)>d|>f7ArJJr|{H(FIQi)Q0L!^?o6uZD%G@$ zfP+&i{E4MrcW-xtZ8xSD9K3d`LXK2Al)3F84Y_&XZ(pijAkJ#czu!ax39y$b$~mie zRJR6)?jQ+2X%Ju)n}^b7prJyEMJu#=9_p&6=!LOnl-RnEAoH%yb-3w}F=_!i%1RHi zE>iypPXX9|TmazL8mkB}`stFqn`0^?7EqY3B~^?(I!E1-U?%SyiOFxtUISUWRHOA~ zeraa2{rPLN%(4oH%h=^=1`(;Lb%KR@LG=->$rn>Q`&thoxm@>|W-%d{^>fYN`*JXp zFe%sOC@b=|o3`+9p6*0@hZQF$H~DD`?+{^np22O8-Sxo&LqXU1e`9R^G1qo>a^54${M(T+ia>5-p!|yUyS}(7TzC(BZG?E(xoF8$DajN4T$>U(Ub=A! zT$fewU=Wn<|1Qe&g8Cdd?UFN}V_5`B^-aMDoFp@^I-KfU1FLghi!eiur!WPk#+ROx zNb0z-?6;Zy9zcU<+fR};vcyWDb^DMsL$XGV=JH%j62-7P#jEnCjgVY29PaWK(ZIYG z3mHrH9NG0#5j4zeE4jMPYQGVPd{}5pKQvbTqxx0+*`m&hvIrfjZS*XFG*PazWz*{IL-hV?9 z_{NU>b9}XFYx1{Vwp`pJ;VloLDJ0i-v5O`#61f03R- zVa+dLx;_P6jK!&i)-rCM@nUGGU~GMwYV$+sUOx|(%DPjdhBU9$@!5OX9w$W%t{>mesYo*jiz7G{rkxmb-k?-GBplo*^+<$3M6N|zmHwG zT^j@-=1?)1u590z@9{yu$-s$G1l%mYhdG0P+`aH26Khxv+M>zVsN6hG2Q89271Cq; z^)=#{ubKrOB^18LyL1pctQuUf83c_&J{ zWsbq}_E06ssK&clgnN$*>+_lci0V?&DQ+&sSi}6fu+AQ;A-D zyAug=x%l|fz(Yl|g`)u7?Ol^zi#H=f>UnyyD<>y*X-K8|X5ZFxHH}&C^YtQljC&qK z6BCoy0j-ywAK~9WBy)eLf(dZ67LPzF8%`l1p9uV8rZ5r4*--vB)x3hqB1;uwaKqq` z)yi8MjQE&$pBuiP4ew8n8D?q;f>LXl;bcOM=gXKbTqob&t(Q75UkYQ_o)>0%m^DFB zm`dmZlyqE$>s68LqHB>nas1h_5deiBE^TF);PQqCVb1eWLeeeu^ai7~cj3)EQ%P#} z(?6?=X%+^TDm&xj?{#qR(sli4F2;*nkfBz%GNOEC=|d3@;4tfHTCYl3zvEm4H*FR> zG_7J|9&0yF*QVH6Hq|*)RD7#V{DNo&r%;qUS4`@H;%30Rh}~01{IX+FbOXLZmksfS zikY;(-jW;;hUoXO(&3XFF3tG%J4Ct(B+T5R#T(?W>gcK7`ebQK+umL4=PTd8NTS)9 zC`isXWl&GvKqS)YSkDIeei+2b_W9T9*+a_YS2ajJa3H-`Uv%nv-U;8O0268!!m?CSPXnPtNg=xCDTmBGE2jwMVo zQ-rduU?JRcyRtWCry+Rwypmyt;9q8FgthPOzv>pLaS_K8%HCcRgGnzp&%Ks{8sxNW z5$I_~@ayhvf~$T=Jp!=D<DVZpJgh|xM$;TV41|m0W~GYe_)>8@lnXeN+_)C^vH7(No!*ThXX04&Ms zM!~S?MzzXM`Q?(T$mPX=T&%zi;>*127Hvw8kSy{aII=|6u?J5Xl6ZqPkjLiVhD1a? zIzQxNZ6sRh22$Yvk5(&hNFQMO1BYrj-ZH2X^2;q7t|4BAoeUR{aclrRk(G8l{`Sr8 zO!d=xIm`mi6k?-@Q^qo?Ekvm47W+5*W<(_JEi={YClToUn(CUDfQ!$^c~czYq!q`! zde#$sOwi(@L6y~VVJ?d1@ANDvbQ_xz zN2;-Y>LLZjlMQWYsYUabt3UWrfqwmoVN#oAvSf=|X1W#3C#7Z<>WnVzuNur}inLBx^)d_1tLaUu@ZhM& zkS2l-oU=XIkaoZ6m*RyNk!Ps6PuLg|?E)?wSJ#_fD@UdjAzdRCSq>zf<(}+ed{A~@ zl^gh}TI6pF?8-pB(Z4rsd28AF{n1PH z+E1p@1~0tflH@gtlWcbMd2@9&kTjq*U?RmWQGJ-#8ns9zXbE>v-qmBA$&y*FSrAOU z#Mq(kSeGL$)t2!i?rU@#f1Wq|(|hUX&dyG+nuDj9s65QxI*#{^!$2~-DF%!ygxRU# zs_tXa2?d3bvmmA;g6RL;?DQc`x+xs$gI-IbF#lOo4g3~6S|xNB+g5r4>}U@%+7XhoVfU>q=LRl5z{d4Ii?BZlhY&*O-_w`4-aP#*4Uwr-JuZtq+sh7$T_y3XZAzc5nY-BR(m z1+^||yl^R)H8zKbhks}dcTr)XAw#nT4KPa+79E@GsBw<>iVCrrp=^& zNR9kWs!aY!$QIZT9RC(9iBBxug8DWW)1w?QT|4FkF<|zGu&!udsS^t`LMTUdebRWz`@7hag)`eShcp7`&?TiN+=mErQiz zbCgzlpm|%x%aY`b{hiop>J5_JE^>QYg^Vus+TCsALQS$Yy(3{S8|$-Rx>j$m#8JNlrc)CoKmUboP#OIY zO(GApyA})Nf+yY{UJ^aWH50`v$RM%v3EHH4Q4Lj9Zmz~;u5ukOA_SaIC}nzA%>UcA z3pNUp0QqjFHpMxL>0m+LkRE7?}?G#+ylv`|;C$6Z2H6~T76#uRr)Y`x9b9)l3eP%D-@71ft z-9n7X`7@!|<4d>r|f_Up2*wz{pUl9OyqB{4JC?@fdJ%;y%{aI*#HDCfpv~Letc&wt&VZ`TgSb zQnY@;fzLdLVq7%|kk3C%1DL?CpfjuM8hDq3vqL$)BAqKV{nNVq!Aw%FgC&NYvOA+g zLn%LhiWm(*m z>oFW$prM=s*({Vr_q9Kq$U$prekGWBn@F&}LtnJaiKD@z86gN;9C#9HTxSkXG_8g) zO!;fyuWHsXJ41X(R|;?NLyDIw!^OgbHGa|5QvA#ZitF!3n>ABx$Wj6Qn?||T)0EHh{O-h?_k;pKYz2SUS z2D&r+`hE?Vp*{{pD&KXcA^f zg*R7xQTE)Z1^SFJO_+jnR)~q;iycwAU5;|boHzfVFwq!l>kx_ej-GTL0H()`;q&HG zPL~RG5w9-2bm-Am7c@AfrNN+k`pv0U-vMT{p|nH`ilPOxR0H4fXwP?h z9Bs0si-Dn+*Cn$Dx4?_=W(nW@XWC38)3(~g1bgi~7lKGWEc2voXQq~bs(q>+sB1&B zwJtn-xzOS9tb@B=oR>n>Uu%_0 zBpi5pFn<%HVQI41>>(&9C=yUt!$cgQOZUVsI388NOVr57=oX6Y#KYF@-_RF;7hpu*p__1X*x5?RgF#=-%PsQq)SUjfB$CA6DhaFJ+CUFw@lkK1x10{T4 zQkq*&A4h=%s3{TJcZb)2`(8jzX8OX)_M=~BZ|0!K=j7mq2iL2m}r8?(P;KcyRaN4#9#10t9a?xCXcW_L+Mob7$^1e|UEDqkBv3 z_pMsBYAuCX4riM;*3yYRFy@Y(=EN}}Mr-~wc)N=zyDhOD)s~{JbYh$o?nc1uSZVW} z^04Ul#)BW6}`{bPTCAZu48<;~5 z!@dqPqf$UIaS->~B&=J{$e3lSwZ5?edvBvltz;xzUldn!c>Vb-rhCygAV% zX+{z)UqMN1jb*x5@wVS9u_Rx`+V%jjqy&iW_Vy>PwfmL!w#`Crw0eRj?W6+2|CqsTFkn0V2b^yfJ0b>vhV(!uY z{>@&<)bjH3C~{cK=tm9tz7I%X5Yn|tlSt?4KSl7%<-oG;TD^t0fQp52cTVLx>Opy? zg!!w^>y67bm(`f^7v=DylatwJ%rmh=1`78uo6Shpmc zo8!Bc{QG;|}Ary_FVK~+=zQo<@opx*La<5-zCvTtFtTo zT{+GqraAa&#;VVHwC9dBBj2~8oc$JnFRoCK$_;BVGnNGSH+_vvoh+QZnj>|DP`^4- z)@0TogV+txV~?Y!* zTa#eLl!kYcld%Nf^f?7Mxw}_ZR{H$PviiuZH(O)C=j*#0u`Mbp`uuoH!DFi_EBm!X zQID4wXmi>>TUB~kB{cnkSAm0XDdINHoA#dTI@;<%LUZ#QV8HHjT%i`y?w|Xh!9UxK z==JE)_k71LrltRt5dS+0AK4k8!XK4g+QR1E$ig@p&Kyg;p6c8=PgLjj7LdY;#^~wr z+|wynv}YIB*7HE7{R}yNycjP*X{+L^T$}-d1tC6%IP4RrP~?$JyWm2tZLUX^O4w0t zQ|t&JO=3&8jC^0@_jo)OiZt?aWkbLTzIjuAARAwdAM)bQ1({}}^jkxiw)Lq&$tT`7 zH1a_eX!F%j98ZhCHUYfbQ7&4fO*xG42uq4Y-pRs8xJ7&+hn$@OE{9U+5mc}}*4LiZ z!q7iDwmM(g8m%D6fKwQ4XRotKq~91)28*d|^6ZKrDc0^O_6GkH0^+-LqhvlVg4o`V zqN%x2@Mbyzew^XT`?1*{$Zd>Kngtvx!qT5`fT=j_Db);}jOjAe4wn2{Yz3|Pz$Y0))q9z5B<6-C^ zBkV7EfEf*9ujwd7xe&|^m8U4?diyO<^j+1yvT4Zpm=p52deQxU!*L@Q7(PEe+Ikoo z3xvokiDHp|N0D^ebAWMaoI|NI(&FM|WIfAaKf0}{njW%qZFTq7<51{w4sdNWkWbVo zg(%$Gn%S_hzQtcl>Pb~ngL9zxQDOCsjGj_S`H3Kdv8s|$%^al=XO>F2yjU`Ea_@(q z9XILgsNVifwKkVfRI@^uM1pP-PVuy%`Q#y-z%}au1R}A?i(G{8J{H3?MsUyz3IxFq z`ni?iw_z8u4Bld&DrHW304vkB*iUdlAVHJ_I=p!K-ub44O}*@trheX+(lQClAw1P9 zq3+q$H8mC!#JGpsprn0JY@Q5}&@kK^pN-A{7+?XFOce3vH1Dy=lHbsZ@~-J16BZSUSo`>@QtZ=lvGc9k-00!ILd z-m24n=f}VRX$j-b8jh6-0C>F)=)G{1?nI5P-9;tkMWS^tZ=d4^*&dz+z8eF)_^hGJ z4h-WWUxz&S$Vajl@!y}FO~$0_Gn?gTIQjN>bK#TTAC*bNbk#W_Jc#-7>F8|i1BS8C zgQxCJPVJci+Tk<8&JR^>MS;(eZ2Pm-7zyR{unWygrC+S%DxH7&O6%(jaVMCbfbDGF zo6t^$bJSO*%IMbX46%qTw_sdfIh^h9#85y3_E=xFT@q~N%3}ZxU;tnT8z_ZdInBd5 zkd%|uRAUZ0X&YECPunrSj2k(FgM)TBpf+e)ObTA!7GjZ}qN=heD8#CtkZmew!$FQ- z$An*}rwAu>mYD#}O6OMzn~@2^>K8<=^!R^TQvo`tNkJ4DWcp{&9+>7M z36s;)Y)o@aT(Jub&i|B1`kNK-3i?N9_x(lwUvl|9CcQSiXrl&oUDtC7lN2W#CGlPJ zAN)z)>Y0YC|2LdP|+ksTo>Y?|v zfgc{X&P~MlJPw1l534i8R+`M80e|VE6r=^8lU#eq@lu>)X2+0PV6E@IE>I(U`EvWg zR-xtY(|*LyaY+la_wkUX0f>SA1cJ^+d1Y;Fh?^J8`}1^m-L{ICSszj)k>&O8^HU4Z z-f4IQS`*C7Y2?bRU5hGo1v_~qlU&oQUX)7u(#3%N6!X_+=Jt#t_a5Q^24=(ze|;Z>^b%3~ad6PF7JN;t_i zwCcDN{`{$774WAv@u5AxOo8kgzkwX4wol5Ekqeps2&4Ph#a&u1?k)GplG+JS7t7={ zSF_NB@R_t#NetA30YSS5Ab*`N4=<=V*3YvlWA yhsHKc&v2KLplt5tW`kN>b0%d ze13`B4xkXW#^La5MA6EkH19h{+J(x9dwBR6Bxcs8z%KX$FuFSEMp#C8JK?y|tbT#J zvLw*c<|S1kec4ZfVO{ycH}wSA3kt4bH|><@u1Qry%Y-8{Gfb5;PuAAbf504H?_cWg zUz++pHa3RFQ+!uelI}isZRccBTRZy|#b8o19o^OA0yXy7%x=%?T7A6a8_oP=+l&xa zUQIbjS-{gULuNh;MP_z_4(bH@!Z>_3BiFkJyo`s3BSr1g;d}S`E2PBNyQQc}D5qlc zBh;C>yLxzPTUGXAMNwd7X_+$pytz~3tB$YoG+V_(gB^}d6)iI}6O(I;YbzUra~Nme z4jGY%$BiaB<2sX@xop(BD}oB-0aOrake-h$vVNlXl z<$0|vewNZrkKTY;25riv%Es)=moCc;FcdYF)8iV(K(_mLF6x<|3LGVXztk$%^Za6d zw^RnB4)sz|4EKi*A50+Uw;IlY4llM9pOyp#JG&d*TyIL!zLw0{%BqsWvtWn!-M160 z42&qvbc%VIKa}7%d&I{b68N5xj`r^lBT(t;`T)|Z{oR`Yk8v*ck`)&>u+^u(qNuaQ z3&WaErUKc}hldr?TQ^=;@m^`B`)rgUku`(|v-XOxncl!T^loTPAYcJ3RJ!%>sus2n zB9VK7LF68Iyd&_*xKfR-(GPW8@-K(diTpMs_=UmFK)tF29i%v=^ZR(QM#X1GN~QPV zXRU2tn(x9pN&J``Y=sS}^L(ETq&CXG*W9ujZU(VG?~bswewzk$NjYg@A9@A@#@?Xdwb`(icy+V9&zCc@8MFPMm~O`*fOiYZRQ($&b8oArTtL-ln491`}Wy!0iuGu3oYv4Fz{@aTdMt~^X7R^|JVw;hYsci;3^O1BkXOh z9t@rz_IDGr^|WJ^EPZm2IPh8}f;usd_2oB(dOmx}cdme1M7m0OvrTyyN7)vwe{M$& zjQ|T978b@0e*rl306sm>bSilt{!%U2NtOfO&*;LDb6OxWepMTDEO4D$82IHE012{g zQ3xs#vxek%{|>S{G#un_#Dc|@QPVtJc!iEDXXK8tiX+$JP@{D;-%(Suu+VW>Zcyc} zePrxDT{*0e#}I>qCqo1phrbpb3&xa0T%y?&=rv?j>bVGjoY6$=b?tf6HUF-h#5E1& zms8EbdQpMLLJs|BhZTEN0~E5ZR+>|`MQ^+47z+=*$N;@};Ba7fd7eR)iOknJ{x+)m z4Nb=(Q%qOR-pw_a{ISfdGENC`p&)%&DSP>V@n)S;v^2!Hg~CPMwKoFeVN|V?=g~|B z7z2GeCs;IOM|>ynQ{L}b;&&to!Z`!FMMIse3XZSDeZi ziAAZGx=Ve!ul?w!OPACZonO{ut@-3XWch5>(Zr#Qw7!beAG}4pGAZxVnL1Ikakolz zU_IW_ZZc*{_hDGl)rU;t$boEF2pMi&czjhWqXaQGYfyOK0%>4A%d$4h zS;X4WrW}WAUf71wrFVe}iwHHzcxh>AMU5>YYXI#UbMuqk-E{vRfGKUi(IY}d1%16+ ztY!L?V0HckKt}{D`ZRM`FJ+YxQ#XIM(Z3E%D`Atk!^C#R)2eE{f_eP(H!wP62~0Ia z&@2}4?iq0}6{1si-{;BIG}T*uHu$CVf=OgpTG|)RwV3`Y5s%MKs#e7FgKKSkx+Bz! zoCllKFP-k!xoKx5kstH9&!TZn%fsUJZ@#N;hJd2nWKc`|w#pU==#|@yVWB?G z{L1A}A0UpZ$)kPL4yJuz%ky-0K9~pCe^&#l$SFboi}`4XZB)Xn)%h(i185MKx$t7d z>8!`6=iAAv;~+Y&SU z%6t5S(-$GD{#FU>!hPDYAbJ(g`{l9x>^CjbwEE5y8wMZQn`(F^n`ON%TntD}ROm2C zNpXpYBuM`iGEg9@TbOait{Q_jB&;6ap>!2Q@xZVXO6=<5MU)Y#r`&1_tyksygL#gJVBv53>64sH?*vDAquJD`K^DEjno~rt_}*sCC#Kbdr!WXWeEEU7Rs} z9Ps$`w2kwuzAmceYh12h6-bQMjiHQqZl~>=b4(V#vw_sq+Lm66$cFwi+xD|P*+wh; zaDN9zX7!CXJy~G^WGibPMYgg`K~XkTJo=XH?fm?TzoB*iU*iBL8ll3ohi0qAYp4#R z)wxeS11DG{8Oo!s&pHFJOyMFSj%N+T#xUi(bHppf5h!6a*lV<)Z4H9X3UzyRo++Xl zPX@y_`F0mP_UdtL_MX6@kr68lMC7wiJa)j_Ndt#+-)qhMTBz#yCTzJ{^<#cS&+^wm4WBai;~Q&s(_3?)d~YIkwyOe46=Lbz6~HN!_$xZ~3w0;rQUf zwqvGX?_hK*pEaetuXfOCF=lFiyPTmwW=RnMVVvyOd3meg0I?LVzqaup()uWQ$iM^I_|EtKEoQ- zDo&N59iNba;gVGdrr-Y=n6#ih-!Y?n0q`6yt=kvejWM1l-^?HJvErIu)(zO?vm6=B zES&KE_%4fW_@6zR>qYuE)g@%pu6nKgsflAR>UbJo|{?x7Hm0x zO?^_TVv`5VJYuy((`j4f)!Dq*{631#d&BuYxm05RU617b-gDy_?Ry^k;hV>=0=mZq z9AcZuCClbpuFTv!39l1&Bww+s|7tlcVBsIwco`Y}(DoPiRC0$=vCoM)-QXvh`Pe_K zrm7*ICyL|}&v88ZT$Ir_8frupt{}BXIpUkc)KYSg3w{PWDT9^8$R1K3T`x{2rjlwK>o8SQ>zOK%(sH^EOJ4;5to*rLEx;9;=)lwL& z>*X>ytY^;z&Ii63CP^4&4zjfQ{Z6h5$toNxgzg4HD}U9IbVAazaHbK>PTXU8GoSHs ziZ<;Fr6<{i((~uKsV9|pizGc?9nUK=c+)#9UlSWF(;4MwaCClSWDHz;HlHZCPC4BI z%bZdOklWNvDW6hzj7H21fA8>HZO{6Q?x&;(ySg^PFIWk|swko7|6@rTB!MX|!#`A5 z(1T-0S>R-oQvM$E$O5wxGYAyIY-(du7uGpSAX$!^L4mFr7W%UgkiP2BRhL{XG*Wbj zg{_2jK@ziv5QUkNDHT4|k4D4CZ~HEaTj2VTt#==T6KF$3$}1V!-OvoZ1p|f8G=kFU z3S<>mhcU89T=IzhwN5~AIMMlmxl1)N$>>s4Y6QkaGoz-+g>N=_is=Srp=i76Yg=N! zioZ?Ek*}=PEETDJMTys})QXiUc~VIEO7SwV3!ox-ot zlos`g|0m)3=*ebDX9mAdnY5J&i81Q z6&{8sYq0Sffy3fZG3HO}eMpqvBLNy}v@|p{Wp|BMkH69&OmU_TdFD_(MvQ`V!@|jV zjOUhNaj?v^moX#0mo$P)U!3$XlKEVvQ)=X<)9p%fsS2P}>WqF#eUJ|N0h&b@jZN;& zQ=k@Bq!H;zqHX8#gS69KeA)dZPfBJ%9F~s~%hlvm@#8J0MXA!zDL!puPq9}e4$)BW24X5Pve*_|MA;k6& z;8`7LevVn6l2QJn#R?=PP#_|_&7Bo!YLpaK%=>d;zz3E}TI3+c3Gl_XFz0WDI`Yw| zS2w&bH>Q(gi-Mo**cw2(GRZY2yLYXlH!rncRO>LV+qx)x<9@=2l#i!MSYogx`#}Ou zTZ`huk4g-e+oame)}z_MCA7Gbdc1umiX^pFYyxN+4yAR+_ZCiULM=Tpaj(?=X4ZLs=jMD&MJI17He#+o1QjJ zcnwoSNYHZa*HQVkVUoRwui84m;(%+w(zA5YA6r@6T9>bFZsffpL(K-BnVHF8Gx^mF zWizSM@DhuqoWma+X5p>ZH@elrr5MweoHtx0SUWhFef7NEV87=5Dq|hh6LBJ;BzH6H zNxCA@Y|+x;v$PFb!Z?Zw>?%Lcz_5vv%f7duoUO}i=i1|U`A4fZ4SL+h6*o~mNqSQt z=UVEfU{NG6T2@+G`81IL!JjsLKX%_n_oxPwfpK{tmG6)871BVmwVpgF{Gk5Ym|z=O z@fnGN7sUt$wMx=TR2$yPJe@on&tR9V84evt#y@JCKgs(Hr+yvEn$?q|F z0wb!piPJ_PlS>Jy$OKT}htKLJ&wTiAgI7GrDzL4FkSfR=)+G3*?RFLN7I1>A7Vcmd zfsrai-3M4z0TeyovEE3z8yg zOyUP_Uf#jl<^9iAeSh+`<<~(wqKPraE^@;rKgwfEsP!aPj=)~})KF}uad5+OobN8w zcU!V4%35^Yc`+T>BW01;j*q#(zpPQ1vbzleek|=|!Q}JTi_$U_8hOq$`P(t@M@guL zOp&kUX!LXMv&myKYfNdp!E5t=43<~>v5KIrcr2&C>Q%a!jspBX1V|MmeEW=S6)^Y(Z#bCy|#9=7Zaay=BLxM@XO!T^GPE{YB$v&lpKB^Xo z2Lo+bCS#}C``-PRMYkKc=jB{dwuIRSEiUv3bl7GkA{5fOhMn9@c5L=9 zlyl+<&yrsaKWAw2D;0?MPHx>(9x`2)%BQ+VCJ9;J^|-2RS%i|DRw%$S!cLTa!YVgx z*Z&So<4cqOd8B~!dzd~ShQi&$=#*)%Ti?J9e4&16{kb zjfpBaI>ys4qLg2ktQLCWcGl33dTWoEg<>Y<$o4FFb(glOo03w+C?uGsvsOG6W&>oF zon5YQR)y2Q`0gx~!HFJvn<>$m(PuCDcI*^D711oWZM-N}3C;%ke#Ki?h;2=f3~p08 z;F%ku{;5sY%+)PO`XMmTUhmbx`pd;R46PI@$0K z1}ZO336+Z?)}#{#X9!>V%7Q_P$%kB-@23{0fPQL?G>Uom9m~ z?w5efkHe(^c*$1X%Y#ySr7V5w6UyQ*!;MQH{teAfAiBQ7+}LzJxUYB){DzR<86H4R zq}q~+XjtoF{{i_aN;AZiG9EC}+S-;$@Bfh;w9zf~s{Vc;90dm(`-d?G?#@I8TUl}O z?lH*O!a9}c)xh|qc-_9%R-55FOFixw!mc-2OkF!??k%UmWdbbJel;e8>t*jM6L5(Up4O}TmYhZX zOHhVr;p|t=3wznWSFkY-=iiUh8BwB}Z1d?BZ?fXuuBp59+8Xyo9ju2f*aska$Wu^( z?+AADYqk5eL2JHN@R;WYW6#|x6gG-0x;TW7St8< zYKBp%;l~)KHoF#&XAh^~nemO!Lym5+111sjag?hHIw7Q($uX-_ zvOQwa+kaTibz$aQMGU-onyOJ$(!Z7!t=NkHssx|f16ds62qHo8|jD ztco+xt~2EG7wq8f!{$C;mYtp{uKoEt%+Z$EVp7B42J?|T5kLbgxZN8X(4gpWKVmiM zF^oSRj>Mn{xLLBQsIYnSrrogPTSp4|5!<&KH%HmjLdm?do_MlJbhMAwJ?*uEk?_1t z7$!$o4mu}OuJdI5)(=|xep|P)b&D2JKV)%Q#}J4~Nq4r?hv^Xv|)eQH;`P9szNLJFO0*uDsl?FB!uW=Omjo>dl@(7o4&x3Up%l)dQryubTvS z2|^xp&Nj;Wzu_7cZ21fL!#LDM0D7;8%eMFPdR-Fih}uA#R=yf`r0Ttc1J|m<7Agu z0W9Un+R0b^3tKZ-EZ`A~q4xTdTZql|cadIkjX400zo9I&+{)()gRa7FS4>(6y!H;p zaS>oGrx(44+^*d;|41uwh2KRs8H2wYCFXO*Ip$AFU};6UOi(+6qoNeP<;ghE4MAqYdO}w0>SJe%43+uE6d`C;p=uL z=uo5T8zy`l#ccW{G+&WgC#csKMRJN(QE~S4{A@Lq6WySxKi2JgE1N)?_36{6oSaH^ zxu&;b2=fnb^z%jiIYrp`MXGdi@_lPuiJCwZ*B#DB3%#}pcFb#xgDCtgH@imW(R`30 z8^<$1bo!~uxHj$YIb?ZC9Z>z#V9n61yQb|!^Vj^5{$L%KlL`3OZzwsRh!(;Jr0?{) zEbgOp?x)}+e`;%*6TEGpiuRyj7hs?|J+FQ5-MEbqXaZ7+cu?v*u<{tynn?t}iSm?} z*q=$9aXSij1_nDI#V+Y{;i1xwc)*SB(IQ|ju)(98YO(Gm+V{z|1*Gck>RbV@)%(PD zs?$>R>x8OlAb?ufi9mF0*8W<;pqssO_c2Oq~a|R|5V! zI(|NG2Yd{4my%TcY0h(gb~M!Dv;Krnj&on0cS>cXSR?o2hWrdAgHAty9@y{`&R7g| zlv-H!!F*RjaAV-M(ReQDPF76pW1u@aG|!eMrTN%{_EZ$=``U@q?!sbbPxUW97&BQO zTGOjAs{e5k5mBa_1!ve4kO1fTMrE#B2ZO( zvMn{o6-Swm?w5-E&_h7r;Q{XJAAo^mnch&bT8jiwa9c+ao7*mzTn^yO`nWxu zEh@jPzMV@piag_Ia^{eojM@|muvfd9ANJm!uHfcGO<7>I@y=R?RVD;3qhEc`1x9+ zOC@AD)G0vRR+y3A*4f<_!`*ab%d=vvJ~W94T9D_70-OomiS7Rjf@}tM-5#Z20&B)b zu9g%6=xmn5eZHperi+lVU^|XZeZg;q-k9m6^-wD+Bf%GY)b&bWnVm4$H11RcsuZfr zFXv=AbEEXIk*?xL&EW^R!y(E~7m@xk&ky^Hf^qhR}VvsobS~EMHNODb!ZR+}s;b zr)B-h2U3n_gt#f4XyZtyA8HB=EMD2s(+xcM7n3Dx5hdCGd5AzB|%Ho0SpdCR$M6K#HwshME$ z8T@cu(2A|u*3vF`*S~9$#?P#FQ-RRp# z_mq^Cm%6-NtF&u+9uBL3hi3vXhr{oJ_Sn9?(yq~;Z?c*Oq%76}#gVnn+pQ;)_xK?$ zPI}F1{UBWz*r|iVRJ|vqEa+i-Rdm+a0-FK+K6-=GAtN z87OKd)XS_F(L?>)dpD#uWhs+l>hEv^L7s0Z3MFpBrJ4;6Vluzcya&-zts}LCku*XKvhTQ-j}U;80{W2GDwxw4Rdg@UTpkn{r;>cU8n^xbHF8B=u_QrGI8xu zg2ulSuNsanep|>$+lpOF+2*}bu%kmuz39$GAJjM7J`GFto*YCUvnY``A@xjPChoJ| zYER`**~bFM346$W95g{AkGBYy^?Rf>omm4Zx}>cU#r!tdJiv#9WFXz4oM3C)L zi~gAMe2n^cimJz1elPk#$QO&ZA8r94&RDPohff@;a|=6sHo5N{A#r6<<%nDO8MU?o zHjch3)}1r%XT#ZObM@@M-O3(zeZr#+ z7^32QYJI2^$0KL>eEb7FUs336`~G3FV-qdJPPii|@kn+w&SBC2YUj*T=fW0{@@d@N zz~H#A@@cE@em}37nPLT`=_6R8pRQa_U~ko-_}`YxDH+4jk-ooa1yWCLl#c5R&UmyY zrOg4E@${;opUj8zRRq|d!+oPDVFw97Z+h++o>;xXZ|Hl+-@g#QW|frzb!kw?KW7CkEGuv)1yGl?R`KR!8mQ|rm%0RDBBIIegSFULEHjPUss>!skt*ed^ogokte5IBmW|tH1?_C z;IXTbXNEn%$a4hggAIdEnP%-eR90pu-y|1i^8V7cP`v& z%0#%c4ux5lpPTcki5&mIX>fWw#KD*w6SqUR`YQ8oKL7`3so345`c}>9;hL^3we^(q z={Udl;DnkCN5a|RMqgTiUJ!)JHF3EqK-sht zm2n_w+EW8(mANPWZor^izy2saida7yhmXONgq>)&atdN|wPd9a{kcfu=IMs|t&N!y zc&;sVS%VuhBmME{n?sA-CZ-?&5UeH`9 zx*|cxGN5G|)4%d-Z+7W?G> z3eSmA<c|e?X4nW`4OGDAr2*->_-Bq zZxKk6Oae%6p2oje!V@Mj17g{T_ z&1M}`A=M=zcG1bY`CwiTTfa>|oA)Wj?-1P4g-45qpX>qSi|KZv+_wwV@S8PdYsp$< zXwa)Y0aN`A^4r?}K)w96w~0d3ua9za1;dTe@EANrI}k{G2F(Vpuisl=Z^?rD(3L$p zsuT&ep7iETbZHZL?LQ6j{wJm`DWEfXDXn_-vU{9bHGQw;C7+s~tws~KTPRwHD%Y@h zDzw=Mi5>;to&OyEiTM6&|K#=?B*zAmac)Zz7`h;J_oIxsId>|4n8_X_PZui~)u4<>I%wVtZzWVJp|7ULL&76?? zVwq{iJT#B$M|h)4c2i{~5KRFKh%Ikz#LDa0(x?#fO3HiMQ7ki#36a*+K9`0x5|;ZF z)CARGFEN(IztjunI(3~#!#E{mz8b-x%bE!;v;I+M;j{Q9xn8bi!~E~bB6l*IF}gRJkKY}lK@fpz34z8<|n?e`-* z*?!BXO}0G5cuZ$(JeZU4LY0fK1&nRQwj!R0J6>)3~pLZjwk|90`<=p!_2+ z9X#~<@1F+x#DDSEu3*=@712=qDU0A%elFYJ-2<+cpW_0&U$;WhfaJRT08k_eyM$8< zykI2T){*|~Kj>*w!SK5E9V?Io^}!+mRyh4iyD9(ingSnD^Mji4{ciRh8@_KwP`JLt zVInQRL2_2ozinZ%#_(0`3<-aV@b`VbY*<;G-ch0aYflcs!iq`=Aj7{|UFqcQ4vM#4 zB&;06?jvawhvrgLWJ)!nB9Q%Ch4SyKNP>a3?)Sn>q{0c>lu}T5H<2KPyiDN2aBAG* zGiXGzH`E=^yOT*o@>hrkK~>9LlpC+5VzUFU?x-&agB(^00!)pJKB^Kz|KA|y1*wp) zM!c+)zt88S(DL;Y13z8ZhyA0`9--1VHC5}h`KoQky7pQ(`J1(aaUU?`g7FlBkhcju zhf4krRxa;tW;JyUf4CNDPuK|^Rbf!$1VNX}vHB14?M5}4z8R2&l zCoRp*UciX&&38)pvaN-Wo-W3-ezpn!^VI&^UrHrPfYZpsQ=&mT4o``>$YhV39UewGuFaMQfl|9h(c`cHudsLr?> z6(dj};K@sg)^xvDTN{6BY6_U&JDx3x4Tozsy+>#U1M0-20xm<}s>NMg#v?HVjVKZ5 zpv_+aSj+z)yI-5F;?n<>KL78yLCp@LLD2;o^pfGE%q)`t6VnIW7Ys+1Vd5sQn90d^o2aXPIj&56FA z-u>MjARr?zKMJU=LnR_+Wt@KlL~?z9|C&5D(*N=SNzODAC3^?!OQR!99ejYDl8dt; z?*CZ>{_JQ$o7k$oq&Y1u^T1G!ArLuP!x9iOj(0-R{FfgP51=aOAz=Tp?6N!le$Vas;kvw>UO4dK$|f3_ zdB4{SewvPk#<1N*Mys#qXc``N6_cD`VOl?MGXfHPkhi5KY<2qkc7t!O2`2BGwW~*W z-4E0rJ2s0eG(`EpvBtd!#n!3Xqvh>I#r*uEX=V4PO|0~lmmuDy!~6z35nIVj(VSWk%jZOGq<1<11U8-;_=KTot98yxoQaY%@IufG=F22%c&pBa%DRPVk&7ITkS<4Xg%k^@ ziSx)qC2U)>og@y%mS%$fu5CEMP(;N4<-rFvV5{nZWWQJD%;Hg9Dpd8+6VdHJkRR%H zXl*pj%*^hlF(^bwH}{0T%*#c;Y`Ev*(06%R?C*<_)4jL1wtIY-$&kW8QGuU25FQcx zx@4D0uk^D?n`5Q8KJcc*Q&hNFQI<=7DuLpZmE1#>^GBdb%ft_Lm_R{HT*m`-xadB% zTO%)GN1Yc92^iq2i>qbiN12#1#<$cz(01@LnB&}U1ZYX?%D1LIEksB9w!55e)G^2U zcwkwP{{D{@rdz>hJ%Sdwll>RFj>cR@OybgUVbJyaoBsUGJ10UG{&ubY z3A0C5(Ki{Pg;0E~b}#2!`E{wW0jn~_(4CrY4Jz@-+Har}P=%A0L=Po2{T`&3SM(Ar z(qPXc-YO_?kIxWs|FwUiGLrA$am0M3!|)8{3qP;(J@k5S+)b6$){dCW3;CQ z%fRd1@Opm5;%5)McJU}!lLq=YQnP6)3IY{BFKuOl78t9MC&dDnU0WbynCLy)8~<;+ zpPN*{+bqsstqyCNHs`lzVg)`cz!rde8*L;Y*GPS(0P@}BFV7A!gO2(I69F?u75eb)QnmzD-g0V?Gc{9}CaC?^{NT^gp`-9;@Nc zuD3)bVQL4?0FM5}af2KOr^t)b(a~`j4ILP#?KQO?cgcpE(xbrKKIXDBk-cAH#;ZIC-s; za@JP{rKF^!rlc&?&eOx;kM$~Mu(GK33DY6{Kfc~Ftje`(7ltWFO2eePq(izJ>F$>9 zkdW@~Mp{6W?rx;Jq#LBW`@3DwdY^Z>_THZdKls4`&N=UETw|Oy=7taZ$0=DK6L{Ti z!Ri(Wspi*Hh%c!nos>a`D;N_rt(`hV)mBrUO{4F}AnRynogx}GqkMl$-a}kQ-GoeA z{q)~x5nLW`GH)bHaJSyRA4JfYzHEQvrzj_<?xL>h2)_u!Fb7W5`LbQ* z3ygnQ9BSk5P77as38uA$di1bn4l*dU71n!$^_SBjPQBVm@1GyQKfj+MBX)z7kdOdl z^SA&aF|dkmZctETkeFW(0+`+Er_4;7Ik3g@xIL- zIQ#8QP{Wn~_tQX}jVAbphOOEcvILk@@bDrH*j$fwww?S8g(I&eVhDp?M6?z>#Mbx< zi8Pd4bc@$Rg2ZpfqWG4&p0StiJUaJ;qUhGD0N3wZB~kau*>Zh>xD(WpL#}mp_lK1@ z&7%M@-GpcDi4J+2V#F~qs(KDa20Y<~A!T$e`G#-S#?}&ljzs@#G-LJQIuNjt1={)d zr8@*+FtO22Ly%8AuJ+lC`%wUsaSv~~e*5#qm;lf*f;Uc@UE#0vCj?0sVTg8yNj^MI z(Gv$2PRIIQ9Jn|w2g^a6i1YC90OdvmIq@v+zrE3)-(bT*3V{gOt-pz*Ra9u)g0!_h zFD@)x18w}Li(fNEstJC+gLdj=I`hr0zb$q)78ZakHr@%2lWe_@>Ahevl{BU!{HGTWu&E9 zIXL8HWdm*>) zIlcSm6Z-G(6$Bx~J7Ng=1YglhcLV}VP0nk-wY8l7epoi{Dun;Xy#)c+PodCYALqDD zqwqKG05oKsKu`ywM-gII-+iNoZaNvKz6My|MH~Dy(Y_5w9 zKBm0y1~>J$gwN;e7UqKwH{6K9B7hxbi^Q-0TaDS6QrW7cjLc(fh@t(yr?B9|_S!id zCj+qI0)Qj_{F){{z3U(ifWaDAL9Jr^p^p!U96YXQ=t)WGnbW#raee25pdteVd(PQS z1~t|*`R$&IeV%3CMd#oYprZMLnFzas-Or-l$^cwJgl1Uc~+el8J!YbDp_*G3Jp9`ISZPeJ* zLP{LxtBJ%=UgvueFG%S(K3-T^SxGMZ=P`>Vf_-edyXqY&uP&+aolhwIzBAgV_%eb_ z1u-iL0{NwsPnvpxvCtoEx0t{zB#;EC23(v3e%lq~IY@p0Z-+^*C6k$TDDvlTH3)>N zD()E5&xcx-H+?QgwWSoHguH@l@p^c^9jG@Ms^D+AN1RuF4;lukp<$%Q`69vP@aF{u z1tC$bjsNRYek~3`V}I)9KpHxCesh%WKkf6zIszLBZZ`nH#n4)ab;1?U$6<~hgRu9)>Ai!*;wOR64tIrEVJnYHJ8+ZhdEI_L-^YQn%l1mXqoY>jJPM)I;IzBeR zC&>KB10(U@#MA$j4kmI?Kd6o1_8l;%!P2mtzad`(87ag5EjzwT6V%dLhydrtdN~Za z4a65L09R0{cD+!*>ni{NXb0>FNY_X=ColpY*P?g%22ve&caa+l|L1jc?ki~F3YH&Z z@$(xacajiod#g3An5~DhErBKA-83A}PQ%zfu`~(3ZmLml)L;3CBIYq|V^rIcwtQ+@ zo7P_3H4qh@6%589BZWjmf$g|hpU8V)W}dj(pGjvj?CS8#2Bv1WPoDq^eCn- zvYw^iSM2^4y5&kVCL`bn+Lk_Opt1Qh8cX0?JKok$JOu@X5JLVII|~agn?-KU zP+t5hqPn`eSYJRyu)e!{dwUj8Zzq;@9*%4Zxg#E0p5S{7_g9M@HS@%q;rC}v>L7+y zxuJWyv>=ZpCZ7-lMTfhm_aM#nw(Su&el8g~{S|bGXhiS{J#f8{BqHBFPo578?lZ1F z=J+7-J=X||<(?%;uB;Ys$A^Wanks_jYU!CTPIhu}r1NBGx}tA&c^Euv8axuPVqhLK zKCi&vpWqkPhh&9j5nb=66(69P8XlNQN7*OW)J&U=WdYSJ3YV?Ocp$#9EJreqRKYI- ziymGRuCd#3u^L~e413-e>QdtGCVgtvGb8NJ*Ft;(o0^_ZhJby4lFpIVT$p}z8MTG)k*&=1>ApcH-AxMYbp zVZFuDx$*TK1vu;KU+ARV=HKJ922MYGdSks6WX<~0w^7jD-H!W6sc>yF#QcijC|h&{ zjIl0Z*DmmQ?WMUxQiNB5jYiY^g%)IJ$f%^Oe1CnEu6%BH9j16x3aD$;)YQhZLuim9 zG&`CW*rTOEgXkSRKfAhw@2;)?XTj3nHOQa^Di)+u`nkCVwW0z`vO_GKQxeVZ1JRFm z7stzlRuesi#1&p2Gm91|Y%Vx#Lcgt^p?pTa77wgU(@kqtN-_lwSF7f^T_Q2Ku7Rq~ zh_bhByu)v+LpO{+amQ6-(5IAvPp$s4)UsmP$??mHY zJZ?|dj~46udU^&BqtNUPR`=1tADG8Ha0g`TH>61xNtWq-c5alikvLK z!h*K8DLp(av9YEjv0Ml9@Zd>H>uefpD$B}4U;nFu0Cj{35|lMFlwZ)A;NmBl;!Czl z4Cb6dAf+SWv?BcSO;e;V88e5PV&IlP{8)aB39ps-?Kx$i>x|( zbOEA_6FU?NvYXc1J_wQ+7P3+6q}?CP`R(r0N6i-JMKfU{XeLJ7m|3K_G)^dcotO)y zUtuyvPT0I=Y*+&@kQp#l>kPNwP}sg$jS0K3UuPyu)0tEwdDl$aX;&Zl>+t+KmBDxqGcBxM!u8MA$+GOyy*)`6UMTTU2OHoSHKg~wb zN^MKogHfjTgQzGc9WgGOCAp@7g2FhUSY@|aATI@pOfEM$TL}t6=yjb4ZvwtxELt@> z78X(-eEO7tfG&iQ*+KZQ$cF3!_lN7FkT-bjKn_PfL%qdRlSbti1;5f#`ZF41qu+I! z1#Zdij4iZ5R1!t_VgpbT)tU<%ty?S$}gaKt6 z{tZKl@1tlXoJD^b%&(QrA4&_`Zkni?i3#Rmk4BAB$sc*yO?1`e=ql8Bf9*7{YI!sd z(5^!Zjkl@?-OTz7&WH+=6Fe_WQSMTaNaibfpFV39ZD6UiJNHCD7w}Yid!Kr>Vx2!m zi?M??-pM%dn^0Ztwl`AE+M*c`?nO*{TJVE`eVx7*33dMzFZRt5qYHAjl6C&5agkQbvo`d?Q9yhi#6}dz9R9#5t}P zUM>H@UQ61jEZRYL-Q*@QSum!vJCHHPg-H4k96ZQ7&nJ!Rh2@5)pd zLFl+-H+2A$4+nQb&imh$3)yX#PDeOa1z&oYZI>EO+8&O9 z)nY($sP<}`_jqU=Mx>14o5l(rxK!-lea9Y0V_0eQ(7%R=SQOu`gFQ`d5BQ34L2^j2 zQ%#-BOYz3&lyT?m9jzdoGb+}sS% zG0j5`{ntne;bgtJH|c^LNhV{|vX-c#vcJ1=5N3qqb0VC1j-MQ3=YOM$z%j zSJmbX;m}JmRDoP#;i;M!rItaEj5d)%rY2KD!e3KOnzdYh4emv1ZcA$Ft3;}rl%;dN zsKY&hHJcod6Xkha$jH#uG91z{(nxisXzAXGNfoQqjLcW^B1*~*6BExUw>(lYTierl?^gPA(;%O!XSzK>B^pGu1} z1p_lZEzi8Se@>5}5j*;lh#+5SUvrGXEx@>sX5TZngR zR2YNlT1DA03h+3M^+1Z2!^06U3S|x!BqIaW71ZbgA+I#M<&$tzqRtWg^2sNHP_||V z>9GARfq6COjuho)@@^$j+Y zU>bh!WPvoJcAa&9EXm1gyNI~G_q=%7|7~FW0ksA~B_u2+M!;t8R6?t$3ASQw`IMVT zho+bb7$%h@KuwxYzv}lo2qhEUn-U;T9SA=A9DV+g?{$I-!+6 zP0N&^O4W49-)IQNGuPofnwa0e+WqJnZ5=eqQmAe=fD4sfYQ=S61kKtKHsv~=rw&aI z7Q@h$NK=M_1H|&uN`*;UqG}|1o}b8o<%`2I=hF9*r14U32F35f1R*P(%1)Jk`7R)g z!SKGt@CkUZb$J4hfl+-93%*L>$Vb3T`h)Frg^}E>ml{w_(P?Z3zbWR$veA_h0I9;I zlabakpx1H`c9JUI?@ozv2>%2Ke18F>keGOfg5Ne0CILZ==$et--gWdBb{yQ}9V7Gr zn8Iq0o`qqea>1HGnYxiv)MQN9X-yUD%W|ouqb%ks&UrPn5NhXl%WmrTy)S*QypuJ* zQ(L^l+0Tj;@C`T0b|YB8mfE5_%MDD)ES!TDZWF4eE>M4C@1K>0cO5K7$zI{@m8lTTMiZW#W*eH$C6OV~kxzw-INrcXQXESgV(7gj z*lM1I>*TYqq5c#xaes6F=|~&?wCBUkst?7Oeyh7`6L-ee9fzH$sxW;|V}~O$o0vxG z%h!BzMy(pyuvW_o@t^i747vvJk=%}!AI-pMOw9jbKDT|K-&H0#a{cdo3rvl%*>Eal zI!b=16@sr_I>a(#KhxZO&^$ak*qW7O#DHo?L z1x2VVl+66zHQhXSn^0lWuU9AMrrOvcN~0~#UD`!R`d(!LN3(H#yKZt&fz+9PG&ed2X=wM=dRY&yWCItl8M)U!TgH0ksR2N=NN7L%HaLW3r`uFyJ zmHN+UF^Joix^L9T@CTyOUk~)*);2ac*x&l0G0^Nuw52a(;IL`psdcC48#{&|8VQj$ z$VK0ea41?9M#fTAWjdd`1hwwn$<8N)&aA%4HBVQzO)6*dnEanHhL}*O z*Y1A*x=6DGy{;v>UJk{w$DGo?^ij2*$;tzhhQc(R`stD|&RZ{RYy~9G(85Jy`8H#b zAt7i=rX}EQ{AAGQp5c|Rq8+{BmwPbZ)!h{*?-?I`7VB(i&!9)kKp}yFIpxF@LwwT% zpkTjOgKc+rcNSd>U0om-6kxLz7bVC;PGHUFszYW#TRUN1qwQBtCS}&KI$LwJEl~L@Cf21eY+-Q;;kc=>0k05E9y)sO#!6fS{ z`!VmT#n86sW#m^osn@ZAMY^bIt~iM4uM9`&NM9JHx`yCE(Nt7>Gpls7oc(MbA^9jA zOEOjF8Qb!%+-0GYkyUy?NEXX6Tuho%*RWQ8BYxS=sY*~%on5RN_H)(Y8u%xs95?yc z(%QsgXWLj=K4wjIUWz4+qLq>9G<@ga6eTOG_+?>pxd!}6@guP~9R?QheFRhQ%wa(lc?@C(E=0;@S@ zUzr)~mW2v;eY&!ePtVC_@sj+pu22ycn`=&3j( zTcGEN=ej$-K2v;}nD~yXTo|-6H*q*VKI)XnR4~DtNJl0J%F^CjiKG;XG5=(M^nW7z zv5asSG{z4H!Hi{37xvHc4+W6#o_~0+;MWs+33riAzPvjgZ&TA+c-W+}-IkWyix4*~ zOQN>tP^>M|5tl%GuD&RucuWn*wXq$l#INop=viu08XV@R@4R&^kz3q3V;|LSTxkoGJ|jiJ>=V6;7$ zBo>b0>_q$a)hQ6zwZ6{S7eiF;h*c3=v-m{}p;7z%FzqoS4dAmqZ{(sMJPv-ADuU(o zT6tQJ8&2-4A;CZI_YLJ%Yr&w=vXrd7gl#hr!}CvhWG5&1Zi@c|X&E-0G5=Qm{qrjd zt^>NOJ1^A;3~PwyCWJxz%iONKBUN?N9MKEnEr+TIvTDFB)XO}~nNc6a?=kQ0vtS%4 zgNuvHZ)V2C9|F|dX73$4;d92Dh4aolR`jKZH3W%3_=EcF#ynin2{a;HgUWX$LPElM z7~K{(hu`Z2R$AU(pk>`XUW^sWrYGw{+b-1X0X|sxt;W|G#f z@jn4~azOEyMU?XCf>QA<9Ot=Br$4)bUoC3@t@`uPS8&D zc<-#R<8hbc%Ds5IHAGI&Py|@KvS+XpbR~(2(0sY~_q9NGE#pqATF>*Jl355QRr}glm$bIDRE2p^7|`gP$L^ER4$pW1%xrQ|rVR8>%k#T}4j1x*`RU}^x8kWXN6ie9VxfG8Pa0VkZs)+CC( z$YZ}{u7T+}G%ts@ zSKk#?6b`3#vIoD<5xd}h>tUYCgpK(}hm}eUnW$Q>IYoBan2(Y2g{`-TLQJfcUis@c zIRAdb_f;%L9_aND;y8S9rbT-!V$P>p6R?~wE%FVMo`N|5$t4!i)V1#l+y~|Qd9h~E z5;{6d09U4nF*@I9|6QrT$r4QPbU%>?q^%n=Gg!bDRN)eyuFQ4ek6;nt@Hf%@1d{d{@1b1u3ztFZ(?44_+r3Sw* z(1-o&@x$ixtFy7{T3p}gX_hM6Qgtf{2q^tPvcg$R&csgkyC9&G_{Q5dXyUIR(W;f) zZpH{4ue8!S!1Th$5dZ;$c>yrU44PG2qnSJuQVmHAx@tHPx`0ybR;r)=Fqqg_#X#c~ z?N6TxXrWE2Ltm$bg8V+8NJ4kfN6WPgXGrEcTj!?m3ktqMGyT-Ex!2wTPYR*) z67+otNk5U0?Pl&CIxdA`9z9ve2kJCRhk2#bkvoSdlqEC3* zwk1qSLcSKtJGku%zhIk{8w%q(u4RncPz1pI)*pOOZm`xw=X%qKxQvp@?xhQ?Jf@{> zN{h<-7k9Fo{+l}?kta=L24Rr~fCB;jU|ZFzpEt?&{J#q%lM0B*<(tZP8u%YVTfebN zz+Xpl+ZEsn=&Ej?04ZF6W?(`B>p}-eeM-)uURw-)A!94V5{&v_wius$@N;jWM?NDOEs2Q}b<%Fc5MggN2KGf4)7G@hkSH zC+0yr_WF-7^lvhS#0Z>)n!JPDiwo|TOIa3;v~}~c0#L}SpOTIvS_wpL5j9`ZWFs5m z-mcOh(|)-8++%IH%fm5c#c3ct7GurQi|X-gdt&ZlF4*)&EOL;wLd2U)q0ZXD^~Q7S zB5CzH<$&TJuc?0rinloByHexyQHR-}lOR_^e<%k)=w$&bi~+pCcMp|Xp#z_7W9=Hk zDik1eJ1!vEQGtq0+c=k)n0R~3`A)4az*wihc4A`U+r?J{N};=}>+9r$7uw}BK!7@) z=ydJZ?+_nL#r*y~N%O;3?PK`fW<9+t9x}FBr~4ZMzW7HoH#QuG%-&*h+@O&k3l3|t zTX=m2kC*RRjZoxwn!Ufo(1Xw=x&ojQDHU28swZvcWB=7&ros|Kb5gL;pSBm$Kt};n zr5FMi4_M_p81L_dLf=4N%I!7&jt_u}`6=Au*XNgrNl6swf6X)h`LRi;=^IclwS~pW^W9E%1enpX|6`{= zv_isa`&cDb#+Nf>MxML5!@R7aS!rXfu{|EwaD=L`>W>s?r8~o11gyHaTgYz*-@25| ziD{jQiR?7#m!A-S^sW9uM-=u_-oTXUw5$mecyITm+x5wt1Z_egZQ&!JATnD}hGmqX z;!@v_=P%h!tLU2uL&99RwSY}nj{59d@49`yy%gyVhnV%}yDP}xx6zZyO9EM(3X04n zC0%X#ln~1R$w623aw(zRTWs*~ZRdzupz8K)3X=ggrj_A{wXhy&=g6M!rc9D+;)vAq z8Viu064_j(YqlaGRdMTda-%|6d9s#vskPH3ERDI!zrs)lW`5{!?;YCv&E5&}ftc26 z>sncb0j`LFtS-4NN2?Lalof2=Ks>Nl{jsoVNEvk;mmMbb7LQHs!xyIrOcs zk6gTOo%3ApAD{5ytt;h`SBX06?d5)XBtC$q!*gECxElZ1Ba)e9KFIuRC6AT<78^Jz zdsuZIf(f}eGdn=-oc!xHTI?y`U@o4k&F(2f_j79U-pRgI9HZaZq5Ayvu3JFdvZ>=l zY`=0&;?_ThQ9!HZHd`{}v;Jn2H6WkQbtw0n_-{z&e?Yu`GJub) zP0f=M?=UrGzi?H({SaL+htM@~+9=%dR9h%JE|2`V21TGrj6fC{SGdTd+{n%cLqOnY z5ay)3I-=-H&!`pg_j0nbGiQJZRp-)^OF6gi=}|W_*(##XiaZn3it*F2fx@ZHv!{> zL>RYfvw-LADbR0A%gRbiNhtzWrUalKq;j=-lr9iCAGD2MCii0gaXSj~Q!#n#JS5Y% z@Do*`xtHl+Lp`@f;cCI|sd?DR*DKq1u7awY0QU zf$m4YI8(*ygH}z_{A^|V^INM|9DviLF;WmUrC2L>wb`&4F8{`yh3~}JkCUi1(Y9Ml z4&#-x1%~7#-{t8lNhvfvN4&P^vn6jE!)KRHsTfZb9YB9`MBCgF@#&1Ax@Y@#jrstd z-k6sfUprZj-}Tl3R-&H7|P591y zJe|WX_r+Ub_LcBJBVx-u5IN3azh;mY;@3BP`cc&2piUr$=*E?Hy(I69i|&uUGgdGQ zg<50$b?sUfZkzgLLKIkz#!q zifRF!t%;X&&nQ|W?l}#SvFVVbORY4f8%`|s=zbEHHMd&T`{?&xG*>l}v9*;ns#eF9KoU~*IyL>_4G4nYRyma4fI5-y*i zc2c?ithTtLexgDm^|#VFy3O)^k$W4_j4uB+0?LF62Ha!P(+xA~Hx@pAW*Bj!H0}wX z`am>%|Mn_Ld;M^k1Vz3s8U<$o$>VCR)hnILBzml(@v@-b@#bRLuC#TT#i}oCFfZ&7 zEKbX^C7Vs6tfrkv(L^Wn!dt%`NTiJALVr#AI z=MdA*Cl;eP5^OT)yW~aTR~nGj`<5cBsMk%XjO*BO4|O_upKpaby=M<6BTs36b6W%j z=X$JtSP0`ds>}I410|=)6ew}J0ciko1OPR#ty#KZ)h9Jf5%3u{omgVUTH8`W+-Q~G zj=Wj&iWUo^m=#)iMw~4eBPT2RQ&bToX@}5A9%g@9NNY=`-Gys%ne1;Sf1m_2e5R{3 zz_-_@?6ojF1wa7NJIp`U9j^Mz9W6pjAB2M4B#ih4=MPmx~%|eiX)p!NOn*Fxg0RAg7@yK0re)pSWKKILAfGXy7 zzr?nQk5^i4&AYeaErcVR0sGZEgxPJzFD-@dS_zN-OT3kX40?m7(&Tu>@0dHCMMp=6 z>$MC&MA_KOA1d&f`P{X8nT~#|-8Xlzj#Il9 zPxbP6UmN8$C8W9RT>Ww2?KJ)?_lEnK-DSJg6lcOo@ugn?lJ-HLuY!SBOj0#V!{Fiz zrv)6RGQZxfAt&zP2ug$){B5;``sAPs9c^6?weAU0;zi`AI0nAbP_bWHH87!M-^Fsi zNt1w6gm?FKn=`atVLKF_Z%bKgaP0e_d!8(PS}8nOB|HX3}P{P=D|mHD!T z*jLLQ;CVWRwPJmPZlSH#wzl4xcixKK`#m068-!BuwLlO;cefUgucqT_I zc?1#i?cFP>$*^UbSkyx$k{~RU{ln?;B2_Bf>GHskXkRCd1o9jLMuSH4SPaBk^?RX3m;~OC25S1h ztY_7=&a^^gu=K*f{_KAuJ%D1)b6-sqiUtRAC<;5QgCc@jvPiXISmG@z++JOmCO)Af zlZ(O(uxB}KBvg#9Xz)D;R@yaXA-~Vp<1|Jj$Bf=>imt68RAk_Pdc-eP2xXD_ep0 zGBN{HVI5gn1@$&KFmSg^cR38YKHQ$SP45!;Jj#OuMTt?d2~mUV^dtKW;54+gMLr6< z@me6d#9(XilLCm)SL=BtNtAvGt6xfg2+}&H;ojNmK)Xk+ZRHF=@)%f2J2|mliE_sw z9jJ8jFSB#hbE;f{*wMEiP4AH+g27=$zbQ*rR%w9qWS$skOIlkY<`yl(7~ry~h5umn zTL%pkgN^IMWL>Ab@NgAOi1?@M^9z-Jw={7WYiyRYv$VCj$eYD2U-@j!sj zJU&1t3r~8}t<^U3yp5m*=%Z}S*OT8WPxtojuRJj=nRs8Ah7M4Hz%|u(?n;HScW?v(v1?^$TS#z1D9sID| zlO2qq<&6tVYMXT@VQS%$S8rbMaWJ)U#`>KT>rq?zHT#>gMAmoA^Uj zQv^$Vc6oC0F)v1Rqg?%}Dj3T%X^>)b15H0v{+Y*B1Xxk%cJYSmj;6-&S6 zBURy1gX0w;VV-y`!&XjKL3r*F>*fR(5pa?61Lp z_Fd;-KU_9mKpzSOhn8s#$<5k`ZI1#1M9KFN?&(IkrdSo6?ap(>W@TlxK^qo@w4TZ= zhOf@`YMnzLT|OX~U}zK*fcd#uZPpCMjMOE84Lr`6eI-X-IMFX{fhoD14hPPMwh2IwJnXRIb$( zL!V`eQ8k5y^Z~bTdAVm{fraz7F?V~86us`_-WS)CHWc&EfS0kfG$}?Nx&*asHQ@Ej z`ILVE9Na+oSZ+2JKDD_SpQQ@z2ksf{Vn`I~zX5%0L2^VtsB=cY#dg&0M=)92 z@1Eu=@$SG->i><_`Kum$6*d?KA3ffCP8N-1=s;)oX3veKZ~n}amvj@=k}EFPFE^Sg zDyXw=g`gi+fpsAGB%dP|u}=}sb2N7c9-ZN^Lqj%k&Kl{ywRB7Ru3kP_cLd(toVrpV zr+c`v2y~swYW3MMG+4;Qy*gG{ENv=mjJaW5EhDL{!16LxUB+2~R)X#Jv?cQy)d>_-npEX9{BsQ`;tal;Z92YhVN(!^!NEpoF-|XrUWuy7%BCYtWEoe^@sGPas zr8GFsI2faB<{GK9kGVoA{SHFitgr@jxV9&a1_2bl;r6x^h}&O^JC%$K{;UJHP*6@| zLn%o`&|om*;B$4g^5xDa%l+oiP>vR>@zeU1P|^~O&ZCj^!2WObp*UQ1elL6?O7@E2 ziKp+MJOB`djqT`c(>{$!h75IXV4%!lvuJ(Y&gI2nyZt50FzO7B=ya-cMVR7n99Yln z9wutAdrRYNy!j~Z3kd8Nqn%n`%Mx>PQnRpZh-mT!M>VUrx(f?&h6#NCdUng~U ze;^sBp7=?}rb-Th$&e8N5%{nX#~zw~lZ2CCBPqxXsX{`lTGa350AFDbwc-uW2x2Vf zm4gc2VXU#(q8zGi#X|G5a!X=cc`8-CAmg;l-~&@vHhxp-ydRiK?58$~@(rr}P>n^; zAE|PDyu6Rc_~un4e*FC-(E|}T)4cIzT31j+A}v)D&43m3YqvJ$d{2r0ct#oZL@#>F zJnL_CnEo;102^M-$8+M_UtUqDW8La29j3d|3pgt*J>Nylj#EluxT-m70N5`yRP3oX z5J3%t+(m8^uRM9Y1V^vm1~sX2fucKK)l*VRA8<0zBnV3a7uL}e!Grfb%qXr436r*I z8KW_<5SEsOgX1AT*UR$}CRL;;oPdZ0%(#rhR^&_)(z3*&+Rc7?z1in%KCy(p5$SjP z#XK6}x3*|v;Om_RJ|H3%6!}{d-qoe|0l%mNx69b|f8TfjhV9n|0aq^q*PLG47k|{# zUfFUUXCOyUX@c)ol2&{rJG~R*a8SEHLstawP^UzO1G#GHJwaHLMCI>n0j5e-2QG4hNT@Y%ony~9YTi%1_UC@=O|#)Y9&14m zF_Wi;G%vpmu$-LzEwb_GA==1iPMrn}*JmS7m1&+v0s))r%7TKP0cFTRA4h{DCx-9u1AQym;|6E=v-m(o!Ydx~V)2r2P)!T8W?2*pEFj)$7*>dI{ zRu3LN(WvxC-m*|e=FwtJ+1aX({Hqs)o_=6{(yph0dU9QiPMtX*oyoFVnnUt>;@>-} z2evf`9|_H&LcM-t&HXFFW!wi$&tGGFCI|-ijlE{zfMhuZ^?sPE$OWQ63^*F0@~C`W z^D;Aad%}+&u4O(yEgyG>l;b_cH$eRPVUU1jD5D##u=U~v%vWAB74f`MQMMY zSSrYDX?*bf^!c3yJHm|~HV=+eM{ip|6u{LRI+?$bk-dq8zcU`Ktm zhia+P;OHnW#e{c8I}tzL9n9!twt&2x)Sdevd!uv~e`&he6-#$;S#*T_Bx{0dJ0e0% z=#%MnnagC0wqaFl~)JkZ`8Ra zf%7e!If;pOnpFH~tdK^?U1OzgHCo@A`y!X#raSJL&i3TC?hpBN&p0%Ytd(hTULz0O zJE_nag*+Vt?*(OmoC;_Q5N9-D7CbmKZS_%(>5rE!2%kS2PixOPDSQjmJJ_3A}Z4Y(eLrt^cr8N1i>d69K`-eSbf#b#M z8@tAIh7QfMp-S2Gv4e|}Z;IWoa4!2h1JP0rTG-i>VQ%E%;NU`%jLM?k(HS<@|qhasTo{$)pIjx??Izz*_n< zB*QxFsC6VP)DG<#oqDqUsxYLllx=p=<#K&)_kNWuCf<7YX&{FrAbkf0_GsZ}SJ=n> z%cBge2w%SaAlI=0^^COKZ zgV_C+x6oulIwHUmwzfgCW_&tu|ESRb^}-5zv#)-BTFRb1Cj4@g{n(29o z#lQ7SjlMNHyWx9_WRvTv>h8zxkh*E@SWEdpX(Y~(XoBY4YuHAYA6em}>x!ka&rqY7 zLFaE`-P%qIA?H4y>D$OjN+$1Nf86<$L~}eCV_HGK4*h$>Sf*qLG<<4WI#>{koA4GI znYTLtsNRr&d6Og+k4DXM70b%x+)hybyPe}d%1_@3RNuPLlZzBam;(k!pO+BqrSz~4 zTw=mYP1fDW$s1RZCqJ0oFFhf6?B5<2e=*w&j~loJ9ETTlMz4*>>CnWA$RoCaf6eZo zw>~*6w0yeqhqh6niL#{&>tG7$G{O6}-_*=Pp5b(QTv1nr51>Cn+5WH5b!v+Wk{O?P zc^^lBp){~qh@~%+Cl_-N+-G6IL{f|+`FHl?sFw0);w!D+7E2)VLURp_fbgy3i`i)h ztDBx35xymD0gDk+JK`SppEzP>-3B_6OlGP37BMk$b*7t%Sv~*WKB% z*xYij`0FGKMNskH;-sxTPLM{#sBcudTcRvzquTZewubq=TwB|Ug4|d(@}M&y=*$Ea z|17oIT2P{W!|ihFeY;C>&Y+4ra*FOp5)_3y|JuDtPT3dQyx(-W@`BM5eqAe33j4zF z1F=@s?ZuBD(~NyK!_SJu5ODDDJ=dxw=9hXXe@Pg`0HlHBSxZ}6c%NRa#2f%0)XH=| zovw8Po4^3u@b%Fm$A{iXz@hP@w--L_3B&(lT{}X0H0ifxS3-j7T>zNLyD7zSpcVn| z-+EpQ$R(fUMr8t6KKs~d3xob~W2}mWK#wcy&^GNly;vSl`0drv%f-`!p;Oz@(^bCQ z*FuAwb4&(Bf>Hv~Mx3n87 zE~dXL126RcYF7W@_BN3&&3j4|psE1t_i}-B3gBA)ov$-HtDb>sEo%jv;3MJSw~q>d z>f9_qI-om{4*1VX`bn~5>;#=WmJ~sLmRY9}EfRwr3so_I_0gu;xwKH@D|mh=S|`FQ zP@~0gnVQq%8*`kYi;x%#oy7YB%)3K8Z@yPBuM%0Nt{l1V-9I!1gg90f#^Sw3^INyF zPL1y955VWEVoMZNA(&^H zFMG>IE^6GLHU*j501s-1ZH=3r5M4L}F{t!I4zvTy7y0bh1OaOeJsllJ;K9bmIUvZl zo~wXt{XxS-;O|`1i2w8UuN)lmsw`9n!Nx{R<~BAaqdzb4KB%0l+dDRHSAJOWH%-0v zPpcBCAjhmSDwfu>hZ`$+)K`OFHwuKJb!u)=mi&g2oR+KZq!Wae+jQxHTfMQUMEz*IkBJi`@53`4Ef@ZBLy>-0qi;OewD>Z#TB1|X@EEzY(oy?tq5v$(NqhjAcA>z&<*3r9B z!|BkD*h79eix+87g!tN_g~K!}6w4SRpFf~nx6=G#G~V$w1W87(&DwrbT=nX!&<<|y zI0R3Xd8c55piEZPn`FkpOL#<2|Lfabg|C&JbrUuC848c3z|Qi`-Y8|~xU#Y`V407L zy?sSJhizyPL&nj2VygcH3%y$|Cjc+=`J+C9$>BRmUcf)QE#>|2u3ZlsjLpM(Y?VLs%gEH1%flpkM}ZbK&O3` zqnpgA4%)gQI_-NdTjrym(FgZoyGe@zPc=C{B1 zhXlo;Ne#&=NA9}ReC8jeTP8-ZSdA^`YRi%_rzc3i4K1=AH)q(=VK^hWi>|?WVRqJ| z_uZU8Q69-INxx1ZN(OfhYtjC+AKhA5g17eB5cAT}^WsK)h?=8s>OA5bD49*$NKKdHM1Yjpe~!q{a@$uC-LL868fJK)YU7 z#ZH6nWyk>!0bCaXk65pKD=diK_o}HV))U?t?n}!llVC1ByxY{*8M(~1(%?z>LS0T_ z;zCuvkKrD*mU}@0-Zv-hU)R@ylVJgW(g#)LQ8seoDFRz6Y71CK*i5||-^t}N8`;nz zCjVF@h{81Tw{8#7?JY$qL2OVp26Li<$K%IRP6TgG`hbo&h`9&oH{yVK$Ybwy1C+lu zBro4k(e%(bu9XVX=pcMHfh-W!^|Tuj2IV5Wj4TmXbl_vqq=sQsYAt_sf~14M+1eDO z_Ii`}E&?!uD;OKQQw)NI#Tw8q{rmNIAk?M*af2A-L*>v3;;9bk30@?T&H!xv$@ypG z0t2W}wxJZH;OB_R_x*4c%fn3nJVA_=?rd_5x*p)*J$nf?FE3wQl!_P5h{cE z)VHR_bjF?+7_i`iq}?99OjZP*1vVTW=MdL%-uWVzH|>XD#lExCBaotvx0%64Xzcd5 zc>>IRZ!&f)KdLVkC`;I>Z2J#>z3UH7fQ{skd-0ZCqbRi;Z2X0iFEQ70r=z2TR;FR@ zssZd5#)R6zWI)?`2hIOAnSsYY-(ZfBc==6djxj#3>g68I#Z~?&{b!FdT~|w>tFg>! zK)+m?tM;9_0Wm1#bO0PBu+rc)XBq?W&lxx?g@M0Bw#QKUvnpp_7TPptE_U{1Eoc5} zs!);xW5gbf#W)id3>bp{aWXqT!Xe`QM1ynP8GR|-p%5OKw!mUCrrUby;={Txw`b)s zw&e}`sKr;VaP`JZigTZA|3NegS6m4QBV@`}x%) zEJBp@K$ubZT-;OG4KGYdWRJiUDzh+Qd7QR9O%?kunJAbx$8+ejTP+9!C zh7!n#mSD{gT@!jGAa+%vS{!2qPASTRg#DqpoaRQH1Fkm{t8Gp_?}THwf|m z2W~0dVyG}}@$~epVk9Fc-wGk}_LT@6mUjEKXxHBQ>B97yfnK{Vkc??KNL3&j(MD;g@ZyHX z&Fve1h!o#*=1gOmdPH2I>i&;ja^l~t1E52FZ-9!68Q~yIxfH?j5U*2!L1S+U zTB8ffr6ZQjd25_zx4o<^8tn;u0q;)kjq&a?_hsplQ?4{uqMh ziN=H&m+s(l*dLvnR9m59`$3klKn=tPnkX2Z2A2F4nwmLj2>&4!EqrAb3^|$xnZrRY zXwHXxw|2>Re{?kEw(Nt#WmcMp$S!9D*{$1-4l3+iwUL;QoeE}pVO4Hz8z?bB8UzHSTRJ7AyQNb)q@}w- zN(lk!ke2QSX$eKTyFt3U_F(Dy_P_Q%@qp`+IeBA@XWZF_rdfJV&tSLbu__C(nJkUJ zPvfafN7pD_5XCWRz3;m}_hm7$J9&STCzm#&hC6{YohQ-Ek$>)cUofoI_;yEJNxE5J z#tE|jd&hgLtcfLgXkxYp15AM^k?X}uT$`%eG=cUIQXUzI1R3}5K3`&ut8bVw0j3eTP`)TgN!2^7f5b;V(e>pdT?)Rm2ibNee%5+zS;zJwRRqxYH$M07>Avyj zS&?7Zk8*}28i!Ihf5B=P($A^6jr;0LAo2`jAAgM}eo^I(!@TrKyk-||V4H2VE$;Lw zQ*n@MaBm|Sh2Q%mG_<`5-Fo}IB@|l8kWb=7UAk)|Sx2_Jzt5seA|yY(%UYL;_zG|A z^1~R$O_Z97N+zJK%LHF|?I_;Pp({ov)*b_Dv*>5Y&Wc1RR!tk)qMK~ zzw2YY$u65UXiD_MbuVa-AL+?2jJo3Sizuzm4dPm@6z-c}^O~FK?JMx3w^)MP4LUN4 zob2=?mH~%_3X`ww5-<>dIyPrL{7zX|_+_To2!%@IZmh8BXOU$uro{hKb-z*`!P({G z;MsDPsmiT!>dru;+y3N4wBvVJ`77Sx?4IK@OJ2H%3vaXZH$F|oFQ`IphtXjt4o>Ia zz2~XG3zvb2h^BXUcgr*eHix^oPPPoU$dFaA{s+Q{@-u>gz225nW* zo0#z+(w%&H7N2^{AB~{X+deU<&{tc|V}wwp)LuZLU~-*`11Ib`55EmTqtDZ>FO(n+7?gOS1lQq*7`k>&QZeXf><2abic`^AvW_r zWt%AI+3~j_UvrzE(7eUp$wLJRAI}_?Yq%+NN?2z~=U?FjsF*TA$3}v;Z2|e8+vmDg z@4Qn1xV@jny)3i&`e*|nGeNmd#`GPAd#;*6Y&h1juf0?&lTE*c$Y*ER-9?QhoX+F2Hp2e-y1DP1}@Or5-!hl6>g(^Pa%P5$M~s4O$gg6Lel2GrldX85rbIUI1G#MX+@i1MZ=eWN(2q7@IFLen#iy%i z`iY76i2FzP4+ewwLs1YgCJxQ5ww;IkC&qCx6tsZeP=9-=Li zEYn(fAKIEdKgcj=h30O^qM@O6e#p^9)ji1{!xIK7NM4%>vam7q+T z#wkjoeeptku6K7aQ4~>pWq_Ic8u~pRn{E%+P?|$Rin~KP^p?IX(k;c5;*=8yxO~m_O5x+ zFL&w!r=S1go>j?qtIfE(y34F%q6F8ug64HMcC0!hHB8+*6;K#es=Mvh{F6aU@jSH4`QJpOKkH}t01ewL%1!6OhC^`OXN?7v!@!@7UTcTYecH_i{t6z|A|xk zI?{)nZY1wK8vBk?Y-GC1lvSG@PZH=&I;~wF72JW7(MG%Mdv8W0`D@Ks(bPRnT_~Zo zU^)Z`%+F_FN;dwjK|54cZpro)&nSi{iF?1n%? z`)26KXx^%=>CH6OwvTo9LwnMkS7n%jm(O$gY5Z$7AiYL!eFIV$+2d`Bfm>E1? zKL7GX(#y>aYnc5{^k4#$a^AI07O_I~Lb0C0IUDMqj*X;;OGGY}Hof_m>OE@z0p9#R zJoSSF6BO0i@TPC>1Q;Ixc=P5=AATno(9}X)sr*HGGF%Krg%3!w66AKmyjHr2ZcO@| zmk0DGFDDD59+1`0^m5&Qk7agm`J<+BZ*h%<@%oY>{Fsko=6I^DU03Lj7nzQrND-6T zXg%kK|3Y(TA}e~FmyhqGaH4>d<_p@k5i+=W_xtI#b-=eA7HA(`r0F~Ft7G}*)0|OziGYJLkn7g}6ME|2yvt*8sEH-hryCFOzXSzps+Y++{bF|`v@KX?V z9aTH!b02_NF1&~S{y)(Z{&FxK5r4d>f!c(PX27(w(QApk<8H~ zry!W2Dn^+oB`)QBa>*zJ_nx3~CfekHW^8i%5&JY=*@M-+4^$7@N)7OLt211EeksC- z_#yFC_6^`toTIIRKI2RhEX5cm(zd}6VvAQ-znr|Se68Qw4I~zBH$~nsy-s5u+E?sQZ)A{!L7}*DxzW>7r zQ-|g2i^Ucz!$aIJlyU~=N8#=*B(!7(4;Qv#m^lZfk?uG-Du99w1X!HM#np4?ktnn4oo*$%w=ZRbF_9eiW}K%%W4z9y!c>oV z7qA)mDCuj>qMk&h+ zO%(%zg1czLz1q;~=-v+qj#vcuA4#e{>fXGXhwu1drg!~$)|2On+>MjDY0@i>=v%J3 z+1*y-RPT+@&6y=f@B7jonLuBs=?^_5d>*$r7Pd7RFv*ScUVc z)C=X$3=hp5Ot~X&f!Kt}V*JcPq`7YmFV<#M^4JT>TACFh(oiKY*A68EN-C3&wiFuNSEew#JfGqVJmqe&og%;4fDpBbq0H zju&8gJ?x4PM{e?necw55%Q*Ob`9Ig!5Au@K@1+{wQgcz9$O%3qOI71`JyP{Gz(q-w zgiZVz94^agywL|cO>n4Tqdt(a(Q(9olZZ-mwRzZH`=LD)Jx&ZEdWufj;IOVENb+ra zIXfXHlay)jp+b;>I~pBX2`}I)TNP=cpvxV)UTzo;iSpOxY|DuuF|{0 zw3I|w5I1%j?t;mztg%t6dW)=}Bi?pdPi(ic#z+~m;b8$Gcr#z+_e1RtqRNto7m^mM61luOi#*r5Xi`pP3 zCSBm}{GBrs4I{7;u5^VJ6f}F#LP>Yjv#nI_|fs0(;>g*V=V>BV*cr> ztD0gD3T|B_ezRgqnkr}ghl1zQ!yxIY_~27HzY1K5-CkPLbGp;jPAVMU`((;Onw zGbT5@c{183d8RllI64`ANfD@gK_wdlX+>U4;Mj>YL&EQYeUF}>QOIc5vhzTAZep|< z9y)Zyq7QpQc@^@`2B~2|MTzhE9hly9yxKtmlokPQSxEr77+w$ z!lkLfSFJJY$PJ#!lrVKR>u}Qeb@}vCWuh}1V?T5=*|WBZw%KU?%G~+jo2pot{2s(jep?hUSi3C(l7&n(xW2xgCi3$7Y)A0n7BpJAlHFV4CiR|Y=1H2u)#OCYSNjc} zZFL?wOGCMcuG}UellM|Wc^f_~NCOSmC%jxG-Bdm^B-fyh0l1pW z5cn|(8jAX-dZ@bSl{2;}-FzO{0wz;*U3Abdxo5@Slqx7@HHC3 z5FUz-8!K8G^gTwV9U;>Fq7&L`DpgwaM< zU_!{h+L*MZ{Ta57k2u!oesXINj*N&WVt2l+9lG{=*`oZlB1eo)9%m|iZ>&zOlT^@g zm)XEf(x`rzfWR~LQam2}k$A_=hrZ60*S(zy?EW~F4FQwdE+>wA>DAn0WK4b>~FiTP<;1DeCF!R4i=MBt*;Mm zw#WMp4--~g!8Oq*~fC4)}z{`*Wzx?y}i+d59e= z|LqteWk&dwGJBzRnX=yZX}xO=p5M&Dp)i6&CuS#2kOceLnfjGxYubF1OUb8uuB|%H zi`YtKIcaGSJr3V}FnaSj7_~^}?nZzvM_PgFunJaz~(|Te)kJX{dzme+(`F@DbP(M6`l2rK3)R|l77KtY|lD^~otT*(g-$1Y0G5z>+oI$opqij0NHY^b~Zu02YGTwi1PQ-?xuhL4aoz ziPR8iSJ{(_-3`UI&2%A*`Heck2VL*7*Mfo$?UsXQ9VG)ZSo7TB+|WF-nmv`Vfl~r@ z4%R=_`%vj?MesY$cLHHg;Zbi@bM4{LZP4Hz4xgrJ3Q3V8*5BpGJadhMVGryELsb4+ zuv9f@o`|Q!c9(tajb1~H-rEwe$DBrjVmSHyeLE(N-nYPJZ&Rdlj2FeBGVu)7<*e*1 z|3!NRA*41dH|`4y>bAYr(H)h>J-Mc@i`s|flem=<(T=GI2{Jb6M)kg;@|^G0ovs&6 zr6-`^v(+~oT7o$i>D83Yyo*uMSiuc&0r6ICI zVB^WkfuO6NsoGLa^f_DaQHV*gIIKO~=Z_8*3JW6SG*uyIC(v8s|I7(g;UOKfwfe^eZ@gnh}Ep24aMod~p8hefM2- zk2Ru*B4*Fj=j0|b&G+i;$^>9(RCFwuoXZo*zT9||rO)N7>ocBtFHGN8s}^m-V{bop)86bR&a?O&F$vk(7{tJb40*MrELzPDYpx zad-jcxPR$3?U9hr5$;je;A)EepIbr-9Rwl$c;{@t|20CNGy&BGx^N_*1*%!uE^|E^ z3wkY=92q^RHzScg0|LDsa&W`*YFgn-<+Fy)^WND&@0gTl9ym^q~bgaaxC_i!-ngKlA z7xd7pm7M#`Lc`LP|C4a{4npi~DcClS*`Z6*ATKEuTXa5@y>LNt$6Q`A2+KP6B~FQq zmF_iZ*l0mK>6nJP?f@e~LBV?C)83Bvs*o-nVOcy}A!@yEYf-f}bb@w=Gv&)gEX+E7 zN4*?UqgLR_x&pf}kV70F=cdgJ|!)e zVOF{lGXQ4-12HsS2O^9ZBFw9^dcsg*sktj@U*9~3Vwon$%>Y-v%5S*CfH8hlU@5}P|{Q4TO zH@!)HZs{<&kKB@6t`%mCKdG2M3TI^iP`UbE=nvZyB^aw8(}y>n`M+*W>ohX}aur7; zsJ8@1F)oYcKN-}2h#BZ)y@z`h-plbVS12hekn^&-z|vZ)EoK~`)mIUwvY12k(0IZI z0_uUI^iJ~sR?-EFLD7CRZZQu*NfQa$wS(nNy+onq=@tR+*HVfW|51d;O!!`u{Zm#t z{JX=|7WH= zaNK-vrz`vr7%L5tSgSwINyj$uZ!6LMbaW7aA1reHgeHlVmX?+0n&bX6rXBG%c z7H0E1d?c#RTLg>Wc*87Mv70#wx_fP;+In_o3wcxur*n+XGIm=sjkGnkGr@Me21oS% zWFH11{8Eelhl)SqlP&ou-R%FZq&ZB zZ2xEpP|iklu>q6@Y8d2%-{<=`+P1W9p_sT8hoEE9_&6XmA_5iF`(rsR^yZJGU((W~ z$d7)VEb>$oY%f;vLYOK)_tL-Eq|iO3-&hKBtND}p?VsbGy=sIkc2~1?A6nnx!x~cg z!Ymg`3#mQo_!K1J*3;k11p&g4N_BfG z(}#Pj>oHJr@)f!^Aw}a7C=OVLQqTICdU@dS*hR_xy@01mlLp-Z%fHFB?9;bnzSCz) zsR-e+PDUq5Ro8P(yuyR5L}HHK@`cMfppBJmnfA1Bgfhq*JyZpA#`+Q$fi=k#BHM9XkiQ--eUAfX8<@;hQ!<7du`8z#niI9 zB|TDu^yn)?24Det6!`qa?= zUYpeOX-jU*??Xv6RnRHWkqNW9;L;hE{50Ax6T@$_4Sn&#*`YF>%{fH|@f!<`P%fJZ zB)b-`^8K)D7qjoSmOcx1XmS^Hc)jkMUU~-o((jX4ykyaK;@upK{oSUv;NuvvrkW1u z1bzpj_pcz#O_s4*+bIgF^nEVi){+14h>>+lxf^+6;$32|)PLMz3EhbGLp376gMhjX zziPPnhmD4RwFy^Ie(8%Z;P#3&N_fbsz(fRpF>-U!x#7K-KxZew$69Yfg-9BL8{Z=M zYZ2G$ASg!HB$@07GI4vk+I$7OtsKiZG7#LCXuBf02Q_eL$u85wO)s??HC4`q;> zJPPDtpexckUYS74g3C;zJW4%o@cww(C>T#+ z1xeW4+z8&Z&_z$8nx%wNAO;XZ66Vc~pmG+aVTr=F8I%5h8>HKo5SP$X{L?u)NjO=S z`iL1Sv4Lc9r$2>E(cj*xUB@nycg1z2c%MY=>69UTQ|VGg}ODe2^Ap3KG{ z)z4>>AjB^ZRb*uy`O;s2?}^y;O>ew! zZf=bKf&=m#8%k-8L>@w2S4he z4CfkZTx35;Mw@R&p)xR@X709FffQ<#A@VNmhJDAS<^xP8)}jy7r@!AZ2O$GR=)&eq zX+i7~KWfy!mH+GOMIRs=e4xHWieY`MlJCVi@!hqxF%)>aJ;B%No-_*$6BWhd^5qkq zT@HAn3@#xqyO+ox+R6`YCaUqn(T-~|Qc;+;{@Hq?Gr!pzFXTW`u;_g7{lnuwB0o>r zkf(mvhC^>szySA)rEF8vS~iDc!QV+QsugjG_!j`XfJSlSqp+gC62e;mUOuD@u}+>_ zgDMyWC=D^iEVGH?#S=OXpgDE)2mg~=4(dZ2@FE1?^8z*NC3dsJ*_UMo^%#WRM;C#s z5>ok$`oSBmF+hVzm_VXqWATU>9iHbxisR-tNhve1U@k|Q`1opbv<=h32ZaB3j6ey8 z+HbL*EXCRXt~&A(OaGbA8#}w6fmYy?gz0>pBZNN{@K{vxNoYr1FQ2d0;>6wL%eJlh zz(3`y)M8MRarVe?Hc~S+Hy<+@Wu+i`RhD98Pi7+s6gJCiJ1L^;jyoXH0Lr%z+yRqg9bK zlCE6l_tcaLLM*d}QTORS*pbvr1Z>#CRzx1LBcVaaA(hGe_2)|ljy8v65ptGrzhy>Z zr_F{hKYHbG@h%~QOD&(jp^E;P1`Q7C4GtVKZ89rH?2pYQ;E;uemUSIIjqWCl*B3`M z&-OpDB5)QfzR$JKE==J}?@UW9EOj2=#sYAu&G6i3y7I!`QwtCTYzA|7TfKCkoKITZ z6|?+?SR5+*n2QKP_WV3)6&=(g%E&zs@ZuaMOL=SDei-uq%5_7+CK7L~&NG|l`y`eG z^=CD%VSvV^F)%e$YMYpNv<)r%nwY@3>>3z=FPPcbfQv;8dnZNeiz&p&?df@ic~~_> zgIB?x{lfPP-eX-aa7YNXkh6H0Sk2v40k6iHdb9B+l`x!MlLt38>lwTuGbW1!Oz*=P z&Cc~%Y>5m{KHe(+bM`;@M+>zu%z!qofg!G4!x4~&#zmBnr@GvBfJF9_n#zDm>-{aQ zW*|NRT|Wc@0JdrYN*D{>Vojxd@Ll8Gp0WM&8m%LK!_a`u!wo$C4t%745WVndp{lPW zllja3r#O^x`9y-MOF*LR;SsL|2<^f)OXHVokyGlabcZA_*GSI@2^bWYV7`F~zs@G; zx4WghZO4I+*_hhgzbw69>~)aR~?jZsL!g?5*T;%YA#as^Q}kQK;q^ z@|Jij858=ppuuQ5>I?t2=OmNs??Y!)g=eFruq54Ag6FMvM*|(=A#%pzI&lB|RzD>S z8lCT%YO-acd9c~pt0;U+fRFPs%h#$3me6X$C?O=;8y!*Zi6E%+eYgi9grMxJPuIQ1 za-3Q&vD|Esn1qDHtEZ+Wj>7plH(RhIOd|yb@jV-p{Cyt$H$PV9DnI8Z=@fsnmxR7x znLobYR5~@=IqKGO3h9Vq5+?7j{Y$X zq3BN3COwzG61*7Ts}dNsIYGsl32G-t#~~}L2<8yF|Ms|52b$)-4og$}3BWZ@u@KGv z$Dt0fLr)c;UVU>nSgHa@+33WW=lOMOge?A0Ye6mi8n?SthLZ(uXls;T^u+w^f!XgH zV6I%>*+GR3R7sN?(^wHNO*Evm6;NV&e$e0IsChDgDUAqx4{u3 za2w#zF5AZNgRHrU>f{t{Lq@c|%u|I70E5ofhIc(@12EsCNVIw&J%RY>!uPNhu>}Bt zrzA1{zYty%7VHZ$@|hzz`=bORcK%6G9eUvpMij+f;dJ&wE)8X6Bd1fVQ#F;qE=DO@ z+8ne@bdq58Nk!c2bm-kJ#T8fw}q!h3PMQd{F0Av##?emPn|D%x_x{%u7uU zXA1zjtZw>E#LH~d*5VUU&C4J;N&vl9$E3w)w;fwL`QSZPG-$L%X^$8DXbjMT5%gNb z-7a4cVN3n6l*R^>h_Fw}hy=Xm?Xrw0|6GNuk3vIfo9lhgxNc7;rlzJqCzmB~%)C3o z1KLRN=8Z4Rg9-;6X1&y}ZI-Ymk}BkOH|MWa1N$t*0iT%EVJtJ-U-Ngp_X`wy@QKjX zAp}8@Dm!w(ZZ4l%Ki;5{1_F!Tkfg$HCqJ$q2Y1HgKU?mqmzFfJIE}g9ntBl=a3Ad~ zE|t{TwL|Gh4LS1#vkPpuzSHD#0LDjH*!27ACBJ1zx71%=fxth7i==a)NW}fB^h>a4 zw)wCTsK``NfeG%2sI>L*@kuW3`6uR?MmE8iynOQ%_Fe=1*Qu&04j?*UZ!c&k)sv2< zBv4^E623Ir-wj^LaVWh{`)BeGN#)7vhP&tfrJ=t+ZqUp0_en8uf<$d>ZB8P@y z_TH%tySyLDl_koi_?!;g9p9fiOw_>?<8_0oSqrisQq2QF_6P1%cJa=I$YU1{_`D{C7I;#?C+a2rbNH4{WL(fKUWGgbR(b;jbs4>^UPVEQ#Bn;-(kYx&S>wUtc$(Uq@IwTYOFZ?6KbCWy6km{I-8k1WjCADDYB7rtEs@sa1LPBlOR>^c>FAhrKu z4kcJ^f}{B@+9k=us(~t6FgP(TAbU15aeiww4I6pY_#O+ApuBpM7-6ZO2+&<_WeozOxMbciF?kvrx1E((W^q^Mj(ephB zi5i(Iv1-11Qo2reVj%*o=ZX2^j;628MU+Uq$woinPkVGWD)m|iT_PiDN`JtLp~3u- z8I`=vbaU+?dfNpvsE@EcY&HB*Ke8PnN}}EI>hF~z<$`ey5Ghh+bwcF+vn$CeNy0Fx z6~=~ygutLF`aA{_$HWAre^grnwbVYBhnapn_=nM%uPv{f?gd!t?v{2QXUl(10ai!U zh`cXfVz!Q=O&wlD|69)HcMOsEWF66MHJPT`5{A#ntk($J*tVsJ=H@<7%Vh&nt@0!IfTVr&t8EW6 zJTZIcA7HCj17h<;phU5So6sNCef%FZOhXH%wxZ(v_*l7|Q~1IAVxMScDbMKH)Ij7q zEy@+2p|uD3Kl=@nBqAQ1P!zfdqNYMhyT#v2BXj{Fy{Z8&WT4!e?(?$nJ_hSgW`H`t z7~YU1!CD3hm3=`45jYxik~I$h5`{kHn9BKXbmI{@Njo2S=&8XXCdgo8Xf4 zVEn*Q6wHfL8FY+%r=g}b2Zh@e_2+}+KDDLs4%(A^@_zxt`w!X$?!f(Fdoif$di5@) z`kua8sTc-XlvW-FC(Z-8p3Emz_kcc0D;n4CB)7*l$5ps2j5ioJ4o%actB7RGQ^kRi^c!zZMe!3a~;T$Y7>W6hYi>b zoj*D%$Os81c5`9?3a%aLG=r^Ku?n~jjP7d)3hL?a^5cr09)vP9J_18i7e}4GH+ryxK`B&odUPI@KCSwWg5s91tq


Xyq%ybM0eenqA8`|?$F+Ns9%>G>J8lN*n8<;S_asKAIb z88`}~l+hzE_c8?x#;?9)3)ly>pT*nUOsFu<*^;%|_-OxKa9<*jzNph0wM^kkAODmK zdS?xphw7D{>B)CrQBYjow>aLe%Q_xmtuRv>fRLn!IQ?`5KqGo=j9LG#qWKyU`)==x zo4h<6aQWj6wDQ(Q6fLW{oVzx?kiTZ+F+p>e;!kpA?5 z$A21nIo|ea2gb;He%q;E4OVaZX7t`le7_)THGxAzui262s(|}x{X`60I*yP1E&Yd| z?#4Q}a2`cjdksfwO>z~-8v(Gct0g*xYl`yycYQwuf;uBVVXYYu4)M2g6X=!83|=Mi z7Z-oAA&9Cvr{CWcFtuN#gR^1&96FZSC%8kVY%S~kYCP{S3~QB=On8dOo9Uau`WI!6 zi3}M9IgPq>=7)B{xkB@^fsb_MTF>O_c{Ip-={UrBST7`O&I_K_p?_t*=+;P!RT@9p zo;N@_$s#B0Yk%G;!7B0hjqFW>iXl9j?1)TzjyvyokZFM|)do^-Gp#LoqAJcLshM}} zwd;;Wj1D^B(#h&nB@VkZiuZW$0}yV21oCyV_h`k5mm6BOCHrPy1;NGs&1{L-GKjAb zFUtXh*>L zWow~CZ&Tixg9J4Wb9gH>B%yy?B@3XHYHZ^OW!8THi5u(io)`e|snRAyY_;R-G{`(tz&6J*cZ zH<8_SuwPptnX4?)e&EZMDX=0$wISQSg*&FnF{6Z#y>|msYP3M`@79Po3mb}W z*T)kEg#I^WwzV$vw0JUdDKpO?W4t%WIMx24Ak2U{Q~kmFEiuH30s1JLfdD5`OgGWg z;HqBuwVFR(GMn=7Q@ofAZ|~*`T0D$S8!!h0-z(5Sz+&(b3n-tKXf}&i{F|omI~44i zne~RfQLRRx`L-BT%xkv%#AE@HcA}#CEwOhY4Jvu^Sk!Vf`YpE)_ZNb~56{r@+rZDd zPJqK7SfL_Nj<8(yn=CXl=+qDeoT7O`r3(n2**P;t-@$x%36+z-B$$Mdnl6u28uw=ieu*gb#Os^^>HeFC-U6W7 zGGtv2_OmzL&jg8%rI$CuB(ILCmMHy71N62m}Gg z1*3K8{GO<~cq4mJ?fn%(kGBtK;Ns~qU=bKNhEQgh0*z@l%-zp_?fTyO27di!J4k7b z8k2EEr(DHK8thDC5>~BG`5;0v35ON=ZzpFXh24Q39(>uGe!FH;gH5QdXTpVK(7vIO zkuAXI=i{wccNrgd+eVegWfAlDB3upCl|GC8(177C@lIZp0rAzKvwJGCz&*2nZN z^!JM1*7pp@U-?YO0z~7#1)PfnhZZib#-aN${tsewdJRPz1<=h32dX+?dEAk@S1At! z_CLyy>obdD%Z;z473TI{Yw;pJ;sUhFuR(s$TtVNb{1?GSM(r1R=2V+JEQimnaU{au z+*pL!zL1}B*c}8~lV>4s=t484xPrCBQYJV+rdCEOd279R(Ltk&K8yR$2@spP(D;n} z2iwF-%sN`ohnDL_YJhmtj78Zvrpd>gBTvuNy}w9e_s3|;RHv|JfUGd&IP$?Jg!2ff z%v7f!OA|FT+6_iM-XO{)mpx0-*{)uMjq5YXp2$0TlpsB*P)hS~_}7H6E4aTNsm^O( zl{J}Q)PK(h8Zgjx=^3akOY1Xig9P~u&;WPJ6!M1wp4J2co}9Pq>AvT?S_TFN%E~eF zv@Z{IO3Wn`$q{P|8a8B_u-a(IMrVZA0;5#e%6hlSHec#QpQd)52v;v9zZY-`;t*AL z4b_nf)bn`GJlUoJ`r_8FNQv_%gpN?22Yml&wK3!H09Js|aK&e?yWeu2O=~dG_a*~l?Gs@vB<76{=BQw@vknfJ$1d^P z7ZBHe`fmlzD!njYc)UFyrBHGQr3M&D)%x73)$cC&p+t5E3UKAbNed`+am^}q{P8eI zcYS8OY7L6{JbrngghmhJ@i2P`Kb63Ic}#Hn^+QoaG|}J3ic|yUa+COBcOw5tsg&`g zP}syo%+3zO6dYY7(t(%>Xz2#K!f-jleL!M|;^$0SD{lFTeY1mRd3MJWLM^3RrxPlb zlzJJHt)X?Sy0AIK`xv*ei8qaccdknDR_(|Af`fQ_S1n-*tH>T`v($Vl+kIU=YLs+k zQs^9_R>E>F4-STlbR*m4#T%Z+b8A(@Ht*tzb))wCw72_oTfN?J@5-50aIE9aU0RMz z|BiVVf19MV2IiK-qDD{{jwNSAmPdU}5(*J?ZdY?d+kV23Q zqNo#?33RH0d%)3~^rJ9ZUs3MOjUYk`ZZMsRJ0_Gl>8sPFds@IFeu{`Vn5ZGvfmzCh zs+$83c)@1I6DwplW>a4eC8yv}d-fm>gO#5To}289&}kCHw_}V=3(peDF#O>83Rw`j=qH z=3Gl7A-DTPnEw5^OgackGJ8Xrr1~vhuc)YA7cpUE+4*eopY0YIm7IrKwf8gD-td0F zWzoZKz(V08c;Pm-Qqiz5%TDk;3_bfngIPC(34qeqL~&dZbYEBo!jyBGAloe@D# z_P@qsqwX*dC%lDKev7oD{5%?RJ43Vgy1vdXobUFnjt&zO6~Mq~ zq3O@44JrN|8?9h2*`c!5(tEykUUAWFGp3r%-VD5tu>MkH+#Asq@zD|&N#zrL;2UfS zUN<{7%B2(BfQ*q2ygK*3=|g31ce=KoJaW|~l^13rPbJvhxM|pBuM=9EWeYW;JNDU4%v-V0V@e8@AiSpFr(#5v~^CwEA6{tqa}@T+@vU(=O9KP9v-4fRuQCQF>1gUTQr?HQgp{F^!( ze$R93%<9yb9$?OGxm*dGn$q-oxXjoiTmsqYAn5ju4JDWb_Qv}ZevnRwLr@~17*2Rx z3*R?B55~b;{U5}Act``Ugc(^KL};C9us`DrSJQzqy6ps}%SX+Mst$JO=vH?o_iQ5b zOaMww_j)U#ibTFR5-2+_yd-a>eV#{|@3pFe4CB6;7)+sEw4Bf*DF3>q{593F{lB_-I@v!yQkc zp8upV`kI|jy3_#;TQD?42>AUEKP?L714#)uN=M3la)J0`d62FgPK^>7JUan>gyPia*vMVfc2T#!S(($KY`|Xq!S@BB0zwHp;?E#LK@`7s)7o zQ-V$R4bcT+cNw&`o!L1VT~l~V>OO^8hm(m?hLA>%Og&~nHK>a^ z>V@uN#2UVx&G5<9h9;va2#G$yAOgCfzwa@r|1LyvD#Nhzr_{_S5uq1t2UnIJKfzL1 zyiC>i@7-P9-^+BoMO6?r75$%vTpA8%2)_qFWjvGaOn*NrGubFN9o;rirJD_;y5C+_ zG&H=r^;LQ;pQ{PT5xFmIfPf<+Bn-rictv!XVmUiek^jPR#l-Ii>@v)s9lBZ;il?lo z$k={Z!R%J=TfK_ChU6`|t~quo91y`|n64a=GhC0;4>NbLtA<2}zNyI4t|{E_wJv!x zPP73(MH-rNKS|tnvV0t8fEpyfXX9F$P3FG#N%uj!X&-xE^H)tp3@Xb;e)PLHb;ki{ zXqhetEk#oEYL(0>|8D|=pAr_v{_OsgyN{-3^#pFf+IuG5?bGdP4E=d~Mz6_z`iuQO z+EPFF=<(>NLa4f!VSV)$Zf-eu7lyFcs(E{xk?I{!&O zK!e}ScnP!?C+$4qV*a<1Q0eDrLDodbAADA<;_y4j_aBrqP6B8GUkPt^agAxL=z|Rv ziP!8DGpvh^E8&M)NT;5}&Ws!<`UOeSFqma8P8qZtDpSCsoGJGl&17%xaPqAqwRbqX~;SETLKwk1yej;W# zBVc}nvZQzw-?sI+>M=owceBL{IUf0+#sXa|KZ%XyWh80bk;0&cS21=aB_$slxix1s z8?f#DjB&9w*OEHQRJ5Z_Cf$R)781&gV!vIGXu)TB8Lpw>4)ziad_^;kk9zS`;fvT@ z(*++TC8m6KqmF zil|Wvc{n+sP;DPy)2^uAgl(}U;r{*Umwt^SGdTrCRu;L$C*qPC1_RhRs9-UeZV{p9 z6bQv|ld(p|tF44h!ehosUVi0hF_jp5>HK^uvI7jF&jZ=iH`rz4mOg%Pb$Dqz@=F}B*N_rFE< z>Z2bBK-PGVulM$79uv98)c~Qr@MrtT7j!)6aq9Df2gy$CKrUOOBRuXyb`ZS09k^zM z8tcclzJ&1@A-wu^3|7OF(c_g#fY+*$3fkAOyu^Fju3b~Mma#$N$L97K@I5Wya ziB|Jc!rUnT@Li40)yfcrpYP*Ja1GKk87a2pTyewv*<@zIM#eF1xK#s+C68Uj-qNV| zjM#dTlDrLD<5C5WW~gwhE>7HvP}EY(i-1m2JuBiIrSPGwh8HbwmPXk2=~X!l@D?Jj zvfkKs%( zbI2__WaVH{AY@Nr!b^j^Q-eS0wgr<0$*k~$iH|qEjS`X67Q3K@!^&-}c#G_g>cC}* zy|+b*B8V$Mnu%{xT-Z4X1LYNW6HTg>em{Ybi6kuw_V-W^qKk9JLaf#e$Q$QA;D)lb?wd@FBqyrheUdj;2{Sz+5|+}ncT`r3u?0xng>TPbrny)SlY(({x4YW(C^N{Qx!nl)xUYUC%{p%E zEAe47IfvsyoaR2iruit9%V@>6|gu|1V99@#p79eMxWxG_JmNMl&G`(?)_Ag2Rhj(8bL z=%-|$Zt;a=8WIvbmm`wUqg3>fk>SSVKKsgB!5D+}BjvY36U!s(*7Kb?knX6Ku(VJ2O zR}{F0*d#z0qHCVBM0zSUV-2r5>=Qqr0f;i2Ci2vC5<1|5S2vA5IW z00_F>^;EdD&$pfv8`%?D19{+I#nKEF=@u5#I#;o=mMkSM*SqK^)T`y?WfURa#lb2*i5=Z)1PE}gsr~s_D;VTkW(G- zAup**#G-GF3OvC6!1nn3926amsi=qv5Ju!;g5^=Lx;;Qrk3`56er%An0IBPX z-y8e!Jw z1A%sjQPXY2rnBcl_B|49BR#Dnu)@^=?y1TWz+H|M(xc#P@A%C7`Gv7mv3FHu`43SL zfM9R1Yk?HgSc&akZ`-;9!4hs&v*X&X8&P5sy18A?KNk5F_}Ch(m(e zL+>&W0Le!s@IqIRil7nfXrw&7p4AJ`MJkNV?(OcZpj`)G{EBg#iL+5{ZUsqd+_Aa? zpiKg?N=nN1H=QjlE*oXp9;dgmMt?sB5bO|v!78bJto90!mm3+G1HgT~y`W|d4IJo$ z<^@2lry(Ffuyv?SiWd%PJq1RJ&G6xzOW{@sk03Ap1_gSY17w4F zcaKg2+23FdJ%H6=d@jIe>&1iO5=>?#3BO~7}htn0%G46+x0h3=wCMlk45O&+P z5DrW#PzHt+2jJjc-q5_Yq5q`MhdB|KjWNVrc4+c zlqZP$_|^fSk9-yf$-1NHnVg<>`_Ub(Tjx|-0>NXtgWv(yDwITQm8|wlVbs9QpTA9^F>3mfhcV|4i39#GKvFJ9H@;uHi1?nb!&i7YHJ&J(*qV}gz zd%M34&o5LJ8LTJ`u;6BEa2?iHw)=7p#<)Wot!OarWfWcrwS`prvmJ-YDT6US2- z+}=se8JD(AGhQqSf4}`-d%p}DLS<=f9kJ$20o(SLjhELR3V}t&XJOJP$&4Wa`f*N3 z_*~)`R3CN*;P}S-cbepi+{+N3o=QnV^D=_@I0{toYCrG)oC%UIK-1HlvAnjd3|rM4 zmPqV}eR!%DeENzQgYe>HZ01J{ZB_;fQEx zBTeA&ZCxUw0tVIm{-h_O0x=4{z&(?akPxWy>O{-{K$|`Tv8}y}j8tadPMQMOSS@E6 zdECnbv#Em4iPyi?F9x1aT8`~&)NQY?KiRTRgnVX6*!qRp`Mq-YYpDoxQ*`Vr>Sdo`x-lcv)QV`oE&=wo%f^Y=kqlsO@8^>t)~~sFriO7JLnl<+t6z4 z41)me&ZDPKfNm`b=+W{B&?TRK+$|5bhinnxR!E|&K z6iaFasudQv*57X5*5Kq+jssz3fmvZyUhu=Wp%iZ+Z-cEw$P9y`yi%!R1s3nV^Y$3A zC(G;tjQRcPZhNt`@(JahYp%OidpEmRrS)2fMn>WOBqjZ3$YBgaF}RCH_rT?S3D9Ie z;n~z{^$c#B9n#`L?aNQ{K9?K8;w-UY|Id5$hs0(eIh4W%3!)-eprbU70e1+ZJv0{7< z;xp9W{h0S@F8^FMGPCuWuf3n(?;ZGi$GH0o>*`v&xe?~7DS^aBYzzz*fTrU@CZygy zpzAn+RsY@IgzADcOD*^vlnsCN9%?U@SyJ+$wl)9&NH9u3k&*iA98lWlC9%I=OcHHn z-Pz10EC*oJ82$GtPX;?Z)3w>951=-Pps|}OG0e)!(uE^Go(D2^nXpaT>b?P~VD>O$ zmXHAn;YM&-*=Z(4TK~DURDKkq468wM%~Uv;-%r@WqO}cu;O(upVo}if)oK~4v9SYc zyMP~z`tR0~zfHRVqwmyI&GB*8LusgjB_NZzvflhbwwj^jL={#4dgGl}{aK~AwT?-J zEgO!J<&{TQuhrA}sRnfBAXdG`#>$p=^7!c7{ggMBXCtMGf{JU*@trsi^h&MDIo=v! z_zG2dypZtWmMeXILh&Rp06+!Js#nXIYONTdHw8R0}AR0vJ`t)cj>T> zb=f1IVFN%K^FuN&ZVjLcX*Q&a$Hpr+Z zxF|39I%9)wSS&)f&Z>X#A`m`uFHgGml+*8GZ-$Rna#`hE<+?)Qax(71QaceV?RNi0 z@T>F=?Kk=xS*);(9wvRa?4+g6_>0Chmg;pfl$*1iQv;jpb&W#g(*)(bC>VL^DYP9Ty>wBAI5TWp7cg+Vv~|0iQ9UjBStkXuT3Sf5i~e)zSQ%sEi4xo4+!)J zYi^GZ4J9S2zk70Y)F&Tv zu7Aqn34;bH6_k{8w6r|G3Y^i=!v+Py%fI&=&bYfaEw3RzdA^V9gL7GYKCJ@RNqWFK z`mXukgHm`}wXcYb>X`BsBWK_!ebRPJZ*I?p~* zZPcGnd%e57q(N-CfLp-`0A?qb!O~G|de}?vTl@9#6D(8gn#D_`vs;_Gxa+G=@?@}l z9?#y%|L5eW7TmxLjLzqED+&6H^sv$+O3&v2TzdZ-!g7f0iTWm?sE{I*<&=4h`)dI>Cv?uQpyyf0SgqT-%3$t0*mBcZHQ>!>d zz}5OU&uNu3JU{z7S#+bh8gBKw5BQ%uUKdkA1JucJ zF6=RDUH#4L>>Jv1apT%P*5-zqnit)KCP6D!`W)<>hGtu%J;*iLyv2o@(7-R>(IzmG z@)%hc(CoF@FtiAK*uqUz{st0Oc!cf84@bey8?USwxft;}CxV`j3;GBNy?Fa( zh@FX_suiQeZzNy#0GaTSu7$-GV=r@3&vWJg3i?j}lXCN!N?B~@*(n)JE{5d~+0#A| zL+w6(&>M1^O)hBCTeQflVG)3EX?H6^(S>||qAWZm&|{ZSnAQLNylGG97hx}0?j z(2KgFsP2JvByL>t)g^?30!13Uc&rF17Gi0g1Po?JOW>aWPfrC(gqV4$qNv#N0G&Ux z1gIc~QI$a~iyKd)#UGcZQpOY))hvZ>T6lSRWyg#7S3bA&3(c4*^hL$8o)vobY~O_z zHdW(Hjo{c=8jCF#$NBpVPAb|d+UodPc=Y)YToVWWCfxP`puX_mp3ATQf`9}y zgY60@Ok`k!rDXcyc5!tj2p|{$U$BZ&%Kv0Y6upI~CJQ!Tp`Wp3`UzQm6yypU%9&hJ z!d6(-xSM>{)sOh!cl@u3&SeNYIr-l>d)H~{NlS-`VON+9e*h!{`7j!Q3Z{0ImATc& zTT29f7ez*2pbcTO+2R|2=Wme6e{3Ne8H3~X;a+KI_uTlF+oevwt39tr*N|LZ9{@xsc= z*x@eX?}!(fkO+o};&kRkgU|qSAS~SP2F{Q0@lC53uDt->Al8QcR-wBK`QQ#zRN4MJ z=gm$>yE7`g>+@)+FzREKc_ zUb?yVJb-)2Lq-PU<3Be$=AU9ag5H1aJge;gZ>I5oe??w2;CnOQqjc%?(TW&}hul(A zv>p*@TUZk9tEx{1>l@;U+^9#;V!ZylT=(t% ze7}4V$U~egfAR+}@XvVd=Vy5e3?ib$_kwX)CA2&AlOJAz4h}-Tz>{1QqG!P_?hl;5Tk!2nf$isdS=xe?kwr4asY+TLN?ne+09w+4Vc z*A-3|+r)_p{kS=sKo44=~yLiC3tcEbo2fD1LQ3jVAlrD#a`{&<8dR{V$GwA zNTFQ?4A>wFSaHN~BJR^(#$p92P#`8-I9bIEoA~or`v2<`10c%0FJp^a3EJKR0Kpui zMCKY24lb^Wy84+Xarkf7`@iguGUAIDFKB4b+AQc`J$e%yNGxcgqMxvnlPeA|8f^c^ z5&ZL48!12>H`NBE?SJjgpKDQ%G&Vk-keHaoM{Q6~SVsBp+5daf)X>AG%O$3Igx-HI zdfOovNK?~80dsIxZQ$g8p0h|{D=QuMO9fRaC^r7xRvUUEQPX#~gLfQjPnNo=7TE9C z-q6sHCG{Ql-*wr4KlcqktdEaRgjlv962awOqhCRjrqiK`e$|M<=ym=I+DnmwJDSawTsS*0nLhoXTv2KL0fDtdd^W0r^{zAM&z z+O>?nA3nU@1Ul$;>jc8X{_Ar3IWQFoG71WI-r9^hDgz`(QB{#9`rYfd`S7?)rrlIS z(ZXV#5>v3T5C7-d(#Z+G)P(95>SDj2(za(Ij{5%}^J@ZQ(wRj?RSgX&2Oa>I-h09? z-*pXt{MmK?&xcIJU)x5?3#-Jf({``jE`mas2NCI*>MvUni)m-`zmCk;zifqyE|y(O z7WDgJrA%@_V7X~j495DWRo%>XvwyP75wI&b!^X>ApYO9lv z&i2ey3kTpO5NIznj0F491S52Q8NcsdrK%?aYjQ^_{UKr$p6^w*_wHZPi>Qr~$-Aymguc@kSxhA{~1U(DSL3Xf3 z=H}k~d*R4yKU9DRet!ulgjtTlGc$MJDSbLBig&E6!Zza~erlqV{|IU7l(P&0i65G{Q`>^t=fvveDl z$_fz$1qBfi1r2T3qLNF*fR`uL?mxsNYTgOEE5#IvWyI31V6`H*I%7N10ITYO1Wi}& z1IeC_ycYVkCn$Xr67c5O-^V)c?=NmYHFc1d3I&85rKP104;>;&_&nE#ST8P2Q&Lju zsMUTQQ=2`U`2!!qf z^No!SW8)lPe=smImI?-mWn(sF$3b@HP+S0@8`6TJuC6SShR6qi>g(5*RFNkmXJB9^ zH#|Fdts!an((Mgmfp>wod@amZnj!gY&9pcUUjDhsu20o8b`m9Fq~$3AUhuZNL{EE7 zdS}$(Q7&o{J6F90Mnythbf3R*_}V|H8BfmkEPpSsy9FKTpMgW`|d%GK`BC@4+!e)Sh!(g zM)&mG(7_g%ToLA(Vt02FBu7Q9Ph0-j{Bx$PD29YsxaipSjqFRQV7Hu*INp{ZkrKs1 zERlro8kxCVEZ+DhaY4IWRm}1f;S!9#w5a(@`?>S+>+m7?G3$e8LZPVWo#b!eq3Uav%u78j`{O51Ar;~chl{tS zL9Z}d_p?gae1K}z(b`venTlK-pp>$;nri!=!yF4}V0k!f4ekf+;$i+<)DlvFbQ~7Z z7WXMMC-sU9wo6>B_8DjpIKgC*kmOs&X94FI$@$Q8X)~kZdgfe#Kr#6-_ag+yGkMX3 zkNfXs1QKwBHF?X~<)+^2g@t2$s|@kq&3RL}GG{D%eCYdmlusZkYrhF+ullAvOOiK; zCY|ofUc5yO!@}OE0!xuaP83$%wyCt3s5wpD(HCDsj(Z0Cti7nX;)L`+ zM23c%pHyPpF*CT2LcP^rF2XnZxI4wwCWck(Qz)4stFoi?6D!aI;o`%~V#Hbiq{=v{ zFzTc0&_mtR)6-32V^g)SF|pxPTlW%}sM z^~5aAz)QB$kE!~@A&eroa=o>Z1r5>~yu8DW4bxfh2WT=TNj_VIKg}2FobpFe(ZuhL zTpgTe9RzGL<`Bxn`Q-ZGT#}xNjJtb&a$C~m5AOvDQhno+loDq zimlDxr>$*$u4aMKWq*Rh<{16;O-`cTTMQ=idT;Nirh`@%77X;!N(lY$ew8JZo>sz| zhq8^AURwy19>4^0OtrO5SF{Ij06L()7su8|AncAZygKyrKa@wCJOlp3FbOBekud% zxM1+cf|_oO_5&_|LoMzv&g0}eB9Gv?L-I#U5(3#P5=VqYDX*Bg<%aF|oxLtS=gjfz z%3gC#!y%{1W)Zry*wIjlTY5dG$t4&t;+t%L>S(=N!)dL-RGd?eU((_>Q6^$tKpoI? z&Td)hY~&?4+gp zdgB>oRSnjg?{4;d?3)&v#Yzc^T7XD&WP{;Z(E8q9q{-HVSB@0Yo7J+2tAzLXD>{e7 z>0ljkn979;Eh%WxgTds#>>qRh2@HRJ77;-|x%Dy)!9jkR@9^z6ek*|PMek*1T~1D& zW`dU=)nTTJhxG;C5m93$egGVvdR&uv0zbhxqnfJ>J38li&?rOXVFcu%>$V}aH~RdVg7cUWx!9R?js<&7WtTTXRnTKPrdKxV;#L zUI^h7@J_7aEE=$F@7{u=+O$hJCapY;LPqit&| z8jooOPMcqa1{VES4KeXugu~syYyW?RJqDz{ap!NG`gvn%>k`#eC%L&!-t8LCo82o8 zFQ9;oWo2y>6TTGXl?c`p)$&$jg4inZ0&`ZLc}a{37#3=JXJ@;kqE?VCJkPIh$vftZ z^Z8(jGH&)!T6k3{F;2ov#Iynj1E>E=yNknrn4WaHEAOsqvt%NHnwnLV-p2NG^PY@h zk^YZk3BQjPCcdEo8N8HtaxT8c(pgb{^`{aiPvUy=nY}w}ik6m62~fN&onFc#C(b@v z-(${7N!YP&D;kSmsj7eKDx^Y7?3*$ZGtt7g^F`il3JUEUy?k`kplB5S-dtCG>jEQF z67!R&S?kX5euRKw#fq+`XQv$ZT1uCi@0Z zWkRLps^QED=H}|5R-Pe+wpSap^uq+@jnO}xXRRvQPd?Lo7L0}$M$~_#4Zt*0vKijY z!Su`jo*(IYE|Sn-GpZcoG;xutV?NY`g*`JhU`!cJ$s`bp*V%EBZ^7qlost+aE(x>A z+yJ=((D9E1ckzP;EmeHEt!JnXeFAPRUASx40Tsd5@G!d=)6+5W{=HNSakq*sxI)bR z#Fcj90ng6j6k{Q9AU4p%Rzb)=q$8H!o5FZrVXsR{2d_*?U}?&C5(}Tp%;D zo02kOA^{D|_6xMsg<3aHdW$$^$`|-gDsGOL1qE?v4-qo6ZPJNL^#qFLNLHYE(-Ma*yN|blxaIG?_->4 zGc%*JJ{^XKuQc{cDVkxEP;NsCGyYmf+6z+ldhJ!;I;)tTD0Mxq)-drhqSB=rp=UAc zq|--KRan_nL;R~#wrQ*M!HjVBkd^b8+-`-^mR#)`35%A7gcE0K>xicNm(rFzSXUG3 zo9ZnH^GGbei!9jdB2kPuXHM2f=bDF{`Wul9KNtGDLMEnX)3S?=o$P+D`*Sr-qkj2< zEE}y}tv&XR=a0$B%3M88*qguG=7U5*yHa;A^`kMv;|!0)v&1NO`P7ra4KBBF{gSRl zJJH`3fMA6K^ztQ~F0Px?Od9c@xF70;^pTo|V&}|E#G_I}0@?_4XVvc|JYg@UHh2k# zcez)3>5k1q^Qb89TI0^K7A~ZV?0b%!MSbF(acrEV^5=qa@tVf8xSLcA{8XM+s)MRj z-;bB-6Dc3zEkN~H+Vzo7N~&`Q-c;|OLXV-vKx!?Vc_Kt7G>aB9UUf|cppG;i5Tr9Vpp)-{@|s1 zvRc_l=d^&OItiZ^sgs4V#v6&bd07-fs)3m$Gu;tUG3P5>L{cJ_2)d@3!3R=;t=5uV zwD=bimCOF!jOl0;_498CG(+O-w1jI6eCEtUi@-YVh`2ySfRzj0_tM6k>OX=F{%r0C@T}} z2dQ0Dv3tr>8z{n6eY}%`nc>hWY-!JQH#Rk$R1<}?CG^QxO6yt+wtl0+?fvjh`wF!- zR5vl?DM@FP)mDXQFTM@ucg{xb`F8(mXAAno+9&k`l@o6)eG-l9zr6U;t`Jl1pOH0} z@dE_(u4rCKJ?CJ;wApUJBNdG)n`^U>sx%@iD1=m(eevH#Q%<2->y5~nbuqcETHQfK zE)KY$>g%Hrt;`Y;`5yRoiyBrHgH7ERV4IqpbnU;h z)(&c!E}1-fL&t_E1L>*n3nJGuQ^5bbaQpZr8PFp_!_P!p zT#1*ap{=LM+XOh~*)A!-We!sC)qfEX3I3drU96^!hcPsMiL&uQM3GsSp!rd_`;~=g zK-SJ2j|PVmaSxfZY}}!w@kV&rlduoguGG8KyUJDG#LpMw%bbwZXz5}DsiR`?d#F>iC)Dmx` zD75SW&sK~_wXKd>YyFOg#TF-im#>${q~_1jxK_vfwO>c1lD>()0G zze#HE3JV}A86zqnV<3d5%$VCCom(--B;JtG~ z3swi;1O3rXkF(tlM6JSu5v465=bz}RYk=p8dJWWeZ1z`W;9pS`K*Nh;z`ddX0hW+$@R^v9; zQxp!HYa+-(HD@%if~6TbFDAvU%F>?H1P){RtJwE&`;w`o+<+Ybty^aJ=*q!OSbKvl z>0+Yt(m%N0zKy-3iEL)FPy4RSt%OkT#>?~}weNSkTPD=}b4zhngDp!&$=MH?x8&<3k;H+ZAH!Fo7JZyco^j13UuYBEG$In*1II9Tm%LNPK=F_9l5Ud zClC3Q!h3doJx6{hl{|g>SkUvnTDY9V%*n;YBH%@LyIyb5@-~8qyPhvZ?qEQt%6?;^ z4O#P%oHJh+gc%cZi~Q79@k2C#eg0LJfh1xlxh}#*_P_UdeWl z`=nbBb)rlXTgwzTEiEm;fcWK>=y)E$XN421(*^|E#Dl z~U(g1QiHQM}Ug|wB9P;Ye z5&V=(%resECSN7S#4K%ZKZt`E9~wQyvSR^g^Vd%tNWTxF24w%~m^tR~y*;oOM`pr7 z>INLp&?-+yefgmN3*c2!fq>jkR_*7k&yri?Saz?y!$K;z44!^6_{yifa0j!Ytd;wT zPuHo|l@0TKoMZQOf!|5t=qbr9`hy@VIY~r@Y`CCNGDib-OkqWyBwiI2m4=fE?c7?Z z?g0AA+5FwDD^MPHa1hc!(zePSHf#4Onr^Z4 z{GFWgeN4q>0fp=@M14^v*%S$TBUO;k0lTxZ?7=1>2fT8FXlUm5M#kgI%g)@@)m0dw zO797^SB^QoCbmSVQd!j2(#-Wm$@(knA zaH?%nEkJuySNAOJNhaPLz;JeV5a|OHc2D+%V9>C1144a7$ka-~+m`|WOn!kML`X%{`YLqSf7p35B1Q5&wzW56ljG6#*j~rfkDRm{9`WK+Xjyx-NTiZ zlTAm1e5{SfBloKE7UTK)-WPB^t@QMtAHaV!=Mb4tSN&Bf;fjN(mfxVn{i9k2UA|9` z@~J8*S#RVve|Siekb!}_a)1HgV-)CNqv4n&p|S(#MX0;0uWO|edrE#CWF1lAg7MZi zfVe2j4*}hm59}Sd%4aqdQSS-&M31msdvQmK%VG@-k-s^LGA=qfLvlat(ZbOhAj zK4g0Y1Ox!>S67!aQNuu=%P(|8{%Kl^JB#o6d3y=lXFKM8oBvcyl{OZb*O{)~>0^v_0$MLLd*I5|7oVn8N%+@j#SoDI~6epoN;QyJjHeuT-+*awN> zl{6K}5xt;9tXC+*{`s2_Y{aQ3-fjPBUaH^U^vl=_GXlS~OdD3Y@B;ab2pe+JCuF1= zT3o z%Umpc)eE`(D#dHM6IAg7tqlz*AxI+MXRNJbPa_D&vn+$6o*lDu05;WCbhbPF)^cW& zpNjkA*PnEb!uB9)>W=AY1U4pWgN|tjVXTs5m~hC+rA2Ce>4V>chL~cm#eQX&$QltHMcRb($;N9^`T015I+Z<5Art$dpx zQ7rA)HisiLqFd)nJF^VqbX5cMQZI3^*387r($#E`fRn7Is3oP7Bw(=kObAY=>JpNg zs|%n*cFHuID`9UQ(~XFCNc+bicd>CLx-`Usyyyw)c^kk!N1r}R*tOEJ* zA#{NqSW@>CpnU-_WpNM>cSar|BSd;62*ivZQyz$dP% zI5tDo?dEN>BmOTXF2ekibd=B40LDEP8B2F(v*Q=mHwmpH-vWJ#m{_J}2^?&k)RX(F z;07k{W0*`l(68bR1^~yXv?5$SHu}rt^)UXJ`E%UrC}9loffHAs2S@APhRh>X0Hl(? z8C(kiolONuP{h_GPDQ3+x%o5!L%#*3E6Zgq>4h|gG$7`vc3Q}XMqiSH>dVgXR*}s)%)3=CTM$Q31Co5y99d zqK+~T<(iS@^P)CIe+!Nn-nwy7EVtB0a!EAG+?;XM;L{P|m2o{BJTsbSq?T4@C_^6= zK)Yy6cL3gbLGm8W+1J-sLLmixUs0&@Pvv%q7GPoHf4s9PhYSbeE{@f8h0kUqNnn)} zjUy5uzvShS1fiYQ?$vaMa(?VuO(Ixu$%OUgsXCM?_-1WjbZtrRw|0d~h+-F6IEo-E zV^d6GYSLZLO*YuhJBean|HY~hC)J!5sBz5GvT#*aHkuFAxj0uA`el_ih)S`bMQoQh zRNAD53u&dM0_JRME0 zG8^r04cTu;(R2!Pt4w~6O z$QQk5^BCRhDqo};br+zUyAJN~r0Zd2$}*G?`q;2`nBeJ)UPOq8>&op30BK~cRGnFc z+mNCsELD4{g)EIJ0rrZ9vbyext|TEMV{(#~MB;aQ4qgUE8O=n8+4lVrVLLt(OC@xB z6Q=&fMG-QIW_%BOO$I)!MF|7C@f3_%e6divfdqyeJ)@;y6eg3o3dlgF- z=V!h3D=zwCU&|8hEeT{_=DKvc_<#LLg`LR&y1l)96yX#htBS>TJYQXWtm)`zvYOZ5 zpDOh1F}n-Bs)1^{D@qmeU!a`Ti{G6#da{{5R&$aC^w76xR0i&_9w#BK9re_(642nj zF~kp_YhUWC(+VMLtd@yMXDn-52WU4wQo@Q!KQGlA$(FTt%K}yBV39Uv&lLB~*nj)- z>9s1i-$VXNX6=gWuHGSgUNF?eLa5Y=XEr>=FOfLt2@3^1p(MpZF{Zs56-2xu_!Au8O^6weklF9Z&>W zT}L}S)q)ntJ{lgWrtBLsK{JpqBcghWtYK3F&poTAZKxa+#1c+obp}cx3eHL=r@m0A z9J#G~w6h_i zxhG{$?(fIEsK4NA;35X3H+Ng|jWoylZKXc)_UZC=bKQ#!0Ih`#&_!ba{xYc^i}dG8 zoy1xvB|>IZ1nwBzgXrj*l{rgI`$ejSK=3O{3WF;H7TC#gOTQI&*goAjqbm${Dj5^@ z0w6v%v6ry;qF>t7E91dgaev{AO{f)Dh{Nuxj1L%nuZ?bu(YA0Id&r8o=;dkRofUHS zQhQmKb3A~=ynj5+y-0N>ooI4x zn(L*rjgEd#a`h1Z(@6)Ely&aqwpi^u)4WZSB{TkK`Da2}(*2UW&935CM)0PuWKg%HR(VKYzzzY;~I< zgr4N33G2N0sQHi$4@`-Ovlxx#s~z8~Qgh}#$5Jv=Yf^I{s4x~aqZNy4JdNd7z`$g@ zF~jSvqpit><4L6AxZ3$TcV+S|ZLWdXhNXyI0G#RfqO~!xV@;d&8aKO5r{JHe=_s9>O(-9fj{Oa9vXnlGn4~{_SUKEu=c^G_a)_t zek8v@E!|(<7+_`h*+Dn2jK|+Th^I*3-JUN0g1BZ(it1~2#9 zIN~9-cXsA{LRU=(^Lrj_?nrk95(6!Il1D;o6ETo3jNcuC|F}1vgCtYYk>#GL}gPnk|rad~{v%?I_eSfWW0N0jq>j z!SOeM&`uP1zL*Man6WWzHZ?MJa!NvZF?+RunZztmQn49$3&iBd1`wM!`21|h(kdN6q z8Q;`3$p~iNeiOJnPL70|V>`5X=`qn-*Z3`cLnBk``1zfa`0q6^^yf>g-&= z$naQBBJDAzCNdHa4-Zt|I-@?lH_Q)6#_$LWZ>^n~z1lmfoLNIgCLsvaZ4CYuN;Dzk zF-_Ijm*X?1OH;$1Q9>N-05eD8e-+Rf{Kxf9lLkW9vsm%Rx8!_R#RY18X&W*9{X+BC z1$=rQUS|i(?DZvtfU!M7qs%X$rsZpEU6xyY>Tw^Dp8k*9ON174|-2Qj#2=Cck%9-Hb_o3T8_C>$lzuInSpcOhVIl}o1MvLEkcbi!6 z!uM;=KaaL9W?n%-2PR%_4!~Q5_4if-)*65k1HM>FN~(N(Tz6z<-UpBi^dMUCu)c&E zc)78NV0du5*bBT32IhB>K@7K#@i8|(PV@d!X@Nn~pv@fJaB!5*LZvo%&pw9ZoN*fk-)Z6>xtLH@5CxuVa!5{OeG6=O}Amxaecsg-h6*VJe z^t4n4ZE!?_TIn4b%fG<-8nnOLFxb9gW7*w%SonA}6D{O4NiF1$`xy zgr*5UfBr#D8Yzhu{;#X+4TGOh89L|bzY|tnKp+zq5fRLzYE=#n*X|pR*28#b3oA|ri-6Ql z$nIHa468nZ*ecTb*X}bA^8J@dP zp>+b{cz8HO4WwSR`N{-zVE&Yg?gfL}~-glBr;Dnk*URYpQKXx&U(59}{E8 z4I;d`+!F${_Oh!vOL9#lZ9_)_XJ(>zfNM358o*5M8tj@gzUJcMTyAb`t>_)>8~)2Q z2&4IK0qvq2!I*K7m6BKg2Km`N^aXBH)kLHvF~g-k|wrLLrJbR|3t4lt5rw{#oab zt9kF=Z6Y2=M)CngV*RO$72}4=IYFo1(>l{jZ6c3HVR+R-LpVOv8` zOpQUBL4b$1TG_YO`qwC+d`KwU%+ox?j3r0xc6x5SeJv;F$&Qo8iRmo#jkeRX5=RXt z*XNHTgJ5ftgguSGCQM(3G&AtcTR%|$PA1x+-j`Vb*!}0B$%aPzY_V*`R51T_zG0=M zO+Rrwy_Y~!Hp|LP^=DB1YX2hBAT?0_xNnnLd%pU+*=oTCthBU*F{0?P2Y!ynR;LWN z+hU#0Ya-*WG(xmBxh!`l?{jT_SYilx{{jT)pIiiBOP2%cdTpo;1XXmK`OH(7^FuUmi`LS+>8)ZP7az;^jIVcn^0+OHT{;6Y2An(p$JSd%Rk?2Q z!gNZvw4`)*BO%g_w1B8ccXy}K(t?0=cPv1<6hyj_?r!b_c+Nfd8{Zy`?f!@DT5rr} z&Rzm_B=nRrIfVbY$*uRs#=E6!nJ|p7z!O36_R9)k$=vvE; zGgktG_46JQaVa8tg0&MK;-E*&Pq(NMZvXGuUl)zrG8q4j)I{V5vVV?9e8+n(BPNHNM^q|ob3g|df zTmq9K@+PBEQp($mhdL$(oGcoG+*HehCtIC`O7|iSJJIXR*Wmg5I;NDmR=Ip}VS#7z z!&f#l?=eKgMrm-!^}nx(o)QI(2pPk^in~P{r4gTOoTi4Pubt<9>On%UTIOlXNCFI# zj~IGTWw#@NftbjgB$PB}`{&L}m3QwX1s8Vt4(=YC-zaRKy`NN-<{kMTE)t60ntWG) zNx$e?1pyd~78f*~-Xz@bZ`YzKjJ^LIYX3Rfpb;(FLR}Wc7>ZpqLQ$o8Pc(tf=B zn|PC_m^|3H6uhV6X7GaIofZ2Y-jTf{q^gC;{ufi>@h?2Jr@zr^14s~#;SY&;`${B#R%zZGWliGI9W!8 zT!;8L4Xlxsv!VR=s%T+?hDmU9zfg1p<2gh9n_Br*vA2V%wrk$?7Ku_9Ed@1BJ3|?H zk%UA<1&+2xsY54lW&L&Yno(GAZzOx`0%Q~X?Qd9YANG;#%*$7BRI-|Fq4tbfsqV{`_v;JtFg+vzzW!8zt#EKP`&>!vNMpXM5nO)N)ippUd>Kn#8;(7VkMVIU zszauPNR(`|sUJpd??wLW+l3+>)U_d%W$Yhg1dMe48((88qp|(!gfjnSN`afeOXriA z)5zNRvESF9xT2x~MMGil)ms+bTDS6FC&r-Uhj$}nXjiUJ-dMF@Jo$f}gz`whohXCb z1F|t>-Nfs*R~o!m2fhSdnr-oFXB;eBPE#C6&N%28F{B}lOOT~-BIZums4JUrG=|h? z>S^NJWKrs9NA|04Om;qyU64W~A-j{0MQ5yqnvMpJkFLaPeFg0ODUH0ZrJmOFBI>>! z4sS&6_!=KRerzv`b6DpSC*xu9z6iDk!}v5u$%r{_=-N=aAD%$q4eH zH}+Hdq%hK95TD+z7B@U?J~>SR?AKqa0oA!>*wXv)q#J~o0>IKQx z-BScLrH{V70R=o^)m@{jeeEcBZB^0v z?bX4CzshmxbeF;O!b}xc9X`u^h2zdp8ei=2OU(?pR7@huQFxd}`Dy%8;j#LM1TY&0 z=o!_cp6y9QJ9{mUJAbf&>)Er|*eg(&oESLK6=8&B9@{E+E3cskiuL{jEvVjm!bp2r z)lKF8B&oug)cQw|a_!Gl{dVT@(p58@w>06>Hi_Y0)3?b=?J}4^NT@6G;nP>W94`GM z&MvB=7nhLV!rK7`01k^b<8Y~dIDG5l_R+Lg4;E{4Y|Pr<*B8r5`)(gR$u!KM1#yVF z|6lXAR{$?pYB_r5;jryhw zR@rL+e3s#`e@j6cXcqR?&L+6+0bOrkcorYu^=LGI3fK+&=fp8SqxUuqaVfq$r4Ho( zPPH>Wke@A{n4N8-`m`1kxKy7p51^q`;}n`Fv_+s7n$HgVvsBtEG`(1>UWlN#lX{Q*@4K34I#Yi5}C=w~t?b z78`P+uJ=`1Lt~3YqrBX9V?&btDb0e_rwV9bl@s&uc%z-9p7B3|neKa{w&>u6ZTT}s zys>;YnKM;WF7%OP$N;;^Wmnhr=!?=gC9rw0tS&IR?3#sa{_xLpwSCtUr3?>M;N8>P zR*~d@6ROat^01wS4{bg)k?vzF{nOLkneh05G?5^P+fnaFd2SB-b8lL;5&!P(mHvA7 zGYFe)m>zrG^V+bwr0=Y+Z*pUwp?%);B{ngy zf@y)C5?ZUzy9cQ`iT~;_^xt3MBL$PM%4WOHUj~(6PgC&-&~#CJ>bGt;BMWU2`LWZuVQWWKEn8V+Uxr8edScO{Zq_iMa)@935zmZqP( zSVFnWpeqzxv|DfGGZAD(Y3XH~fwHeI;ssM8(~n#SuTPa3m_%6#+#HIJr#COP&v+kV z>6hxe-`_zKn}|d9kN5q%0ER3Z7T=%a927d4>(wf{&z#FlzArW%pWt1?nuA_=(A}iP5bY zu}pZc)H{6#cKuL@KeQRE6!Tv-Csme)k-m+&e;9z+h%CufO5TM}?*tI%D*=R9SjnkO zczR%jMI@Mx@v%pK44AWDTlmk!01#X;vB}pqZ^VDbXO`BtEeSEeor_+77?CpEoq~^k zjYtsm!YIPYRyx;zIltkm-J-?&>WXE^?WD$(y$GZPOF4)jB(x+2t&h7B$dlutU z4&kbgsddW0bDDGHYw^EugpCEv`(_*^T!P*vTcuUG!~T9F4j&=4A8GtK!-i&SBmi3S&@49%Uajf3lJZlS9bAz&oz1>Y@mY6h zn3++F^Rc|&X|TZbPmrmTZLjzEE8yR?lwcO53&$&jr%RwQm7CKqS)iR4_H@e%@ z8WCTkW+ddH`wTPK9E53kGr2l@<>b-eQdewY?v8CE_}G9B%-A-18jJlaV3|zNE1MFF zsx|l|&wdpDJx_ljXcXv#`Uf#FitymEYmtz=6uS#V5%T=~t}#&k+p`TP68bVFeO`O@W!gV~DlKY27+UX>bp)#nso;|H7#ry^s(C1WieF>r)n ztgM0_NJBBvlP+gkee~)$VYJSCI)rJVi6bSF;x+5U@td2j^jWc?2RwF@!sp6v;qK?p z-{;fbEiGq1Y-RjJY_IEP#;s*?Z6)Rz$&wPVw*zedKguA!P#;@$lB`U|Gi4DDDV+zuR$DO{(qvrm@b#8cf z^Y^UQs`=vU%e$660~eZpqMbG!t*(Gz(MG#(@<$e_T|I>gT9Q(A0X;~VWmKqj%6XD9 zZsI-s-V+a|81NifWxMVS35Geu*R~vnrKY@ZXa}M(kfk72TB-@^*EguE>*L-i6jo8< zI*(|O3uGkpRQN5w9@2l#Au)3p%v)v6S0Q>~NBn9*Pt``!HiWimp)_`f-j62CIgD<6 z9%atb^N_p%3#UvSz4ho3|Y(iB%}LUskdt$6%<&QG!yzjc2-LQEy8OwlmC{UGO-0; zM)UT;oq8oret+~PiX^RfHnbN&_dKs0BVy~E=?Gr3R8o}B#!|`BJ-PA zC6@X{H$LK~YU7TvVPWShQ3Kv1u`)+(#+@vt((_w)LItt+8aCQeK@wO^#B_3b>!5tT zCdW+P?t%AOtQ=-}D)8}QkDTxmN2dLiV6FluCvF0fsiGIz;os4j+eljv^_((?vSlBq zRLo8$Bf*~X2gQtw2y_$DS9->ei8hiWfLt72?=S7?(@1~^#2U6g)HM^lkyK5F|NkCN zd?`>rCh1C364MgTYPmD`-Jc4|0f(_-Y3vq~Ub&#>R!0n`;)eQaSHleuoW?7@? zZ)Br4DlD3szsb8T356O-c~Khy0_fCHUY)mu!edPA463+JmCIs7UaDOEZIj|r`VYNX z2l4{hmo@8pcx%PEbGI8q&0^Kf^qdD!1npA+^+K|BlM^%CLgxU~>3(H;|Kk?uhhs*G z66*aEO{?1$uRCDY@5{AI!uHD#Fm!dUkFP`^_SM@a@IFdmCG#dZ)7tz{kmylmH#Mrn z>U9UJ{@#9aBM5iu#Qki5#GXZDwf^IX64^y_+EzAty_02h z!gpdw_^#_g$27gl+AUu`3Q!5ad`dBgHrWFZY~Aj&42^CX3nKD@(<~F#`{Qii2&V4E zP2csjG8+_Yx3xCM-&*$_m-mB%@dZr@|28I?NcZa$xM4q{-?$!Iy(4QWyUUuvp7DmoKFlO!h#wSsvQCC}&wgwA- zh5&d>lr1y)Yn(`bLC&^6?zx5YZh%I4@iHuh$aj(Bj5`qWz;f3C3l1b`ZX#Hgn{$)K zNisgqw=Ukj6+bPb&wG%5XsR3MVZ8u)v5X^yqug1iZ%-aS5riAghUmo5c~&^z8GC@- zhB&e!w(F76jlE}duLtNe7NG4D_okbN_p2S4KyHK6#V%yPTF% z5;!#ZZ$bi5ECKNQSGu)dGlSL4an5q+PL^i>?j)&v{|Jh7llz??2KjYI6DrI3!9Et> zghBnWQVF|9S;Z_ElNV!rVp84YdPwxBcm8nyX{}qePu3UUovyk|+)BUG9ZL4V4Qagj z{9QR#g?niCR}?NT1?of^p6UdNiKCM{^jat?k4M#%XBYst?wcxnXgvYXwU(TvlL!> zw(YuD$sP5i`flYVp)SVuP77GLM3r3z@$fJGN-C3LiOM=L0UiDLij5*=7Hl@6;u~qS zy8az&ri&7EbYfI=btxdL^yf&<=4uz9OuLzYjKdJSpqLXeoZO?Og!ivPkjgrB?3lg5az#Hf5i z{HlhvRDL8XFlyk@_76!xhA?hd3+~a6Xv|%owPw&WIAMo9(q@FI*k!Ru_S)EGzW0-q zo8bJ5DK@l}M{)<;+PW|Zc}Z&E*y#1rADRRAEg+*n2D0o)t-HDs8wYpHIxEa;%W8t)$D)cd_ z40ruIEIuaMV5IlO@n|{$Fo)Y!8@=zQJA>B=Tr`Qxn0G~{0HrAS)(=1@_&k6GMqB* z)|Z2|4j4kR?;MSMb5F3@J`0eNcfX{9Or6xHSW5?Bv>c&}tWoUXUeveVUiIr@kfd_% z0nuJ8eOeFZtQh= z;#=4i6-Y2zXy~!AO|W!-+?swLDhQ)7ik@_233xPOCXxKB0X}d-K2X@N$y=RDESP*0 zY!`R!awesNKFr20&W`3qgD9VYzWDrrw-K0e3&c>rPK(iqIWAAUL6fD@fR+(rl>KXm z;U|JXV-D%O-79&QbJPq^o}1`bbK0$QlNs3!X!37iLww4v8+($|do-VkpB{i|^dr9w z=C^56gzdh!h<3x73=NFtRqt7TR!$>n%LnWh*zDFIqY^(_OnT^`sEXjV1|Y;)8lt-~ z^ZjiJaXzGQJ-h$=(op}D6Vry`&9JmhhA+cvwn<$d?I*?YHNJJ9b z@ODu)1+cOp?Qmr>O%y)pMKLTp=|9j@hdNK5@Ci1WyV&SGcYq+lgfslsIPGa^q*DUg z7x38(WT6P&bofc$ULVl0M$3}f7a5i=r$$Yd-_<;&sQQwrErb?KLv6k)N;_`UW7^xyMiu3|E;>^7L5HNHO?AWZPQEi z(9@VaQZ7p_Tx*B!LhhPf-08;)J|PaZXZbdoIQ$xbFw?(g|FGO6ZCVY8;n-!x>kodZ znD}Z$yu~>3M5_P$lE?UzL3!;p4wh6w@subf#Wtjr1gLitST*CRE@$sG)2ZbL3d7jt zf0}6Y=+|_S0cQ)0_DwtKn_jf>(#uvE0Fk!Uq^5$bsEyjYYdTXi0;|$PwYD-s!`NUn zEwA+wnHN?k{#yDMN54!MTkhK8kEXZ?jy?6T3Flf{6`J)%`Pg3E#sq;Bevi z>Q|bjJ_Pm8gh8d>-R*thA9Jj(!{7P>c@)s9!Z@K>4oSewJ}RFoJqoEN@8yIKKly%Q zuirdl@}V?rx$Gnm#$Woz0^+^2Q@qPcb8g7KPJs{m{c(MTIL!NxhJ9e%q(12HVe6LeTR##d(1ee0NjO7 z!ptPAWG5qNlr=4&ijF=jbqkb>fWVkl<6x6(uz>s{;dDy%$j^5RF$Ql zD|`}L_cGa5C>V3_8=|q`7-|Lq1@o=i0^3=^H88DjB&(|L?j>p%UL^7*kbwSX`f0)03JG{VNMY zv}FrnL|I=lzma=yZimWuv;NDDRfch*aT=0>NdR^N?b0)d68DVtKlo!G0fxRLu+*8y zO7+E-Lx8qQ;E)0}=esZY6G2ZB&&D!&1lnf~T68hUlGsc`P>&lC&GnIAMdpcImm%Ve z{aqILn2(e=*S*t3f&Gk%gf*M)qb^{hS70{^X!@9!Q0*?xj~%*YmXRLo))19Xp2cq- zNZ>>^JWDY={5=!G4>)*B78zQ=^@fF^6cj#(?(gh$`d8-`MBrks!*PvP>{?o^^rL0s z4Gj=pq0E>}RDSa5t>m2x`8Y~LUc5aitImGKdv$6&E)7sl?$;rQb;<{Sc!{@p{@Q$S zNka@KV9VLG{~W6?WL-NdUdue9;WS+|jUYE!Gb42IEWcM)KB!ZsHWuL4_fM3V5|+>2 zD3#W5mp+AciQ(Q7;Ug_#tSSd#p&j0kg~0emM0_fPrG5JEBC=san5XMP$%t%RTGyX2 z5qcl)8-pIJ`EW6~)v)0>{^H2G<(;aWM=Iy);R5^Y510vAZNiAtjj>pSY|KoP(oOB>I z)}S%rYtdfW7PNwcHd*TJ2r9lj$lC)PRn!Pe4~?_OBFTdnpeYt|kJIASCH^U@t`;lt zt4lr1l4v{U`=7X17d+pjeYP3#yUF%DUAvBxJNE_ONN{cdC0sj%g=`=nom`8Bu%Ml?858a$S!dJ=0k683$7q){QM% ze2Dba((N(Xu^$94y!HBWwdd#0;JJ%vnb&6m%Rhqt)HBm{e|J7u{)Aqs)uzw|DH9l zg9r|=5P&3~A}?(wYGD^s8@&pTA-1iS_ExEcrF)KkQJMI90cGh>A?5H$1>Iy6KC;+qx!o$zFx;KHF;N`q zvz*r4nXu(+rJ!fC87a$3+8PIua7yI31Xw!r6WV&;A^O9!K?My6HujAsQ#55zx29K4 zyvQwC-!BrL$6}<4H1C-XH#K{E>~gDd1l=8E$4^&O&IW`sv?Cp3K>UxpJ7iE88B(#> zc7+BR89m)Qq|Kk~HnHPmXXm~(^*X=7aKX2mW8#U77~XfW(yKgLBk|WLr;_;~ah;RZ zF*n~(o%Ox9#WwSTrT*Y@55vs+ayc3^&Kj7EhsT|lZ*NW`S91XNlkU72`264id?yVZ zwXGZ-z6Zfx9lviN*tn9EbPSocKI!2!eh*?6Z<8k`_~al~Ug>N?r4;uE=@wYbab17! zrvyL1OhhO$<9rbzWxtk7cXF}Py#oeoZ_ztff`IX5DXEx|{R6Ly1mwe*lvYuP{G5skka2dbl3haNed~zB z;mqpT?@89dZ$ZHq4ObxeMEz$1kaGV;X|dB-Pc{wL7*Ww^m&dyyMnABKEn{T~=ch z5K$C+hr~;sIYd_$`IXMS|sw;JHSe% zIk?XF5(CAG)TCXfQF6A&l7U5;$qE<;iIF00{u?G}d!ivZfDzym>5tOmCCv z$bx@L4a!?uME+@H?W5t0yK^`bE%gL=`l?Jiqq^w^?`ER1CID6&EM{yBeQfw&-@8vg z62%t&UN0Nzu6iUgD(_Gs@{}SR@=nz5(!1M=b@WOKAq4WvVQ-$DyUrG9yghjH{n8A*CeZv%7`C6E z_kHtL^*}+Fy)REzicq{O%y&1iE>az@Jce8Btv(iMWx)xZ@3(_29>*hvw=VxJOjhz@ z94lX(o`0@q!q@G%;-nsX+R72bRf@Ag7tYvg?MyPP@# zLII>Nk?Lu_Tx;Qc`!PezznX%8@b!K^^mC-5`fo(vzY9i@1j&W(TGp~d5uSIHkWS(cj&IVpu<%^%YHbzvn zUp2nmf0M$ZSNHQE`oLxL7G%5rOIj#1add(A&A7UUCEqcICUUM9*FC8Og>IYhCy_o} z323n2%VwC?4b0z0kDsOU?M8(1(cV`c5YF&hSGpM_%rQ?Vq>WaJgScaz+f=Xz>z`q1 z3@+x6+w|}6M=W(vI30G2pm^-RBn!(@V4xIvkFhuIJ(KCXjDYb2;~dXzJ$;!jhTwX6 zu>;ZGzIY}$yelz^B((8lH1>0h%<25#eDQ4ks4aI}JPBoMlGh{V3Z?Ju=}HpvOZRaB010EHsR zm{(I9{T+XgD{q=|=~{7)x;qf40kdLcYLc8AF42~1e|rJ$CFYmsBX5oC zuTIj1t<0w0&7Z=4{2;LeR1*{*Fy!Q(CMD6^6=oHZF)|4OB-w6Xyu&#kTcU%Tz6mSF z`2bdkcYk)jTb6<&68e3oEEAr_o>A|R}l zFQRNzOAXkKja7_aufQ*ptt9P-$XdRu(gbGNsgK`A%zRd*9nG$ss&$@Cn)cx+^(irQ z=Zf(K#qI?aG0`u3nwU^BC(G@KO~tcBw8%;YXdsQ~+DuJ5qm(C7Ks6VYWRWF*MuG9A z4RQGOD#PIGNZwPyA#?Z*M=}%^Ocxk-H&#AAf>aXp^j<02(&FU>x3N1im&_x0*z@nKIK`O4V~UsA0R~2>uGwo&ZaGPyp3iWA1~lRLrtv= zQ)7Yym^@rs;Hm(*^~lJdZ6J@38L+2IxHmiYb@s4z3IilxcP&RxDgq+|&J>aANO3*F zr2~m^-j%R(eRyOB5lk&P9f-oDmj5+DiC-QJKSbt)2IVBSOFflX; zP^^suONt6cj23)ab!FcrrLbm?4MkFuFGh=^$-f8bajpA@dJV1+8Plyj%s#?)W!!>c;1+r zdz*u$>X7PuVmd|0UqoAx@M12 zSMJ*enVS(5CE7I?M6n-i@C5M{la;iL8qYFF|08-xhKr~jGr^WEssBa;FkC4+YcqtX z;SNA#wEzvc?E4qJY2IEp@$&letLK_uD5J3@_Q9l;oy^1p*#}H;_OgGW1ze`=D_N4c zR__?Yeo}ekYM-g&(MgC4B4Hy z6(g4j0UZKq0qQ0NcJ99H=5jAjrT3*Ss39H`UxM5On{3^^)QEh6x6-#}af2?B*H9Ok z{LMjl?QGCtkoWmnW6`e_+N&p#+p=D5dv`b1QcL2NVmT|>KT@A%pZunMv}YTAo1w7jvmQ7d#@v!y_p)N=N7mZHF{fJEe%KT9=>81XF507;bb$jt zR%90_U!aVE$KWE2BNg&Qs8w@;gsE2r0Q{>fHa%sgQ&meVoQg?)OVnzn4u?*$AjCvB zUn)g(f=tl!Phf|t;+?w!#`u^Tr3i4ZK6Vaam=OJyY*j=(Ftj)Wj0ub-!=&CKc3&u* zz0Uf5&v>oHqei@WtX@}}bT_87TjU4uDK&dvQ5M7ky;LR?p=5;_Z8vl4mJ z9P|8PvugCyrldEJNDyJ~{mE`MiG5Ti(qng2X_yej$Vr5v{xmu~g+oa46Dsm4R!0NA zf&HMlptG0vddvn=Oa|=}VRIW*>^Z0jATtLSu!qiOIAVheF^B1Oi^tk0lb$f7;jt@cV6Ac*)deG0u#K{)HzzE6J9r;$28D~JjU+lo-aBFzbv&z zQQF&Z{AS$~9%mk4%(NNag*B&xwx;wU`HCz#)YjeO+pJrt{O9+$^N>m>IrC)|xjWsq%tni==PGXW@(3^?H{%B?pFqQ`x>ntuumV&@r9|E$ zWE4uCb$-!U&Vr=4Olv2t^P+Dz85im$ce#WUMgO{2>S@ z5S-9k_*Cb#rkJcP;<1mRz|4$KKHG&AK=5PfOcc_gw_4W6)4@3a2!QL$Jy!CbL2lv; zpu`|c<$mSWEN2G0{Em7-7%l*Hzb5tLVmDeMAmOB)ODH#l#q{b`<0d@KZaw%D^hzR7 z?9(iZv>fsG@uGzsT;&gVhnt%^e-*BPtc%5c|KglJJYs4=?8rO|$@1L?2@qAvb0wgn7s0@FcfDyrJ+Y+5cx)JvSrikH z$_T*!)pc-xK13EC$w zgGYbOi|A&n6J9pB&1^q2*j|Z1wme%6XL0i+-Td;J(;CYFlTut<_%Hmy`dDS*2Mgo2 z->xe8&`^0#sU38k3qDEuTY{@pgvpi*)!_p_h~nt-x=t)_d^D(YG7k+~^PWF+A@f?z zj*n`J5~Lc+O?V4b(in!vZObCVdUr)xmnrm!T8$=)V3BAVbg&5^D<&kNIum!(MQ$8k zB0mv}m-|#khkkD#WTS+V>FJk_1p6wqP4}K@5#$=hSb6is6&G1eSN43OjVSH7a7Ce| zI@=E86GWa+5L2f}KKv1@Y#iag0DTB#1}Y>^o(BuZ6TdqPYbv0clM@DlMN%dTe;g magnetic declination (radians) @@ -2381,7 +2381,7 @@ public struct mavlink_sensor_offsets_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_mag_offsets_t { /// magnetometer X offset @@ -2398,7 +2398,7 @@ public struct mavlink_set_mag_offsets_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_meminfo_t { /// heap top @@ -2409,7 +2409,7 @@ public struct mavlink_meminfo_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_ap_adc_t { /// ADC output 1 @@ -2428,7 +2428,7 @@ public struct mavlink_ap_adc_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 15)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_digicam_configure_t { /// Correspondent value to given extra_param @@ -2457,7 +2457,7 @@ public struct mavlink_digicam_configure_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 13)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_digicam_control_t { /// Correspondent value to given extra_param @@ -2484,7 +2484,7 @@ public struct mavlink_digicam_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mount_configure_t { /// System ID @@ -2503,7 +2503,7 @@ public struct mavlink_mount_configure_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 15)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mount_control_t { /// pitch(deg*100) or lat, depending on mount mode @@ -2522,7 +2522,7 @@ public struct mavlink_mount_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mount_status_t { /// pitch(deg*100) @@ -2539,7 +2539,7 @@ public struct mavlink_mount_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_fence_point_t { /// Latitude of point @@ -2558,7 +2558,7 @@ public struct mavlink_fence_point_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_fence_fetch_point_t { /// System ID @@ -2571,7 +2571,7 @@ public struct mavlink_fence_fetch_point_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_fence_status_t { /// time of last breach in milliseconds since boot @@ -2586,7 +2586,7 @@ public struct mavlink_fence_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_ahrs_t { /// X gyro drift estimate rad/s @@ -2607,7 +2607,7 @@ public struct mavlink_ahrs_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 44)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_simstate_t { /// Roll angle (rad) @@ -2636,7 +2636,7 @@ public struct mavlink_simstate_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hwstatus_t { /// board voltage (mV) @@ -2647,7 +2647,7 @@ public struct mavlink_hwstatus_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_radio_t { /// receive errors @@ -2668,7 +2668,7 @@ public struct mavlink_radio_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_limits_status_t { /// time of last breach in milliseconds since boot @@ -2693,7 +2693,7 @@ public struct mavlink_limits_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_wind_t { /// wind direction that wind is coming from (degrees) @@ -2706,7 +2706,7 @@ public struct mavlink_wind_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_data16_t { /// data type @@ -2720,7 +2720,7 @@ public struct mavlink_data16_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 34)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_data32_t { /// data type @@ -2734,7 +2734,7 @@ public struct mavlink_data32_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 66)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_data64_t { /// data type @@ -2748,7 +2748,7 @@ public struct mavlink_data64_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 98)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_data96_t { /// data type @@ -2762,7 +2762,7 @@ public struct mavlink_data96_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rangefinder_t { /// distance in meters @@ -2773,7 +2773,7 @@ public struct mavlink_rangefinder_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 48)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_airspeed_autocal_t { /// GPS velocity north m/s @@ -2804,7 +2804,7 @@ public struct mavlink_airspeed_autocal_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 19)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rally_point_t { /// Latitude of point in degrees * 1E7 @@ -2831,7 +2831,7 @@ public struct mavlink_rally_point_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rally_fetch_point_t { /// System ID @@ -2844,7 +2844,7 @@ public struct mavlink_rally_fetch_point_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_compassmot_status_t { /// current (amps) @@ -2863,7 +2863,7 @@ public struct mavlink_compassmot_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 24)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_ahrs2_t { /// Roll angle (rad) @@ -2882,7 +2882,7 @@ public struct mavlink_ahrs2_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 29)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_camera_status_t { /// Image timestamp (microseconds since UNIX epoch, according to camera clock) @@ -2907,7 +2907,7 @@ public struct mavlink_camera_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 45)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_camera_feedback_t { /// Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) @@ -2940,7 +2940,7 @@ public struct mavlink_camera_feedback_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_battery2_t { /// voltage in millivolts @@ -2951,7 +2951,7 @@ public struct mavlink_battery2_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 40)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_ahrs3_t { /// Roll angle (rad) @@ -2978,7 +2978,7 @@ public struct mavlink_ahrs3_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_autopilot_version_request_t { /// System ID @@ -2989,7 +2989,7 @@ public struct mavlink_autopilot_version_request_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 206)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_remote_log_data_block_t { /// log data block sequence number @@ -3005,7 +3005,7 @@ public struct mavlink_remote_log_data_block_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 7)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_remote_log_block_status_t { /// log data block sequence number @@ -3020,7 +3020,7 @@ public struct mavlink_remote_log_block_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 29)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_led_control_t { /// System ID @@ -3040,7 +3040,7 @@ public struct mavlink_led_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 27)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mag_cal_progress_t { /// Body frame direction vector for display @@ -3066,7 +3066,7 @@ public struct mavlink_mag_cal_progress_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 44)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mag_cal_report_t { /// RMS milligauss residuals @@ -3101,7 +3101,7 @@ public struct mavlink_mag_cal_report_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_ekf_status_report_t { /// Velocity variance @@ -3120,7 +3120,7 @@ public struct mavlink_ekf_status_report_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 25)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_pid_tuning_t { /// desired rate (degrees/s) @@ -3141,7 +3141,7 @@ public struct mavlink_pid_tuning_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 42)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gimbal_report_t { /// Time since last update (seconds) @@ -3172,7 +3172,7 @@ public struct mavlink_gimbal_report_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gimbal_control_t { /// Demanded angular rate X (rad/s) @@ -3189,7 +3189,7 @@ public struct mavlink_gimbal_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gimbal_torque_cmd_report_t { /// Roll Torque Command @@ -3206,7 +3206,7 @@ public struct mavlink_gimbal_torque_cmd_report_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gopro_heartbeat_t { /// Status @@ -3219,7 +3219,7 @@ public struct mavlink_gopro_heartbeat_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gopro_get_request_t { /// System ID @@ -3232,7 +3232,7 @@ public struct mavlink_gopro_get_request_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gopro_get_response_t { /// Command ID @@ -3246,7 +3246,7 @@ public struct mavlink_gopro_get_response_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 7)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gopro_set_request_t { /// System ID @@ -3262,7 +3262,7 @@ public struct mavlink_gopro_set_request_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gopro_set_response_t { /// Command ID @@ -3273,7 +3273,7 @@ public struct mavlink_gopro_set_response_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rpm_t { /// RPM Sensor1 @@ -3284,7 +3284,7 @@ public struct mavlink_rpm_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_heartbeat_t { /// A bitfield for use for autopilot-specific flags. @@ -3303,7 +3303,7 @@ public struct mavlink_heartbeat_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 31)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_sys_status_t { /// Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR @@ -3336,7 +3336,7 @@ public struct mavlink_sys_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_system_time_t { /// Timestamp of the master clock in microseconds since UNIX epoch. @@ -3347,7 +3347,7 @@ public struct mavlink_system_time_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_ping_t { /// Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) @@ -3362,7 +3362,7 @@ public struct mavlink_ping_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_change_operator_control_t { /// System the GCS requests control for @@ -3378,7 +3378,7 @@ public struct mavlink_change_operator_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_change_operator_control_ack_t { /// ID of the GCS this message @@ -3391,7 +3391,7 @@ public struct mavlink_change_operator_control_ack_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_auth_key_t { /// key @@ -3401,7 +3401,7 @@ public struct mavlink_auth_key_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_mode_t { /// The new autopilot-specific mode. This field can be ignored by an autopilot. @@ -3414,7 +3414,7 @@ public struct mavlink_set_mode_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_param_request_read_t { /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) @@ -3430,7 +3430,7 @@ public struct mavlink_param_request_read_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_param_request_list_t { /// System ID @@ -3441,7 +3441,7 @@ public struct mavlink_param_request_list_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 25)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_param_value_t { /// Onboard parameter value @@ -3459,7 +3459,7 @@ public struct mavlink_param_value_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 23)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_param_set_t { /// Onboard parameter value @@ -3477,7 +3477,7 @@ public struct mavlink_param_set_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 30)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps_raw_int_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -3504,7 +3504,7 @@ public struct mavlink_gps_raw_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 101)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps_status_t { /// Number of satellites visible @@ -3528,7 +3528,7 @@ public struct mavlink_gps_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_scaled_imu_t { /// Timestamp (milliseconds since system boot) @@ -3555,7 +3555,7 @@ public struct mavlink_scaled_imu_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 26)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_raw_imu_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -3582,7 +3582,7 @@ public struct mavlink_raw_imu_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 16)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_raw_pressure_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -3599,7 +3599,7 @@ public struct mavlink_raw_pressure_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_scaled_pressure_t { /// Timestamp (milliseconds since system boot) @@ -3614,7 +3614,7 @@ public struct mavlink_scaled_pressure_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_attitude_t { /// Timestamp (milliseconds since system boot) @@ -3635,7 +3635,7 @@ public struct mavlink_attitude_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_attitude_quaternion_t { /// Timestamp (milliseconds since system boot) @@ -3658,7 +3658,7 @@ public struct mavlink_attitude_quaternion_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_local_position_ned_t { /// Timestamp (milliseconds since system boot) @@ -3679,7 +3679,7 @@ public struct mavlink_local_position_ned_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_global_position_int_t { /// Timestamp (milliseconds since system boot) @@ -3704,7 +3704,7 @@ public struct mavlink_global_position_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rc_channels_scaled_t { /// Timestamp (milliseconds since system boot) @@ -3733,7 +3733,7 @@ public struct mavlink_rc_channels_scaled_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rc_channels_raw_t { /// Timestamp (milliseconds since system boot) @@ -3762,7 +3762,7 @@ public struct mavlink_rc_channels_raw_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 21)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_servo_output_raw_t { /// Timestamp (microseconds since system boot) @@ -3789,7 +3789,7 @@ public struct mavlink_servo_output_raw_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_request_partial_list_t { /// Start index, 0 by default @@ -3804,7 +3804,7 @@ public struct mavlink_mission_request_partial_list_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_write_partial_list_t { /// Start index, 0 by default and smaller / equal to the largest index of the current onboard list. @@ -3819,7 +3819,7 @@ public struct mavlink_mission_write_partial_list_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 37)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_item_t { /// PARAM1, see MAV_CMD enum @@ -3854,7 +3854,7 @@ public struct mavlink_mission_item_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_request_t { /// Sequence @@ -3867,7 +3867,7 @@ public struct mavlink_mission_request_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_set_current_t { /// Sequence @@ -3880,7 +3880,7 @@ public struct mavlink_mission_set_current_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_current_t { /// Sequence @@ -3889,7 +3889,7 @@ public struct mavlink_mission_current_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_request_list_t { /// System ID @@ -3900,7 +3900,7 @@ public struct mavlink_mission_request_list_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_count_t { /// Number of mission items in the sequence @@ -3913,7 +3913,7 @@ public struct mavlink_mission_count_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_clear_all_t { /// System ID @@ -3924,7 +3924,7 @@ public struct mavlink_mission_clear_all_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_item_reached_t { /// Sequence @@ -3933,7 +3933,7 @@ public struct mavlink_mission_item_reached_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_ack_t { /// System ID @@ -3946,7 +3946,7 @@ public struct mavlink_mission_ack_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 13)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_gps_global_origin_t { /// Latitude (WGS84), in degrees * 1E7 @@ -3961,7 +3961,7 @@ public struct mavlink_set_gps_global_origin_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps_global_origin_t { /// Latitude (WGS84), in degrees * 1E7 @@ -3974,7 +3974,7 @@ public struct mavlink_gps_global_origin_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 37)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_param_map_rc_t { /// Initial parameter value @@ -4000,7 +4000,7 @@ public struct mavlink_param_map_rc_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_request_int_t { /// Sequence @@ -4013,7 +4013,7 @@ public struct mavlink_mission_request_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 27)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_safety_set_allowed_area_t { /// x position 1 / Latitude 1 @@ -4038,7 +4038,7 @@ public struct mavlink_safety_set_allowed_area_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 25)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_safety_allowed_area_t { /// x position 1 / Latitude 1 @@ -4059,7 +4059,7 @@ public struct mavlink_safety_allowed_area_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 68)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_attitude_quaternion_cov_t { /// Timestamp (milliseconds since system boot) @@ -4080,7 +4080,7 @@ public struct mavlink_attitude_quaternion_cov_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 26)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_nav_controller_output_t { /// Current desired roll in degrees @@ -4103,7 +4103,7 @@ public struct mavlink_nav_controller_output_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 185)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_global_position_int_cov_t { /// Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. @@ -4133,7 +4133,7 @@ public struct mavlink_global_position_int_cov_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 229)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_local_position_ned_cov_t { /// Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. @@ -4167,7 +4167,7 @@ public struct mavlink_local_position_ned_cov_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 42)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rc_channels_t { /// Timestamp (milliseconds since system boot) @@ -4216,7 +4216,7 @@ public struct mavlink_rc_channels_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_request_data_stream_t { /// The requested message rate @@ -4233,7 +4233,7 @@ public struct mavlink_request_data_stream_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_data_stream_t { /// The message rate @@ -4246,7 +4246,7 @@ public struct mavlink_data_stream_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 11)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_manual_control_t { /// X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. @@ -4265,7 +4265,7 @@ public struct mavlink_manual_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_rc_channels_override_t { /// RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. @@ -4292,7 +4292,7 @@ public struct mavlink_rc_channels_override_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 37)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_mission_item_int_t { /// PARAM1, see MAV_CMD enum @@ -4327,7 +4327,7 @@ public struct mavlink_mission_item_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_vfr_hud_t { /// Current airspeed in m/s @@ -4346,7 +4346,7 @@ public struct mavlink_vfr_hud_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 35)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_command_int_t { /// PARAM1, see MAV_CMD enum @@ -4379,7 +4379,7 @@ public struct mavlink_command_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 33)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_command_long_t { /// Parameter 1, as defined by MAV_CMD enum. @@ -4408,7 +4408,7 @@ public struct mavlink_command_long_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_command_ack_t { /// Command ID, as defined by MAV_CMD enum. @@ -4419,7 +4419,7 @@ public struct mavlink_command_ack_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_manual_setpoint_t { /// Timestamp in milliseconds since system boot @@ -4440,7 +4440,7 @@ public struct mavlink_manual_setpoint_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 39)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_attitude_target_t { /// Timestamp in milliseconds since system boot @@ -4466,7 +4466,7 @@ public struct mavlink_set_attitude_target_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 37)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_attitude_target_t { /// Timestamp in milliseconds since system boot @@ -4489,7 +4489,7 @@ public struct mavlink_attitude_target_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 53)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_position_target_local_ned_t { /// Timestamp in milliseconds since system boot @@ -4528,7 +4528,7 @@ public struct mavlink_set_position_target_local_ned_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 51)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_position_target_local_ned_t { /// Timestamp in milliseconds since system boot @@ -4563,7 +4563,7 @@ public struct mavlink_position_target_local_ned_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 53)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_position_target_global_int_t { /// Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. @@ -4602,7 +4602,7 @@ public struct mavlink_set_position_target_global_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 51)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_position_target_global_int_t { /// Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. @@ -4637,7 +4637,7 @@ public struct mavlink_position_target_global_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_local_position_ned_system_global_offset_t { /// Timestamp (milliseconds since system boot) @@ -4658,7 +4658,7 @@ public struct mavlink_local_position_ned_system_global_offset_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 56)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_state_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -4697,7 +4697,7 @@ public struct mavlink_hil_state_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 42)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_controls_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -4727,7 +4727,7 @@ public struct mavlink_hil_controls_t - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 81)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_actuator_controls_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -4742,7 +4742,7 @@ public struct mavlink_hil_actuator_controls_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 33)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_rc_inputs_raw_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -4777,7 +4777,7 @@ public struct mavlink_hil_rc_inputs_raw_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 26)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_optical_flow_t { /// Timestamp (UNIX) @@ -4800,7 +4800,7 @@ public struct mavlink_optical_flow_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_global_vision_position_estimate_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4821,7 +4821,7 @@ public struct mavlink_global_vision_position_estimate_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_vision_position_estimate_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4842,7 +4842,7 @@ public struct mavlink_vision_position_estimate_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_vision_speed_estimate_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4857,7 +4857,7 @@ public struct mavlink_vision_speed_estimate_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_vicon_position_estimate_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4878,7 +4878,7 @@ public struct mavlink_vicon_position_estimate_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 62)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_highres_imu_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4915,7 +4915,7 @@ public struct mavlink_highres_imu_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 44)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_optical_flow_rad_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4946,7 +4946,7 @@ public struct mavlink_optical_flow_rad_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 64)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_sensor_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -4983,7 +4983,7 @@ public struct mavlink_hil_sensor_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 84)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_sim_state_t { /// True attitude quaternion component 1, w (1 in null-rotation) @@ -5032,7 +5032,7 @@ public struct mavlink_sim_state_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_radio_status_t { /// Receive errors @@ -5053,7 +5053,7 @@ public struct mavlink_radio_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 254)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_file_transfer_protocol_t { /// Network ID (0 for broadcast) @@ -5069,7 +5069,7 @@ public struct mavlink_file_transfer_protocol_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 16)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_timesync_t { /// Time sync timestamp 1 @@ -5080,7 +5080,7 @@ public struct mavlink_timesync_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_camera_trigger_t { /// Timestamp for the image frame in microseconds @@ -5091,7 +5091,7 @@ public struct mavlink_camera_trigger_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_gps_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -5124,7 +5124,7 @@ public struct mavlink_hil_gps_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 44)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_optical_flow_t { /// Timestamp (microseconds, synced to UNIX time or since system boot) @@ -5155,7 +5155,7 @@ public struct mavlink_hil_optical_flow_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 64)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_hil_state_quaternion_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -5195,7 +5195,7 @@ public struct mavlink_hil_state_quaternion_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_scaled_imu2_t { /// Timestamp (milliseconds since system boot) @@ -5222,7 +5222,7 @@ public struct mavlink_scaled_imu2_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_log_request_list_t { /// First log id (0 for first available) @@ -5237,7 +5237,7 @@ public struct mavlink_log_request_list_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_log_entry_t { /// UTC timestamp of log in seconds since 1970, or 0 if not available @@ -5254,7 +5254,7 @@ public struct mavlink_log_entry_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_log_request_data_t { /// Offset into the log @@ -5271,7 +5271,7 @@ public struct mavlink_log_request_data_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 97)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_log_data_t { /// Offset into the log @@ -5287,7 +5287,7 @@ public struct mavlink_log_data_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_log_erase_t { /// System ID @@ -5298,7 +5298,7 @@ public struct mavlink_log_erase_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_log_request_end_t { /// System ID @@ -5309,7 +5309,7 @@ public struct mavlink_log_request_end_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 113)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps_inject_data_t { /// System ID @@ -5325,7 +5325,7 @@ public struct mavlink_gps_inject_data_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 35)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps2_raw_t { /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -5356,7 +5356,7 @@ public struct mavlink_gps2_raw_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_power_status_t { /// 5V rail voltage in millivolts @@ -5369,7 +5369,7 @@ public struct mavlink_power_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 79)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_serial_control_t { /// Baudrate of transfer. Zero means no change. @@ -5389,7 +5389,7 @@ public struct mavlink_serial_control_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 35)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps_rtk_t { /// Time since boot of last baseline message received in ms. @@ -5422,7 +5422,7 @@ public struct mavlink_gps_rtk_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 35)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_gps2_rtk_t { /// Time since boot of last baseline message received in ms. @@ -5455,7 +5455,7 @@ public struct mavlink_gps2_rtk_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_scaled_imu3_t { /// Timestamp (milliseconds since system boot) @@ -5482,7 +5482,7 @@ public struct mavlink_scaled_imu3_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 13)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_data_transmission_handshake_t { /// total data size in bytes (set on ACK only) @@ -5503,7 +5503,7 @@ public struct mavlink_data_transmission_handshake_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 255)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_encapsulated_data_t { /// sequence number (starting with 0 on every transmission) @@ -5515,7 +5515,7 @@ public struct mavlink_encapsulated_data_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_distance_sensor_t { /// Time since system boot @@ -5538,7 +5538,7 @@ public struct mavlink_distance_sensor_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_terrain_request_t { /// Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) @@ -5553,7 +5553,7 @@ public struct mavlink_terrain_request_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 43)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_terrain_data_t { /// Latitude of SW corner of first grid (degrees *10^7) @@ -5571,7 +5571,7 @@ public struct mavlink_terrain_data_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_terrain_check_t { /// Latitude (degrees *10^7) @@ -5582,7 +5582,7 @@ public struct mavlink_terrain_check_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_terrain_report_t { /// Latitude (degrees *10^7) @@ -5603,7 +5603,7 @@ public struct mavlink_terrain_report_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_scaled_pressure2_t { /// Timestamp (milliseconds since system boot) @@ -5618,7 +5618,7 @@ public struct mavlink_scaled_pressure2_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_att_pos_mocap_t { /// Timestamp (micros since boot or Unix epoch) @@ -5636,7 +5636,7 @@ public struct mavlink_att_pos_mocap_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 43)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_actuator_control_target_t { /// Timestamp (micros since boot or Unix epoch) @@ -5654,7 +5654,7 @@ public struct mavlink_set_actuator_control_target_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 41)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_actuator_control_target_t { /// Timestamp (micros since boot or Unix epoch) @@ -5668,7 +5668,7 @@ public struct mavlink_actuator_control_target_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_altitude_t { /// Timestamp (milliseconds since system boot) @@ -5689,7 +5689,7 @@ public struct mavlink_altitude_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 243)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_resource_request_t { /// Request ID. This ID should be re-used when sending back URI contents @@ -5708,7 +5708,7 @@ public struct mavlink_resource_request_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_scaled_pressure3_t { /// Timestamp (milliseconds since system boot) @@ -5723,7 +5723,7 @@ public struct mavlink_scaled_pressure3_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 100)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_control_system_state_t { /// Timestamp (micros since boot or Unix epoch) @@ -5767,7 +5767,7 @@ public struct mavlink_control_system_state_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_battery_status_t { /// Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate @@ -5793,7 +5793,7 @@ public struct mavlink_battery_status_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 60)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_autopilot_version_t { /// bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) @@ -5825,7 +5825,7 @@ public struct mavlink_autopilot_version_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 30)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_landing_target_t { /// Timestamp (micros since boot or Unix epoch) @@ -5848,7 +5848,7 @@ public struct mavlink_landing_target_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_vibration_t { /// Timestamp (micros since boot or Unix epoch) @@ -5869,7 +5869,7 @@ public struct mavlink_vibration_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 52)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_home_position_t { /// Latitude (WGS84), in degrees * 1E7 @@ -5898,7 +5898,7 @@ public struct mavlink_home_position_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 53)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_set_home_position_t { /// Latitude (WGS84), in degrees * 1E7 @@ -5929,7 +5929,7 @@ public struct mavlink_set_home_position_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_message_interval_t { /// The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. @@ -5940,7 +5940,7 @@ public struct mavlink_message_interval_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_extended_sys_state_t { /// The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. @@ -5951,7 +5951,7 @@ public struct mavlink_extended_sys_state_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 38)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_adsb_vehicle_t { /// ICAO address @@ -6006,7 +6006,7 @@ public struct mavlink_collision_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 254)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_v2_extension_t { /// A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. @@ -6024,7 +6024,7 @@ public struct mavlink_v2_extension_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_memory_vect_t { /// Starting address of the debug variables @@ -6040,7 +6040,7 @@ public struct mavlink_memory_vect_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 30)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_debug_vect_t { /// Timestamp @@ -6058,7 +6058,7 @@ public struct mavlink_debug_vect_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_named_value_float_t { /// Timestamp (milliseconds since system boot) @@ -6072,7 +6072,7 @@ public struct mavlink_named_value_float_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_named_value_int_t { /// Timestamp (milliseconds since system boot) @@ -6086,7 +6086,7 @@ public struct mavlink_named_value_int_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 51)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_statustext_t { /// Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. @@ -6098,7 +6098,7 @@ public struct mavlink_statustext_t }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_debug_t { /// Timestamp (milliseconds since system boot) @@ -6111,7 +6111,7 @@ public struct mavlink_debug_t }; // custom message from the simulator - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12*4)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_telemetry { public const int MessageId = 204;

vtHRz}%-IMzdY8x8N^Uq`Da6pFV4`r?UP0r- zwwyFJ+8WMoi;8v!r!NN-NBDe90j4LXEymK*bF){Y6#tznu2UOaIuS8mrZsxZ?|P0r z8UvDE-e}o&k(41KL69U$wVJsFxoAD!v}t*&E!V&Q?s62ICtBH9;||4=M-9zN>q8uN zV2l?n=h6NHQ48!3ttO&}$uDdHGGPq&JH$lerqRt)wQ_3y{5q?@v-iP2<%SKh*sckscmc}jV-H39_uew}SC z`&51>G5-EZj@{t|FNpX}Bwlw~Ty{^_^tyh#`Y=q^gxvaWf{mYwaT>u9W*=cWyhND3 z<=T}%gqvbaf712dE9vtIQcPeNVeZ2_Udn4$;c=uX6uS66ATw14D!@8L0I&8{L;P*{ z$x^QUqF}*&8b+m7Bx!u|g66$+nR`KCxYTb8_F_UPBKJNJS;x+eK z=`htGW@4+zd53?U`CvR7KLKdNkQV%(sY3oRc|0MKq*6nGNG&!H+y-^i%5}I$JcC36 zA^&=qm_a=?^s;@(J2uzzGVi$)U253d)p#v1mn&KUR75ba>Sr%{h_lO9V2<_0X@wO! z+~VJrH8gqo?SmgMdM|uWnkwq{-*Jnm7e@>2`JqzYehn%}g#w_@lcmGo15fxP<1PLB zG3o~Ms|xzJ@jav=x>z1g%1#DRz*W++a5#F zbO5K$>V5m|D7Vad+me7%uFH;Ui=B#AT+^-QAx3 z9TxJp;FLi{S&8nrm#`Pm`fP@T7_Q6l8ggv_Qawnf?|S^!_G`ZO*w$hC!htyHG~$`l zRf5OG`mdM?p+Ul;@7MWAY#CjgIeBc{5)#UgiYbgbH9P9BR=UwNd)<-)kpzT?x$P9BJ5czoNT5p z3}z@r#c^b)=f|PcEAycMYzH6(>r;u{ayi@QL#6%CIm*^ z=fWdWD-~#atY&N{zoE;@SZ(~UUck?hQCSRMHk9ytlfbxmZ)slick?f}v4#L)f$yoW zkl~hX$z(lFc^22V>%R~7a}pT+Z&2Yag-+K2i9tXKNMTN2QyvfTW6WJ{{^QMST~nQn zIyDZK!x10C(s$SS@Z?cIV^AB(-wyJ}MiUR%I)i{6m8P!DkL&>ppa~G=v-op3FA9~_ z2iAVPr2c6Sw{YRp$FMi!%-Yl}a$$R=z}oCE8qV6>+F4vGdPc$wj5Tu-PV7Hclznxv z+gmr#3<{JM+G|I3CJ}k#q+5F;YlBihfeJ%MrYOpvNWSnn^aqxB{FE87395SJbYR$KCGhu&w_2S%u@w1He?9C1p@;4_?&P6faQLU0-Wa9lZM&zD zG)rY~Z+1lQp3gPC=2uLN`&z~=;wSySgF>D1)u&Q{z8wUaLj#yPZ2y6I3~~=l3~6oQ z%(_$5Lea{NqpY)vWw88c6q#f|IFbfvcv191PL8YHRxg#SIEA0T%zah#9Hvfe!836! zS%h53b2YW4SGaDneY7ZF!Wg-(+QlTrzP1xyaj*xn&FFPL_vdfp1nL`by!Y%#1(l}q zsU%|Cy_}yQk>YX ziXeK_+rz7h`xt}g&=YG}Q;@u95dq5|J%CS5tv()Z4@!xVf( z#j~Evl+(L6AS52#*F^G6ABqkw#Z-ysZ&mpCi+~W=6uT@Ph6zF35pzb>hZxmue?xuM zPW|`C)4KAy%#+PT!@8Yr_J_@Hqm9-akre6<2JGt54>ssx6lx>tJFoKv@}ZZzRGb&J zM?s5oIHu3PKI8w;O-VpV)Fv70&XLt&qV$|)z#e&_;U;Y~*Ry8-&S)9l*8ERK!n00{ zXr^I(b}dk0jp(37I46*Ygd4;UJH~(52TkD)eWQ|DQfroxySq|K|G~HbnG@C&<$o^l zG>9RL;G%6AmyAF&g2E^($hm*ddiKp|GR0F=RwVjLr{n5s)R7l9N+VNgqP^Q8kW9&X zTApOeaw6pXFFvWbM&)7;-&MIzer(GzV`0(Pey!@2w}{(76sjYOLFdM3eVmW}K?~YEcp|juZHVuws+&$Y}(KU`#@C&c*Cb6 z+?07_7|;GV+wIWW@Z3|qHl)zhM-pn4y@IIx@jYz;PTLLi`rMCQ)iIraK@S&v%$p*g-#Ss$i8QM`&@#C*aq&&P6J{+u_wSVEPOwjZH*NPSfOrXvSYd^TYG5`ysP z*|uC?XwOwnvub%ag6QpHW0Nsgh8wqh&B)mR{52Ujd94tn?I2{FdrcW|o-QyOxskhn z+%p~Oc}tyX00Z!(t`0adCc3aN<^7#s&htk-O6Qxi6w(j!yfB<|AdQ#{(r2UAU+n=h z&@zmmBHGI4hA)e&X1^!eVB8r#Qf~^pgb8Z3@gR`KRF?hpy>_!ZW4nYEjuk0YszxAe z0{WuwsB7V}N+G0Wu&=$Lgv7ptbo5?P3|^Rv=aBWlLT;dJA$vP>zOE2~jtzC8n=9Ye z$&*aRhpq@hfa=6Tu7*4bn6&TL(l;W$kpZ`%8#$9?W=CtF>EZwnyPBqlNR>%~tYq!aq2U!F> zA>LOX2Z5s6X*v+?ktPuGhurtLYd>uDPGc)m-C0{n5_eRds@qn=@K-iw4(hfx5?9Uu z>Or4PYwbCx@ps>2dxDicob=|?Y8DcU8nZZ7rU)Yt`FkR!~`J)DNnq(i1s=^NK!jvSP@tbk#SW7TW zoUsQc%gAVID$GHz@L*ydE50E_UI3-ez(!ycv2aKfl`M9lLT@eTj+ zKazXb-D($N%XOPgN3_B%bu##M7s)htH&#a=XMs`Vs#uLyvLyqI8gFlB_Y<$L4+3S2 z<6Y4*3n2kKE59vZdD8N8ZI=YjES%>;598}tm2Jzwvd*ReC~TEQT=T;8@Ngyi;i!sd zRq>TqLSTlthY)S;Ipt_3g+mwxfe4Dm5~yMNFxQKafXvj4r%Fezv@`URgvA$SqXfQ> zr-o({&L45>k^&Llmubs(fC-hp4?3BUE0c6taE^vJIFD*LF6Hbz*R_&a1 zf#)tiqB%UbGCb^V=9-h*(fL?pRcojifOZNG3p3I6qr!_okI)oiWz9<$SUIAw6M_dw5Lt|3*W{-kT9^&%)`*RcqXq!nmGe3< zzQt?MXlO*u7?|U;b9_;-PayvCRQSA);l&)tkToziW?#g@{A<$Q0q7}{17V>VmtvSO zAtWC*j_S6i-(tiy&V6rckD6@lc=y{nk&Vm!Pzk>hzWV5rL`#7w8sc#mlbK21F%OMK z{&nA93~?>?&ZF_*rdZe2A}7{4wBufw=W~S}!&)NjINKB+gpqRFO+$8F06pDzC%i8f zZ5k2weGlyA)^&AQxl+7G{es(2RU=Nt9J*sDK> z9=?x)*WSS4j%rwDv~Jv-ym8tlYy@eim_7tHz~w3-fyk*>8>%?#>yQwnVnf9v1jCx} z7S*2xSp_?+Ov;yVhjLoH9~I@8*8?L288z62pcsuihYk_>27QT@+9hyBvN z*S)KRqUyibEw;7}B+Fb1XS%1|Mvba8&^qO&SDsf?9sO|)%P#7 z{h&$-b$;>;`F);|?kPh<#z1GkMU_l$@fUwGILO>}C)Zk2b@$<&hvs!{LrG0VuI4op z9Xy%MGfByE7NkaP0!4pJ1x#vvEDS~1j_1Z+QORk9?VZHBq17qr80{BNt6P)BEDy4N zh(4skfE;tL^*V9bJdum4c#VFoFpWs`(%X~_*SA11bnUtGnt;`G>8CwFHLPPy5!LiN z^SY)HWUKNUd>ca}{j+_hk7{S$1UHs+?x$|zL>}8WwKZPWuWeINsbU$soD6j-oJK+n zs22v|wgD9I;|FJo>M-YA4Qic3@Bk;@d%ivYdOz6|wBXV`9Y7s)5R@7?S?*m&TQ#~N zI~u|dBcYFF!`UbR*ybV#J5oqb8fs6Ia{ZysnCoA8aty#VR<@^ z&5f^#w)|a&jjAh+X`K^LVLYn!3e(Os$5d<~fMkCvd%;IUVZL0H|J@o>mG#z-v<;&U z+sIkp`og&K(Ov9gju{jC=6PPE`A?U#TX>hzzrXw5;*0A)Zl?7`D~~m3`ww-?k#Fmy zj^fLRYiEMjJA|V%FtqOnN%;yyT<*(TCs8x6qAaCGpo-XpmYM!C$U@BENM1tYi!->? z`u1z?pyMFJlH-orI}K8s5fuJ{E0BjtIP~UZ%)euBC$r%KgWnL`0Nk6bzww$H?K3>3 zMe>SY^GVeesyjoJO_ys{YriB55~snj1@^qC;UmDcR1o9+%J4((-Jf-=3@KPw7pZoA4yJb6E3ploYHf4r)EQ zpNp9S>B`<_gTUMEzDbyxM}t^dJd^=RtLx@VPS2koF=qzC)#Z8uYtTy?PJbG+l5)T4 zTcXn^xtJYgO#vjpPznLVKpSU$Pbbb6b{O;LwDLWR@9%e+O~FWAh-p02pZgiyIar% zcZUQgxHs-@!8N$M1P_v+!QI{6-bF~&Qdm$(=9ih)>a zy9ZnM{W?vWY&FlQv(2rZgH*dJ-Q4}aa_TRsO|)?}-Q30b(xhHxZ>CD-H;~GFx8?Nw+xKm#`h1NSQc!*xi9coaD9qINH486=Q<(^?| z`uoE~UA^kVT5?P6hLOPyB{RSZaH|$jkuuQJ%gM@C@2l^84JO2M*;Mw;q4}f&B(j1? zd71(B7GRO^zUdzp)2}8eG$x9Qoy3P@NWt`SF}i0ZL>RflLa5o*%zk#c@M^~E_PF|&~{OzvZ`ftQIQ&946 z_p}b`DSmd7Ez6uYEE2|x4X4h>F4Bb%JkAUi&G;yP%wwUwnINCTnZG|*q+ln^Jd8&^ zB)&X>@d=+lr^lU7r1KqOR*q#0Q7n={LGeXH5$tHeO)GGz#Py`{ITFP56C^rtTX#;m zT><^jA?g@2ul!tR3Q#2(RB}a$62gExVOJt&M;3-4k{67|&=cAbeaB1$0y_B^t6A%N zt81$SsgBx`?NQ^LF7OhIr6Ab%MITPsLKF8n?i-$F#LVT!#f%p#of|kZ{Iz)gdvbta z(61eJCxha^)4F+b!N_PYLo=M*j%NoG97{5ZS;XENf12?gzGtH9V=1VS<5tkXA_Go& zY(V?7OujRG1+1pCkj&tKf)OTqK&r1&0~?Q*iVc~T5M`skEI8e4;B19o>|x>##`}%~`Jlu^eeqhUc841t0ZfPr`~4?-Q%`LL`=`e; zqu$2P$3JNh$etmQ*W`YqS z5b1B9ui5*9rX%tv?{^ymiow)XW#{}-4T|9Yv}v}90i>uJxT4R{@V6$nW-%c7)RF>( zh}{f>y0Y8TSjx1)(6v~Q;$NPKTt~;hwd_i7!Bz>^*;&X`Z50I$C6#xw_Yv;ecUZPL zYpkn077n)K^=#z&Xk${KIpUJemGcPvO%>!~>lsmV~*JBX7b>M)Ue49Z7f z`LLv6ukwphT_eolAjmDkNX+E>lUoPS%PO*-+oz&jG2UQOI zHfy~Wl0~Z^+2Sxe-lq+_W4+&HZt*n_b*kTjnyc}*kb$rg{(m{Q0$&C<`t*4}BiZ}+ z0KP8lsRTpGBB&!AQ6cG5>6)-Nk6Zm}H|#b%VC zA4^L~UP1;JprtjrTP`Ok2^-T0ZG!_&$*=wt^x0Ba1f-6#E_|1Semr z;GJ(`qzC`fH?Qy0Bh%hnEm(ITdnzWr*CC`t0p4}*^nIeB?bH=W%6*rrt zOpc46SRzVf`LZw(^7^i&R^K;)@Q!J2y5dWs&-D?u@gVkL&`KeKn+13UPKnMQf)0QQLR{yjAK5xMhU{wn5ZjgR3 z@@JDd_Zf}!W6d4G@7fQg?*aTNSyy-F(eO0BXr@TVZwL_7 z?IS`_-iKid`V8KK&mC|q&|9A)(A(FL#k!s&75P^l=RgUxQc=Nsim%f7q}Fc5X!ZJ< zpo0`#%gK8gc@rS4fW6eGj3?`=&_pIk1=d_Pk1=hqa6qsmk|h^cqI7fv_lqQTORjez zY`RW9g87@ClHayM_Fo9O3$*E|c>e+2cTmVnm`(=D2)OPT5(Of6m$tI)nFmT_dQ&Bx zoCt5rz?UhKa4!c#X;FZk^}=$Jf1PfQ!{4w zobKks2GDHnNJNU^?~D4a29+$0!+%#i9Z=?RetBwDS$M4ewWqx=6?n2;>q+CZeeW>W z4w3?xmhA|iHqzXoto%RIB?&9O4XOjX8EaSuV8oWpNYIVaCXu{#5 zUM9(%lhJxfO4U8=;UQktv&D4yQ89l$BWwURr&h!0v~0Fg#JV|*XC;*csD9n8CbOCT zNHvJ?wzvY2)4(ah9T1W}V~SP3naGiXbw7Re{s@TtcUH~ITP)TkVLO1$d8JWamHuus zg^yBh`JT(|(gFZ*_dMKH>h{8iqUB_hEG;qFuKHzdL7GEED~D{+Qg&~4bP3;x)g5J< zZ$56WhQ5PhrDS|Mux|6ez5^s3Gp0kF7q;FD-{>K_ZZEpEh-B0rM>|D?)7vf*T6*PM zD?MB8b*$#9zI;hStC%}Pe(|?a^Y6HLt3X_@XZ$Q*`t1Gjdu3&x^utv>ehWI1=$Dzb zp4;nN&uXWPYPj==h*sOxZxaHCoH|PD`;A)co>Iyi7wE46(}d|P^Cv*04#b-In3=z4o{ zyfW2xyW1!)@W5`~CL>f)mjx~_oAG$Pme}kB*c*r8^TIZ}01T(^%*+nqNOEt9R4=TO zY1+DOFXxi#h{Z|x}M!}+RVFCa3xUa8i$x#5}rzgF61DvBy0(f}7e2@A`Tg>8uGRFz zd`%6&vLAfd)3w$9fz(w^oomvyvgZb1(PihSKSQPpXI4~z>9l8y{>wP(`7z%P0XwbE z{OK(CK88$_mzC=#!|4I5`-A{j)MN>0HGh_R8?&oOvl!JsTzNx9ty>`B+%DuCwVIkU zYR=6OrkA2uwg60ZIIU(oNF`&-V;{LQQCKA}8_<3EZeIZVFE$S6i!#sR#yCkA8}k&^%O82DRN{`ZwP?2i)#T?kr5 z-~nA?&RYm3pOL*{Wn6CG|7PC(o!3AOLK*@uT>Lr$$YSu4jtN{b`2e{2sD=E^DOkaWMg&eXo} z;r3VXy3e^$rJq@f&9b#Zvk4PanM}XF7IhWk6pwECpVR&C2h75;;v?%WRnx?P==YZf zjPVnZ`M=tXrkOW3l4qJg`1?cY>+AntPtV`j=XqciLIe#BTav?xOvx&LM}{O6HaPJ$dyg5o`+p=#$U{tU67L`k9gtJUs5fAWjw@aNZMVsC(^a(em( zFfcSQ?;unVsbEOKC4Q5RE6B(y{;%BAKR2pI-cF~Nj`RO@ zH_IRY+H27O6!W@Tt(X7H75o~rzcej|Z|q+KEQxf?|DQX3 z`x~IG90%gFG;btgL;Fq4@9D#3`CslDX<9vMynf8gl z8ntNs>O^|J5`gd^EYiuC?(9+9n%&x}VsaI9ybS^y+}c~J8uhf_>?Y}$J#s3E=E}oo z#}_a$vCHjeY;sxtQQ+BJAuLNS-b|9hoC`<$#@}$-LZB~2)#NFbvR zxQNr()6my*LD_hg4CDP+t+ z)n!#h7?fE!l;q^RcYQ-$y^eDn`FIa#1?TwGKDc2&Eetf=#VlYqOHvi2qt!WJGOC18v( zOsCh&{0S1xCQeYiM{>6{#+=TWZd0m~m_lrmV}J4%-acOLx3FlzohCdUsKBKjVF8HsRtnjr*uel+~M~<>d5&;%YV1Rp5 z=0EODzvnz}te}Dd)oCz+uBNDSxn`N0L0{$>n!(*mIsCMA$FeoUSw3Mc8Qr*c_5&h9 zTnQF0vi@bT^wF?kN6{{m6Sg0b zjESkwRXPh*#5RG8I7OW#DxDo~?);I`tNY4!Yv`Ccho^;j|^vhZ>Z2JqQL;GQPiOxIg5YobO3@Vb^ThcZ|NIxuq|~k^a-}W z=Wv%Biuw-X&XeFKLU0Y1S$nL`&Nw+bwoTaH-q%j}nE3Y6V5+cs4pp>!bFqyuf%%a~ zbuA%ykkFD-Xv8x(hT>=$q>(&|uv`*eJs+2 zjh%r`rf9hDciYvkvk(TkLK*G151$ZGFqjWz4(XH7NN+e6qo5F#$LUVkshN?ydIujR zvC`dFYC}rKS9imF=r-RBp<&`i?(2!YWgq$a$n>YYMDKOl09O2jfm6)ftXMX%l!<(Y z#{kBHxi2-RdG!681G`ogqlt8q8CoA7-zd;3 z8SOYYcEdsF=R^1rSzu%cLLseyOXt~TAnoa!Us5BUuVm+Mz_b|t-Xw?%(DeI`4LRUq z_wq^IUGc&Ed~Dd0Mzx#tF0J6h9D2D5WCh*|vRg?8$v{&D$ANp${+drVdP~7Qw|f;bE-RKx6{X!vF5Vb! zXhG;#5Vdz%fiS4qWGhVhRY7vPhL3>T zCEd5|`+F9NNTQ+dTtVFLQS2g#2D$7u?Uj``W~%8wVg1Ij1H8Y7;nv1-QnP)LZ20-( zZs{@th32C{(=ReFh@Qg;F)^r#2_VGz>L2#EJ2+La-8N0hQ^6!8|30E8LHN_{$6=06 z4+y6mY>W)a-83@`VzX~6AWB9$d%~}p^RAWD*Qjd|&eh5|0+cWxX9>N-FXl@aXW9^0 z!h@KoUlbRRCsrjAZiT61QytAnI0c{eo<(G4qKs+Ss1e8Xo-7;^Y>g}*o3*g|%-EiP z)44Ymd(dWzm{{@}bfSx75>Z@wk3-q2;bKe_;{nmV4A zPO6YlVEJOi zZ(?C(>}R+~ymMxI+in04bA(m@-U5E}<+UW;t^rq90=OJ1u=$`D3no;eoH}z#g1si; z6wxyv?(vrL3EaVpa-}VPD@zSHWG_!uRH*bD!hqv7ulYchc?rs^{;GPA1B4i1ky-8T zXsEDu=bzmkjuIV`8X6jM8T@e3K&y|@;#ZeQ{#&Zn;bb-hAW#D&TxVT?@Ss@tf#&sV z=)s6r0<+`eFIKm!GJ=kX&Q-;N(oRD zHHE-=^mxBTl`WDreA_^eR6Ta{qX%ZcA_S9Gj7|V)ZhrzVZvfbU*V*YOl3CL4S3U>~ zpmB4Lk2w;Ntq+%TKcRQp`v~i%)qYv%#-t}r_)5_{ZYrvNo%?p{^pwwYwkNzQ&iqo1 zZ>~?09u@S3gQhe3w|~j6^&J*Mm~UUJZ~)gma|)LBg#;@nB%*Rn!+DLmA1%KdYW){o zwg-lLKIXDENpyA-4j$4N_{6YnDul9}PAz43_PU{w=sQzQisj?ayU8I#cMz44XrE>C z&Gj;s63Z(q*@6pamSO2|xJ!!=zJh^uXiJF-DWzvyDU!>Xg~iI|J|q)O+`^l#4-j#+ zzO2SMc$->78rp>??*M8w2$p*BgZ!L$0z^~l9ZN#hQ<<+SwR%4&Rj`niBI_*cla zxqT3|F7-FPw9E`S8&|G_TqbEm=%`sJqpI#>5{-Jf6cur5jFwZ5?;#e(bbf4ymOD(oAOx++E7a~GdgN&Jbw4HfdU`~; z0N6p0oL+{#kc#_!>y0Ed-1fY z$%XBElcim4$1P1w7u@H5aOgD}^f5uDDDPq+_p6^~ihKB58C?%ge|r|qZ+kpjcgDh3 zNTi)=A^zPHfH@+F4?dMU4mS)bvFU@#WTapSpT7ew{KfU6bg2tJ}-u(`yBF?M*}h zTPK|=)84!(RU|xCDw?7P!l9cj=?M&E0#3am2$37io3=h|_C*CE0)o`&=y%%M4wog3 zWH!J3WNK97A?YkHw$3QSe+*bWB(px*4KI3@4M_w2Vru1E^nN;3bN|Hf&cxvEkeK{! zSdnY_oqAG6vRJ*b4*;EA}TfoediZPgR=;qNPx;FJHoJnECdm zRJ8~Y^U1&?DM51z1gvbQ&Z0CL!~^c;=H`LO@iK1VFmHSYmGp8RLlf*a2be9x+Ll-A znHi_A8Gi|@l_|lCKiuKa!1X<6kVbCa(bTid{d0_UCIHVd_a-APB%tX`z^=>sgs1rt z9XnQQz82DA_TA|go6@IPFF)KcvH?F0%K}zOBWH68d&OQva@dqbO4`>|28H^8fg(ab z;RO3RC5*r|FAd|{1nVHZxBHMASF-!k=ZqIkbF|Q|7b%F0t z!EI|OZEtHzXdDSCzAS~EgCi;Ycj8;#m2q9teIH2TX2SkC#TZcmLXSWBo@H>zCWj+s zv+%5r_bQT7Nk)+RC8H+2%O_DFq%Vt2e9Ob;<_CDu@Mf>aL*&1LgO~bu%EY>7r6Bae zxgV8eIrXbh4fW*EN+IYJcXroS&(G6CvR6og#eC^*a|0Do$zf)hrx2~)de2Z(o}I%Y z!d9(9Ax3X+2YdLAiT4x87Mes{f2YEH(Mtj@PeH8H_6;GG(_VR~DQvwEalu79JY1Fu z0_#oLjJ}e0|BoNXjG?!Tj}fgn;A{4^GH=@tf#$Mb-3fn_Xyvb$@%X;fsr-PbW8<1? zV2-NK93^E|*#xTjlAmypb3maP%#y01{^S18dFf!2m45!>yGR--AB&WfG-Ez)HQAWx zhX#iMd5$f#(Yce@JF#B87kq0!H7Z;7xV7I zrDmlYlaZqJ%przGQoTM?*`p169sCGgtbP-SDWoN7ErF<0%sCLU986%E2i-40uaUeF zkkgqylQ+kmNi&PUs7D#EfS$j-JZ`5Q+}VJo8T+7(OAag=ktCVLbR8Npx-xtwA9Wg{ zKp?P^ro5g`BxdoaC7qUBCsC7$m9P>~UFL|LtY6loD~y0Q?(x^vn1u+SWI?3lXV+YT zgYtJh6qH9-@DGcL`wT57b_)38&F1(9V$zWsVq6AYN5mMAQcmIa7P7!ZBUk_}mxiQA zxMQpt8sr16GF%M`z77tSX)X_@uK zGBu5EC5n_A%W|Z|bi}7;6xIx5T{Vw$Emw=?DuhEd6h+@xriRdLo>L4>O2!cYz4$Vs zD+YuFxw?kl)u|zEI5!e5`%jI9Hw{E%6n8ysz;sN3LyCN#P~fwMz)gvAFN@+dE4PRc8EDqZ+zg7-BSKu>SC3D|}YN&VSqx zi^za!f&B~-wb+-iBDM-d(Hx_A2ZP*aPa*E*MT1zjKG^s*6yz+#+8h(Ig>u7av)C#Y{dRGtQFxaYBT-SuakuMQV*NLZE3>+IF^KC+Ht+VTq(ALQzN zO_%($F{d}wYW;PXm=+@*&(v70D3^<~9RiAY_ZDW2=2#JZRibqz+WK{lZ^NXclOQbE zLsKE_u}YbQMZR#zDIlV@sb_ysQ)7Kp*4Ae5m{MJCrgEWNdM|?bp#~94Q}5)(rNHCE za@7;R6>1vQnHavx%~t$^%J^x%&2WN(U8>Uw@zyp2`A)w}CN&gH-rSdsO=^p`NJF-g z?fq~;*l(_>lRi<=_ea8-J4|1F;y2T6&B)M|401eLY{}kC;S`S`z{STmS9y{xXjgC( z6R+Uh-QCqg0Vl*=v-kHwtC*EX>-l@|cwWkYWW4AQF*1y`A2vIbiWY=_tGc%0J55yz zdu5)8#o$60C<$XnjM;*QLEVU5Q<%i90muVwsBCgLXWa(n$$p=6(W0p9@!w)!Tl zf!xqhX@_>dVRS6vKu4eOxKdI51CZOBP4Lju1gb7; zI$DTcF5%>y@3_I^O)kocB3vDX>i?6*$8R9~RT%DMfR|K~qIj+95ZWxc$wzl0cr*~A znHeO>x?9%Q=KXh>%bx}U&=U3OxFu9o62!!7yaEz&eH)sH8NR4-MWj!|#Q17cfvJsV`F&AitwNcb z1As}Ij7%*yP1qA09{%!Wq*}EJl9G1P$@<2I$N5hQA)$^IH%$h_Up`9nFLT~OBm~C| zO1208MsZIEquYG=rxJ&W28#GN;O#JXjBap8#(tyIPKt@`;v>1n*8Idb{{Bbx&u)lU z9%5DGqlkc7B3c3N#Wy`)dfy#yEt9ogLwBa0wx%~42Sw0{Nz0NfFo|hyoy{}O#2yne zX-?|oA@WAuAx&DUA2#S5cw@+Vug+!h_A|eP-7`VF@D+vTc9o`C2C6($MrA{;*?pU#t zl2Iy?%XTV1-1lkc<`$GZvGg}R9L-3&?g@vxL9phvDn^d+18EKwxT)L&KhO+9El;;? zn85NKvFkr-mc+iMlTE#n6mT_Qgxs!)lgVco;p8M@oaWSO-QDjvNCx9XfOEzN*LPoM z9!^-S^T3)4?a!d5{s^3Pb-f-gXv@F)kXkd{u$j+{kK3>JMSB5aj0}%U02TScY?ru! z&t9y&tgP;y@LJd$=9~BQ$GKC zYpX~7oDAwJdlGC?sA&T~wdl%itZaxbou8u~(Kt&6%w=T>Gw~n_BXgF@syeyRS`m>h zV`0PUA;^;T@2>0&`X3F<*(h®g4~{{49kuveod$2p^|0m{f_3y9T;k+%z~rZDX% zX+mH(U;Cisq@+qqOSLNvy6uMf>Mdrfl#5leHt|`PoEBYRyl#%Xo-{QyLQGyj=R!e3 zs=Xx#H_3`pQ)3GR?|NhQ0;Je z2L_^osE^ydcM1z%@61h!A82wK^LwrcL72S;d%*4{5DOM3 zdWOUaypny|HaF-TLV~L~P%I;~`|TMM1ww%J3lKLGAv26y+i9|@`>qZl0 z-N8MdmyCV4h!vWt3tLI#Nl4acyfW% zI3AGRdfMs|Fc75E|2aBikP76+k0pNMJmJ0B{+j>jx)ADhZ=yO`ZzwL))z%Z46r8$R ztIH_jRC6;Ya3qes_Vww0FLKosHS8J_Je2t->e~W!>@k6mjGsibVv?Ukxs$eC>u?=m zEWj-fZaFX`MG=uZmrV%ngJBZ89&mMD^$aSz>m(vMpVfv2d~hMYSY8K%nn}LykGfVnAT5DBPYlUhMK<9rEsFoNet&q3H~*ErGr9eUnUYe{n2$V zvRL3@_0?jqe{q5o*p+Z0H3HzWeUsDy_=8A{dfD#lRyhxzL=Es@o%rMpJeaW5KX-VK zdo4IR%?ng4qAKPgK3XW;Tjz*~!(5x+{8n!O;SU~uvh7s*HPJFQjmr8Kx}UCQvik;O z#T)|;l3{j|PChk1CJ&dT!_#&nd&^}i-`4ER;&TAdCEy^*x&05MP9=J3v zR2yt39gGuv+PaV%=IlmMi+bhudjWoFdjyk_E}D%ggfXW7IfUaD(x;4Rr8p==gdk(U z(iNS$eKiWryZl_;Zf-*QviaqE@m~>L85s&e6ch8oL$zrNG8Uh%(u1~LsJ#>YpJvor zbWlWawrN3S0#3%K`}N13*M*3ZdLR?Qr~hCCpv=VM!V5*xJe&PY&7iG*TAN zi!E87KKm;^8cpGJwyyM5bz*qM^%SCMF;8<+)`S6wx=4Jt zXb?cX;ESdE{N!}KjIS%df!NKiBbJ$)+fY-($;KuttKOdAM8#R;6{31Th`r|xsRx-g zHRm|?1?K&7%sweo_OPNX{cT!4_PVO4?86j;-@fQ`D19iMSy+hL0R`!(zS=l9BDPAh zZ{KX~QrB3-Y<~Cs25HbZCw9GwTQI+;kKKh3aQK~%ikM!Hs}Uw*IQ6G3CU?{Qup~~e z8Rjc8Zi)_LuPMU&-m!v{7_2B4{%cPb+V5IBdc8X3zC?_RgQq<+ZpnP`R!ONE^M>&v?dr~lHM zN!H9^q4LMA$fdo>tKUZ$CkkTz&9sYXI#8PH_3gER`HuY`-M5-OoR2yB)U)U)s8pk>mGuwBw_l%X8-r-jKgd2Ld??2hHU@hXcXM(C|&+Ppl9g#12` zAB;0>Ar*kGBL~ES%;0finAoC&86q?xA2iojTNI}3e|HR_REIoU5Hot%%~Nj7PAz_> z)*E(Td$eETcJMZ>A=e9j7Gg|;$0ET^zZFDBIXJ>rdS5*_8S#v^1VW8Wc!FbG5lP74i1i+JDBCI5N;`&aHN*Zxz-QFqY-a^kS9&#<;;I8Q?>s_sp)=1 z_fE*Jq_h<4AbLPeo8EXzWjlmkj&hZG@NGcDYf;nB+S3?W9|-Vh;4I&~99y27_Y*O? zyf`%>t)Jc3fVfm28IxX9EgbcNs0ab@9Ev!!vJ93jWkND zBEKLd(WnVbr$x)OSEjgT$kkC?QNBl9gB>gM$Nu(x-q+*=63Su3bR`k~Y(`&X2pfHc z2aUylWb(i}+wMabd5M*f!-U|vN{VIbLQbQ8Z&VbMt#W24j2P6AouV{)cVd*CJ$4Vl zh=9mRG(9pbTgFS6smx6}ay|FKRo@6o5!F93tlWAT8be4-=ly~KnXai^9{I2kgtB5z z7h&U2y@ux-`{!qb-g`6Qbq(C{%l$fIdA6XCkoxbiIJS8HOt8(~;6e-HL+Dk^U?jK1mLW=&-?`ycyodhTLZ16~_=D2Q(@kbpYvpqcr`YgI>l0emXq z_QKNwpyB8hWGm7tL7j6D0=_Ve)2MeZb!*thMJj8kty;kiYnlzaQN)oyq@JVENwT?e z?Rjz#LXu9OpLBwV;O}#pbgfi7Ar{ATpO43>lc(9RtoA1=z)HR$=ue*Ir%~!J55(uw znIHuuQ29eC1pMP#4FlI_XGS}?wYL?V_;{`6hK9eSEE&7&_=ht>V{}#`YgBZ=X45k2 zMZcY&RP~+&eewC(1U0Q|NzOK3x{Bkc_VsOc*}1gTWu0(X=mA8z5Z0{w;CaV;8y7fywzN zs!#|3Gt%W`(W6_xgALWW;>{*Q*CM_GWHDL$n1@Dyc#GsmiL!ka8kRe0r@;x~B1T>V ze25&LBItziGXhz41B?6$0!fjD1AiFxbDHyo#}sbbVWVP%1SYQ4Ov%hiG{ru2kx5{8 z=T(Tz)~!&Kp_MV$YFO91Rr;tf)>8Rn&+5GvJ&4`z zP89F3>C;+h&2zd>NY*r_kfMphWb~ue5#1(-e1mY!cge|M`#M%tH3u0m)Olb|$RV6_ zKfh*6p)b{7oN$0e2#sko%DR|7-!`v(amXR_NM`}m!ZNWSoY~u<cnMW)nXSL20UF2JTUAJeY5g*0y;jCn9hoS_|aYxSx-1c91d zuF<D?)n6}lTail>xQq5G?7MkF#=4} zC!ri$E6CH~kaW{B4ol={_+Hi^&)twl)#{gun%|bo@ff@@G377iIbF`|d#Z6Hs309s zcr`>mR2PreSyzEQ%Ypvz$WF8RG|Na5)bimDkH`@)vUt&BVPyqh!Mvb0Z%32rc);m5 zV5ZVR5KNON0tcgZEr9a`>yPbIV&lLhD~P4u#AH`cVr6Z?M`O78af@a*K7N!KaCD!k zbaZ4U1Ka3Kac~5>MzQdW_k#5mDa3QT46{2vZq0Hd%mKo&1~~Bf&d~{DIT55DPLAMM z{RaF$s@R~n%4iiI=^F;l$_*aNo6}UndUbxIZVnCxJ;_Is1QjgK$FR_$6?4X#%D;+a z50MiG3x!A>$2gNqd)RG;Sm0@nmbx;fD8FyjN}pdKixu7o3#X$0d^5Q6eQBN03a(k- zXW-t+WiEJ(lPsJ6YTD@IeT;$SdEi2NU|NQIZm$n>UssA*4WUmBH`Mu3GrESOWzT*f z<*VZG{S>nzh&5YgE~TeO@twAE%(`@)AUr2 zz2RpxgMFZ~HUYCz-w9*z9-L(1zG%>PVZuVi{a_G)P^4a0nipaDd zc&UJsmkWsN4IF18SUO8{Q-RX@rFc-rq|O${2e!qMCY;cTRk0dBMZd~ zN_FJ`RjdcXnRqsE{V|vyr-ISd>-o2VfxG=jKd@*_ZfbkYH9JWk%?=hJ4pKaX2Nvx@ zggjd$Aa~Bj<-c^l7Sc!~y`8;o4;eGn$Z(9+JC$g+#UQddYsTCY7w zwAl&?b+e+6H^y#J&3cUMrD{ziTadx&nMkz6Ok+&Sz_Ae)0Rj?IG21$03eg0#x!ya4 zp;+X;RhGO(#~Gj#1*Vd_cPhyJ;O@xX;naUB0++eeYsoIGVcBI>YFlP%)P&MN_Gdr| z8Igh<-!c@qbjY<@;U>v**dtF0+CphKa~ln5z=DDk{iXNm0s#W)+#gwz?Q#&fxMcb; z7N(|-WB{*W_q13B5_Rp#-|yYeg37&Eej#AO7Wjc2HI(#x%Wl2I*}fFq%J|CL+t&!c zLd*^ny9Rop>rGRL#uC#nRV}wR)p(TNn5iQ!m5VM4 zKPeS({HjgoT2xa;!L%;y8^py(LY`ZAc?YqkbbEmrZrUaMD*6p#X-x3Ty_}B>bXIMo z&Dj-ob+S>l>?Pwr^YiNR9^RKh&O=J7=~Y-O+E#}3ON$}B7DOr6&Ca_~Qm?-)kBlU7 z?x$`iE;p}Zck-xyn1br+%*BusLo*rtv?$;7B z)a0H7lB;!|^x&OeiliLzzv`5anQ7W(H(Odb`2vFJENhJ)u+0)tGpLcUVrV_aa=j+N zA#4Nl7~=AHOX{#{4U!6+XDEv7Sy}^XMxEA~WC+4BjIG+u46{eU$(7eW2*`TP9~09B zO7be`7^0*9?$lp)bZdRl8)t|x^0TpOjD9PxEK@f;%%wQR%;B{(JK+yU zM!hi?dbJ2graiwKUwzCZ)U4LWhaqMSc1WZH<`{Ep;&E$ibkx&pF7!w7T-*k<<@FyC$Fhv` zB@|4>MkTzUNp%&LEyPYi6i`5<*wjs46c7TPk-1DE6k|b*DsLP%E`ui1MIdA~`BrREH&NlDID* zz%M}kRb41HsLb2`Aq2Jj=WR{p#Z{XqKJoXNc>2Ld=)}3Q$jSUG#}!T1cnSVKf$922 ztq9=-E>KW~8Z6&rf4O?FCg;7zQy;u8tb0lP6HO?D6@Vn^$N?ljeoSwKw$m>zYLSr( zMh`vE#^km(h!N(-DY~L-1(hWzH}0Is)(`k7kP3SlE^MofHJWh8;X4 z%AwunaLMm0bQ;Q8KkYKdt)F)4UE&)z=VCPBP;b z%@@I}8MnAHTGaZJkuR)#a=q+nw7q_gm_>2RemioaNE0UjsKLv?dSzeoz`E@TZ}>US zvv!rB!sfG74L{5-v9F`8y|UUsvU#<-T(OYB;i~iQ*Ut@(KwT+ksHn0|zG8h#uLCjH>ER@l8P?6)45(impN1dm+eaEZjOI@<1@x@0PJ%`ul*u%$ZMS1SDuk6v!3 z5U<2s+D`nU?gGdmVI>5Egwc?}ztDt8nA2ibc5Ccu=W5VTXjEbfiT?CDsnei;A30kT zuaeuNA|`|y>H|v-4%deogc2i&%#JO!{50@2<-5`F%uLe4%pl8PV9!3!(Vbfx3s3Xe zz>$aNPCvqN-kyE-HYOMA>$fr0V+M)gL0&p#iD15OthX zJ6ANcCq^1+$JsGFC-FE^O>P%G-1_U`?kuc;1ryk(v{5CU!40{QJ#Vu(g?cQYy>D-C zLqZ<5fgWgF=NU@4Yw^rnBLtexo4S{pu^>~3a1M{T!8FBB?e-MQ!r4t)?^cVDtv_&n z9M-banxSXREGul0_mu$)F6~E0*SBXFISf(z=_Q~l!?YkLq2}|LTWowVfEHg_Xj6ZE zE0~XKyC$14={#WKdp|p)Ho(EQW6G^aW^U?PG;SZFrsi3)lbiZ6h`xB~B1UzGNNmHs zI(L=ZgP}_~&})Rv>83(lBGMkaLdh1uNhGqJb%qBza`7StMU>21)=N2fAxnMtJ!XH1 zCVhWYcpdGY?#xAyEs^qLS-Ep{HmS+{d^^HY*C7qAv-IM^0bbKq#_&u+>Lq29bW*y=R6?4{>-b#EScLzKV*Rn)Y5?I=!N_U_VD?waiS zWr%&bV(0?z>o@&7O^58!Wcwy($LXD)t*TRgrfk8PJ`|-+GqlLQ&ZDSz2&WK$ z+opr8&*#E(+1|Z?(cZb-8RThwCxH7SBw_4ck>_xJ!8JwenxV;ha&L!nwP{#{y|AL? zO4bQ{I*Hc`!7gw;)B|&&jp=evyRO;n|4{V~%#}7>xNvOS#>BR5+jb_lGqG*koY?ln zwrxA#e%^DczB+&4uG+i1SNFQs1@2-QZ|^WPS5;Me`!eN~i+cJHyOQqi*i_&7kCj(u zutc>i)l$4^(gCW~oCE5_Ojps zq^+1*eW$3Daf#q?bgO@baq6|Qm=sl$U0fZO+m=k$GS6@GfHg+}VfCm8#y}9vL1Z8Q zVQLbBK6sFQ%GqH=XwasnrpHGy!iUKLB6qh;#}1_NDJeOJ+rmtn=96z=k%AoXD}Mtv znv?aJ0p_x_!i$o<28YpH?WP@h;v6h;TtCx7K2l<(I__#Kps18GicM0RY^Cmk;|J?Yk;N6Pkna8u4 z%5I58@h6W7{zJgtjRn(ld8_hdj|mawkUZwq;et_fh_m>r)o$JW)3W%}7CPkSR$MZ+ ztujme;+*avuuIc!r{seWmzU%$r0djRPuc&zIQepiW}qLcu-g@7fetyX>GJh@;^tOGoJp<~g~?BC(a7ihuux zLM6f5Dr3}l)n;V5Y_Au$Dk~dztg*UXZwC{LBk*ip2CfPKo@NbTLnukd7%OIn!;KNF zr1Xm;q5rn41%VVuOpJ>+ya;;^wTSIT1VN0X0PGVKJ-REn$#Ey;K+^nqhoi&U`K!_F zUZ%0>GEfM@q_h!t1Jzpkki!v6xZS=$ZXO`#JOINX5Xi__&0UngzEu0>L?t~LeXG^Wb zT{A0tT)~sh40j>CXGSysCb&UQ?9`yg#{BRR7WF8DMv3v}13U9FVm&*R+1Sl&<4o}g zpuVBtfr5l%fqHCDK&__xq^257?0xa{TDuO&;_BCLcjS)<l z4q0IY9B$r6;(NrUn?llVPhWRQ2l)|U0YL||0xKEMZLvt|3gc#N(mO++MX-2)LMwu> zBT;nzPpmD2e7fk6q>qJllZ;0#L0yA3a{pi_6W3Wfn_|0hM!M;n)6g@%Oc1~Z4D-jT z0wgThpaL(6oTGDWe|~Z`>8A3)lsBV1(psL;H2rv>Z8;;qTG81?ytGYTSp7-Ng#JdX{>-zxoVx~?R-tQ}@I@77 zJuLV_N&vl7(wHTxa`WTEq~9%Dd=xOZnoF`$xziLM!XAmI0g7ix<#pk$-U=x^CfAvs zX-DM<6{NU&>d~Qb+!i;X8)2#(=jG<_{7Uxr@Vo=ka8$tb&R!AH1nF(yT9luTnwg}- zL3Q1Lg-2O8yONK@S$&XPV9M=qg!xY#ED8t?@yA|Ssu%=`0-gB8rJ#>;ax1ves*T63cU+Im zF0#IM*4rm1&S)TNDMR^OM3f{z+~5wMCABwouE3_-e33@==&f!n&DGw$r8Hz==Ub3~ z^9oO}gOr!1DTZ5Q`&`~~F_1)AV1B$n^S*WA__9-C4DjmW+m9?MTf1mF2f^?LK*>0@`Gr*%H-w%tj(-W2EMZv9|BuWR2{PLJ8PcB}1Q znkM#q!VRNnsK4_9a&3xAm(!NY!lE20$C=tVGeu^^-ak3?tIi{&+5ulVzMMqTJ3)C) zYu4cUP;-0aUqO)bJD{OVfe?YHgRIp7^(JpUxhe}AQ>$yyXiajC?3~6!p@03<;?s;wq5yL z7@I@vd8zKJxVw4f;66JTLZFct2+e|wT-jt) zN|oR`>gAiy3!5+;CH_u*ubGm43f9eb-N@`TtD`1YhFPEe0%HS}5WD52TNMid$}7iDt% z#Vy4IXQBS(zzY%-h{_5fE=x}h;(-Ze^thQtKp3Q`iMmUMPPqms60Kkwa7bC|}LW#5_HN;U%K`9|3%R zCdudWl+?bLvsZ%>LmE?x3b5r56SFl9c>{F+1X!txxIfh?B8WNEafwU!3)lL6_Nj|2 zV{klXc6%|n3sNRSp3pG>J^l_=l~rb%B^h?swUzu8tv&eUfv@+G^VsCxEqkzDS5l>U zy9TtQ9p0vEq4P2(0@j@R2dcX|mflJ9=9HRO1vf;VG5-3*T#Z|0Z0 zPqW)h^Nv@Q-tt=WsL)l64|ZYeEq|(C=&-6!_lg)9rz|-B^UDd#TpR z8F4qcf75WtQrimuf*K_jZ?i?YUJxGwu&&-oJ1N*(=B(%Ur!u!@Wov*0vy)oubn9;; zX`5jJHA#Zbm{aawjn1uuX9c?XL&O*N+d|^by0P8icnIYWxX;*AP2|`2Lfr&;+?OJk zI_iEQa!+{WlfZ*Cww8U*-1h#Q^QlGI!km2aP174|?+jhN8$9cCa`tP?nv)dPb@)j( znrGYjMBb9#!JOgQ6jxCbArZkR+Q0QhYWS6j?dn6W&$4ZxA&q9xPaGhxl0lf)fScJOu6>Ex$G zJO*G_FCI{)G`unD1z4Z28HP8ki!)FdedshVX7Wsie5C{-fxB+f!K;IG;?~KXrn9+h zmaDInoR3ZaV}29yLKTl<%Hn;F{thGLU%d76m>NshBEnaub|_OwVx|Cl{vW@_4<&#* z$eXJ=ISeH&ht0*_(@N*#?sS`}UF4po>iMk+h}WVI3K@>NMh)-1w4y=?U*~%F^ElNc zMeXSBPAUi@nis%tHLm;907^j5@8N&cz(!!sgjEN+@XC{Dm1cDcQC1DuJ} z>5iI=i`djeG&(8`3BsIAAN?*IK9OFK?sYKkmPcIl$MS|T_}=|aW)6U(Vlv?~brvF~ z`gYq4>b24jGXSuOTSh9HuH+mx(>*rb!g+WNoY z;rp3T^oIwL>o&$+0_pz)+C0sUJFk=NQU*RAo%||om~YLslkfL?j@kPA{&fOk#58v$ zk+f9tQ@6O3tNcM5c^03}7hGNY+Hri?ug2`5RHQt# z$EE6e&`_%SXRDD>8S*nc>MSFru4e+;dF9s!n8}3o4(f3ntgs@nlYL`eMx+N}jQR&K zG3^E!A(aMfWWzyk8%{T{j59^^W?57T(WvUn+N!OO$UEij+lA(6K&p@+2(eIp%Qxe` zDTae2UNsP8#LQYcR)v>WxK!WUgNE&|?a$d_Rtx>N2MhF(D{qVKedV*}dC24LzZ}M= zVyzoBJs?wQg9!l&{~2L0DN!2^!~j_K79g?Q$1g4^CHJ11*Z(8B6o?6qO`Pk>3mg#6 zG5|=pn=|s~=ZHLu(I{H-#v)wIb>c|pK*4UMEuphmxiSnO;c=28;@GTcA}TMSzZcsb zuyF+GLQ+Kk=q4h-Yn$$ALTxH3J$utLt;M$qv|0eSx}$4`q`9d4l_OPlWpN3~>;7on zi(8UFC^xXS7eGkRlgV=cpPQ#G-oUHi!>V5ZMPxVp^p(C&kEa;fmCBbumXwsd|CChb zZGs&Ri{(4#gm7;prT|97PsGq@y~`bNe6cORK%n;@3I0Y7>(M2K?VDHcxStfMu_7(w z$q)m>n=1L*d*n@_6xK@~2b^{4d5{{lk?g8`p4SiVRkP8&_CnU*N9+L7f`D5|LFski98 zL!fBuMw-jfWixkTNSn_uXUJDdID+jOu( zJ5|!?>CjGSD5rs7w@9pfY=0r;vsIpDf#{Kpw>$xxp1@*BTW9+>(|XT+2SzRw84?Uw zWhM1*cImzXhjJ{^|Enbn#tTeBF6_Z;*@j3-!A*3gZd#eB^z|D+Ql|RE$o`1HjD?YN z%?-Or;e-5qf^` z!!Q-H_ezVRq*vKZ{{qwZ7{naR$z=qImp3x`o!_XNTjwx0c zq@O(B3>-RDy||bWma`3VBC@EgxcK-GPTX{l47d{nKaJhA932tJganu^@Xw!ydQb|~ z|J`5z+pzIH`BjxBuGy#Y-}6H*M%hSk}qnl~>G$35DTYkBR%4w=uw#U3Y0KN6{D5vDGxZ&E; zqqug*k~0^@t(|AmpUAan>0C!2pXY$#GCusFa zpX?t-Bz4yVu3cy>VW7B$EWHkm#;*P{>N>wHGT|NplT1?I~1 z=`YJJ6NbQ4&?lD0MJc`Yf)`EqoNng9<1o(uXgj2b#~Tovb16ul4iuJWR_N$h46}@> zSu5e*RO1vh9$ZTKntx27vkYf)N!rsFHpXV0I5wS$N^+HS9n&_ICDa& zOQ#2C(@E=;P`7`u_?sBXa;08b8Q3WT31sqn_QHvyG`wj09CAElWSoE3JjT#ulkKiP z5{oQC%2wiI)%PvUFKLuXmzL&} z_f;WMNu9ANX`%4GW5q5IT0nW+?VT)1s{{EKO)=kdL?+5sX}GoDIaJxxhVOo5WDCi;|got8>3cZGESI=O*p6At))ghy)O~6_oN9z zPOhVfTstbChsu%BHxNB9_)||DL+4pNVh7CQFX)3QCm^v;I!{iD$PAwV|eic z`6TFycYYfoK-wM;<>K}B&eIiy9L&AdR`bQ_^`iI%7a{hy)@!$~KgYi7>oismSElEC zYRA&_L!&&>vC+SLH5qN}v5D3l1OD7`>1bDXqVD>S?Y+7s0#7Oz;P97jZu{Yp)B&Bw z-%~j?-rB1se;rT0YiXbFdqf84=umocl##uu*THGcT*L7N56~cF%NX(T!bB0zY`rA} zO*%totc*K}HTT(izsR&slpV&xPdVU)0B%G=kTz8>y&#fLQ@qsNSC(Hdu2MiV(RCl= zfA&O1gJJTbqo=yMl)~9{$#%otceb@KSNsRy#6YL>_zV1Px299X3Y=uIED$OFdwV3K zfixF*-x9-=R3J`j`4+%REe@yz4DjryeHH4-bS3KY7>ZWoeraUdikB`##oNrtSo-+> zt9{_#d@38HgvcpXj&G3pU(eO$vK`waBm*wr^{eLz-jm_eM|a1j-g-0yw-?!8 z!|&Ur?aDOks@uLex*UpX`hVT+P>)=M0N=)WV`qp0bSMA{n#}=v6jeoG35vW;<8&ReS=GgD zPxk5pf(gXIXNx9#{U8Q(#e|OKj}NNk6~y44g@@f(IhHn7BRq644X{rp=f)b3tU9l~ zOiEsrBTF1mb`ga_8yOAhXcuwx6*e2Rv2n3|q7f;u1RCGl-gbC_fG)2BM&QEYQpj9k{)=i#FEuP%DX#3XB26%^fx zUXmnt&8{eghHAegW%nE=QI`{6g`ZLJvF8GnaqJjccqP?r9;UQ zmsBG$9KTONnjH=j&XbhBn74Ry$Isn;)m`+=Qn1YS;tzvI)@@qxP&qv2d%Bb8`G?ml zR!Rx=5dcptLu?RfuEz3TgcB2ccFvclRPk&K?Wf|hW{(v~1sK>RpVYRtF|PFX>PBFD zhLgL%WsLfgQuEFWum#voe`R=74@-L5?<2N8TBt=}`80C8E|Jh9v$zg1JEJGezq%3Uwa?rMWz%sWV?lU}5^#p>O<%{t-Wo^HeP>~`%PxCT%BXI@7u znXm7*svvV=E@ z!^RNN+rEfBA*T{Df;WsOBgzw3Ir>e>pas%t%b*YYQP`jq4;?c0Y++$sU2 z^AcsEEiFy#Zp}4Y%MQ$Zd^zBrgAY?j)slU-AahEI)2nma=8J-nhKn@H7k?{GS3Rm7 zf)U!>e_9@TSeyl)Z|6KM27da>HjrBz}ME~+^(a9$A#OG!$So6hlZdM$|)&X8MDRp=A= zYwTAOW8+F5Z!^h4ZiwbZdf{t(zS@dOJ2QZhX8!WTpc(ZPGuRB|AKX( zNPxpKOXx}ao6%^L(!uf42ZK8*0b@jdUY}uuJ?N~eb&02exF-bIQ`1{iy5ST%3MuS zL~v7-&53R=72EdXS?!Ih`84;ly6Y<>;Z^&yj>VIPU0d1yC*sS_nQ)<8*DpHm#^$Tv zYReB`As2wsjFS&tc7bE6l({a>3T+I+5$c1YA7p4VmsDc`-yC}hC$LQ!dU zc<87)=&K^2$8lDsKUlL9wW|4sSIfQ=2F_;xD#joZY{T1t8^Bh)u{H(95VPjD9?O#= zU@cPT4Cb$uIEHo3EvT^EC7wJQN#0)b`ghlQu{$hNxP~0W=CWC@6>2#FHNyddGjJLyxK61fQQPQw}i3Clm!!kO}0Th_gy3qu>HfYJea)Amh|W;e|c=C_N#hZ z<0#wB)dfoTj8*BQIRNZNgs$P$T*|Fh%c{sA-C%)1}+Vxfw}YB|j&I)2txuWZVNl8il8^`vU2!__~1&2VU52FaIr&LsA#Bl4|WBvC>$)ZT~*xt_XdKs5s zkYV5bX$Al!<@jC=3S_dMd|+-`eig3nxmX^yFA}_}AI|h>DH}L5Q`65st4AoZ;M%{p zyotJeYOM+PBs=TbRQg*f4A><>PVR8)`bVgRMa)_7)Uh%6;Ikb2Rh%MUF#QSJ7QZ1F3bKn*6Q7Rf4ktpoRpI zBzR2$x@16s6x<{ItRtZq7KLoRzcFRG6c%U5`yo) zN0KR)5M)9U8VLlkI=q}(j+g9Um&Ru665ps3a_usA#Uj*{!0f{R-US0)OYxx2ziW#M zwxM(DgOE2m$(17w%dwLTlROm{_(v!En+c4PhZvX->=r0g!Qe6A!IvxYN&XOF^Juy@ZQ`se#G%HQ!{+{u%vu28!7 zMQ-;5e44HM#uj@4O`%bQZ|6}*q>FYzN$BRX;}nGy9-szzUpwfm=Nl1DR!o@SJo|4~ zr&@OgU)E5yThsj_T45 zSgkSCxl*q$=cg22YP7Fkhk{nV`XM4|U|V{_L4hef(8-%U<--GqtTQb!tEmNX>4C7a z_Kqn_4KL^s^14h&EG(-pxYqLd>rO*3XlemJw-wZA;*h3Av0!<}nblh}LU}wJBI|E>{ zllzpl885SDubzi%Yp)7NC*vipbUufX?NL2(%tOQ{#U@(!;*f4)#y4Z~I!46le!A(2 zNHEV3vD-b$S8ep%fLIzgbDEi7QAyJCu2qNT_U#S_9E2-*vNO}~V(tPvAtH&W9VuBC zms*XKEhj>QyB;38_K-5hMRAB9q`(=1*3u9dx5o(MqX!&kJH&5*moa{#v$c30@SS6= zZ0$H58kDHGBxX(0YhIVoAlnG6=Jm{l$e&d}x+kBqR`+>9XgwN7(^<~Z5qt-D zZWe9_n%q2W?Jc?T%xS+KC{!?-5E7sx>Y+X_7#^j>M}?kbnrEf!jF_Szhi#KeS%j`x zrc?->;^(?n4qys)Lfh10v60Pfrj;@PwXscX3;;a?kKS{;*@*OahCKPeq5DrA0hS(+ zDnn9R^-A`nt;XD!;M}&0QVy^`E?yd@F@k_`2V(b$(bKziQ9rKj=Iz>C)ufw7)tv+B?k)2%etMd) zMP@jD*t%px+!p>gN0rdr++6EJ=G9j*NCgoJbj~JpewD`6)?RYwpyp||#DAxveX43a~jJ92F|3UukiyPF)4-O`?tQe>_o()KF2<}TRDx~$r zq+rfUPPTpu3{byFq7>QT|B8D}Wc|Gj43m<31QPKDf_)We@6O(ehs(8z#SktiKHUJQ zZrRY`YM8QM$L$3a@d*hTX&ln;9b)u=ttmwLzb>Y@QUU!j;1dey#da3IC9P&W| zzMTxG(~Ly~O0os9VbH0QvcKbMjat7CHm<4sG8(zobPLzYMtk0DYl984m8#n*Nonlx zx6MYyGu7iSY?`k~FGuP@c#&90K&e6pE|wME8>apaO6lz7dxRGy_c_26V3R;p$6Igi z?0R*0@}s?#;ATV#hD4l#ZJ$8r-4!B1qKYO0X@TBQ-1{M7msH|RTJe9YO~q;|7WKRy zy)`{4O|`4qJvd0jzoarP8VRuW(Uz>-2nX>E#iFrz##i-Sbfx2DDm*C$ZbKA7VIxB^ zAjVqKr`^E_xoNWHd;>L@sIYy}xc$9=LhzrJC16Ndk2r7K1Rv(xRE+PSh>&CkIjmfk zjz!fSfKqQ3hYWfl^gm#gNtSGvDv4oK!_ySlhSx8ij@B-$%#lRM3S&v9vVE`qt#rdH zy7T-tG&JcfDD=}c-?%8g=QA2kW~bR$*xTB@RUDq5TnCFYpLv6-p(d-R5!0=+kmw|3 z`b<}e@o{qz^`p1q^DmNT*wJU}-`uP&lNSwugzzycF3u%Ik(c(wAkyaczwxu!itF+w z>_kPs&|n6T6C9)|;^bwPiB0u}yJ6>Ft+I4p7@vL>ly<$&7jzB6ic|C@Z@@!2@Jr#0 zJnd&6LmTY2t;yY_TSE&Jv09XD#RsKY`&ghkT zm%CL!+Z!n|Ys}X5B~*FfG>adomj--CH}oXF3+@4uX%uPwHh#RsyN;(5!d(Sa(?eQy z$s;j9iB+M;w7nMgMQz;rH6lgh5{lT1USvuCb=tg2PWIA^1SLIUFauuMb+_cCZz{GZ zUJwfj34vFeUv4NQ)BXeq58#-|(9{y(Hwa6|8l4L0-YG%q@jBk#$t|LLJ)Sx^rev1; zeiP5H$>TF2SHPU)u%QYdv3ZqdImq5TGOfWnLvkA)xzP*XnXm5sQ>|OqS&l0z#LF)1^Jq0&Zw1$nkDmHD z)64HU-x*kkVY$DsHV7=%&50Flc{b6^7_?NGl7NR^)bBrh#U$x>g^LQxAVVpn-kEMt?g4IHB0r>1oVH}7L(=V0PppJ z6Q3GMKq5m-jNS``I^3L&Y@1r!Q3tt+MBYbTVVTC~iI)98*B*qmmxhm>-VY6iZT^pp zoz2h9l(a7l0oZGws|v`K-8gGpp&ZcQX*C#+#(bltHnwMK#9$GFNN~~uPDt!KGbZrkE$m|Fx-Xy@kB5s{e z(Xl;uHyS(MtqlSV(=v;8NZM^*XN5VTBqr_t>bHKc4Jwj`+YRUowc7&87@VqOFnk{2 zaS`C2X4Um{2d`(5q%n-H6Zz(ZcgM$>fNy9eET7j?=_5(9+S%BkyUnC-9TvJJW)(M5 z-A&SCXyK5Kk|H%#*K+L^bYraH&;Kn~#Ei^Bs?*Cwr!Na~UbT78oejr_6aNeh;Veq znb;i7>jf9k#A>@upwajG>iO||BvB4ZK>qBmSRq0696_`bBhL^5m3T*!f?^B(<{>e0 zlTG$bFqBpG+8JW$sOlqT#SN7PC_p2CmJ?rYI4)oBFgD9=3`lQg+2#WiczmYR)3TFe zr5!V{x%63l5>Rolu`^OLE2yN|&*cTNDxV|o?J9ED-1FZ}V9y56P1THc4M&pXO+AY& z!iF^I60?^On(N$$)z;^$^i9S$-hyuP}sq+eknxTZ%G}YDAKl@cL>OC(f_?_(E z9_x7Fy&_J4RqmcE~S{DH>vmFlvWYJY)G_zy&T?9uhcs z*MhO=`M@IbkY3YLY5ueQwQ(N1R7`F`G>C~Q;8dY7jhe5d=ShU_-?{B1%l9r3;~f12Ozq@-ow{#K^7meR-`s2&a9^B5mKl6T8EoHbUfiXg z=zrIAE*ATDe>}FPbP|jFeD@Q6-(TO*dRn0`G)%)F9i>cYc+RWjFI+UmyW5n+ec^+D+vNjI?G_f zI4_JyuwFC#sUf2}n^0v#{d~z#W6znGy$Gq1TM#56;w3Ur=k?OID*8z&8|usBrZW-PdI}iO0MU;@R-D?l)xl(NG`%LYiOi-A;a#n$p{pclAmW-WVbe4}uGKiKD zv@Rx6(E5J zgJw$5h0lB>Xz*=7;YILe*SqU^ixMXyanT7J)?BYa?fV2NJtvF;;-=SAV*0`0H0s7R zNcVFQQDQio-78#7Y<#x(1zru>*HgS zcpf@C((p$nNV#Pj>%T16Q~37V6X#Advmn{7wMS4m8x;KX?NVxpvo;<}shB$uLtv%`!*8>A6K%l@%+j2!!9$yVbfxV%(@md*zzP`Rk^FBa1_;X%nS%v!Kkm(YV0N;1 zEdvsPPLahW=#W*78cAyU>1-{xeJL&R|LW$%tS5jMcT)8D;$kBLo_b$1_NfpKj3=XTk~)EWsXn$BhY{@5=?z+t`iyd@_XXMV+m#&2^+Y4vYoL2J!9-{=hv zHXWl;98%=LjgZs~pwb^^C_L(Ee4dZF8r6~KM)d6}dfs^V&x@|_b?GWA`|7KrOT-F69|n2pi=3n;-MybsCJuEDdXN9Ye8 zvnAT27Uy0%KFZrIVS6)jDsr2Dz{gPk1fL?iqe-v*4?7*xZeh&D_}=*! zrGi_hsnE8VJj`M4bL;^YxCZ5~Tq&tDra8xn5U5VW2@ldHf>v+j-FtKtDGa2Eg1NF1 z(|wq@_NZV*Ecyd3u*LYVZG^mdy;)gF%6X^DHq&3sIfNnq@!5v{WIeYW{2%(8rw7Hk zPxLJ@6gh(bPP4^BxY2=itdDoob-g8p{<@BSrC%STdEa10goU3XyV~R)doetLr*z7u zHDdn}^soGuAA6GokLnB8!Pr&&IPW`E^q4u&N^p-=SOdLV7Yvh{o!8n`u}hloZUDPX z_nM|=J;7i&4MQ~ihHm=bkOt1D-WeF8<6YkCF9}sK!ma?$yF3s67#`1Ru=gdt6U&#d zr-}YP2#?XPy8?y1#t>~->DF{uir9*RM-bhXWBT`=l_aE#4#mHi55p>+h;8O$~x+>@=pf!<$)@Q4k5RGH!V~P|832cam^Y=p7%b+f@58 zXHTaW1mQf1f(oShUF}V>n|l~Klk~O+sK7#4JLI~4gtrw{eXOYjqV6uD;<<2A&{!}x zB1!Wk=j_`D!XP~WniymWCdZ}>G$$h^s>EGh-`-$~)Yw##3~T6esC{HPMbm9U-YGr) z!R;H^4A|imfA{4I;~z#m@E&@F44=1PCQRaW04UPadt8TP{e=gf36&i+lj}lt?d-4- z$FPsv>T|0$jx$JpJO}E>#Q0WrU07p7#lODjiRf@IDmqZR-B4TA#`yw-E?&-xWQO;M zGl!);B?Tp{45Ok!kkO=3c1oKm1>ZrLDOH-}w9=hZ=~1QPxFrYE8AVJa_;NiZ^?2q% zTs2LM{5mA%^W04Hhtr%mVq*YC#c%vb)CWh^zyxUIRI@tfXH?q3l_DQ4-^MZ^3qDe?M_Hs$a>Hv>gUk!Fv8v!-BN0OszB1ZwmO!R11nle|HN!*rXp!O%3 z#h;HzOklRg0c^>;Vq+4Ku>+&qX1oyHCpk&IKcx3DGP&{X5S4lTAy8eOa^_!rP9)(B z$1S6Upp)Hjzn+}9K${aLF4<%<8I?0eZ@%190t{LLs?p_kr&oY&{qZkFp>1QB3>s?`#O4@4 z=q$Kqcuo#zCNu;1a^*q2x?rQFLHVc_JO?Qh)i;QP>=z-~q+h4|7mVmt&%%Wo0$5-t zGX{72Qw8(*(CiY>oc`YvW-QKE8FtA5H4dRnp|=!@jOUj+_8wC+qaOf(0E-^-RXcjX zuFv)1Nhbc(^n8%DdMN~nx5vTSR(9aSM!!EMuV*mWyCrI-_d1(}UZN3#Uw6g#t_6Fd zj=Sa0_ltR1HsRSoA0*7mcxsFE#vLEsRSJB~4r{Y?6>q(e7gA&{Nyupy?F)cF!WabP zWVQP2cucUIU z)pnsz@tBxN_{eG4*iZqudbEU1Kz(oFl!!eLr==kQj-W&9+W9Rknc-#Br%eN9EciJv zLFIas1chY<>jD<>xwP5yzkcF%_gxz@?p8%tJqjG26R`H=fIQzb`OP4qXLPD;5`tonk0h^(JK5P)S<@T(kBx2vJH3)i zk~Fn3iQ~rCmg{NKbAe+fu+8yawj(B} ze1!e8o$uMx$0i%26o`1`Q?{1ETT-MDG^gPSI^?+(*e*;d^`069#HhD5@X#LwPcQ7VcY^G(10B1FuN} zDd3vx=DD}Ix%J(1wD21SHezq?WBcbZs+HH24+|Xg8%0Cc3$k{r4V7lCXS&R;;Rf8o zAR-#QIGXsk1puJ>e5{z|@6bWV8gKF9BWaGCP6fcO|4r59cTImUEXzS2Ln!}%D~o}I zl5utmRSCJ2`D|BjktRXZkE<>FYr6u_>C#c^1t_6k;PC<#S^pqaJrj7k zJzx9kd=Zy?!_W|vzU`EacmzkrtQ)kcEu3xyWYdEEFGp?|5UtF6-&NXY2`BE&;!f=_ z8gVQFPsmCjkl#)7pIaXkJuud=JkCqEyT(^ZLwmm&8Ky!vf_Z;l^^b>C_S(=qWMB}V!67(IL}v7zs$`9ikX z2+#~=nA=#t&V>2*A1IiiJu*7Io|#A}cwPw15W&8#-tkG`#yp}g5fC>@C+NU@VG0Pe z-9q@Rzjus``9o`Zh)|u^h}=eg1Uh^?5dl~I3tvLH&HC{J+0R^k*%0X@?EC@!Gy~uY z;S9pBov#X4vr{%)>_3}XbvpZoyZIs@p;PcH$hEBvEhugk|Th+cTdcelPy1q8(4iABSWv}Jac9m(?{P`p`uv9o%;lO(#3CtDgqlCuN zBmyo1i@pBC#|K&6lM!iy{|t`~-BwUQAn^76R0LLi6Yk7_!k8#HmJ)=jw!7?mXV1Iw zf*SlzLyIByJc)xcrcFrlG*Yk|F^RpWbdG({>%NypS8g;Ujqh@&8 z>mAqAaxzv`8ap`+pv6a%@2)AUlrt`C4TXUyI?TNd68a+=)TC(P+Njw8!i9ZNug&Xe%k)ylEWUQGE?LOQs)4_EW5O+KC`m%F_K z+(qrCn>D8D1l&xA{qvsuEy-95P$e4xpmH1RI-X`H$ynQ~WiUg1SVZ45a66Vmc^}Md z$2;|A?jB|MJA*JC*Q24?;CT`cmw^N)j>w;!i)&zTHJ6(zdx?|x$X9|wO)~FOREho^RtRiN9&Y!<#KqRVRpb%{ zfFG85TZYDW_@BUE(BW8*a-*x=its4-?9HpXZZvTH4QPE2`2#Z@jn;W1s}7!XtBsVb zRRV6T{Pb&sI{a+y44kZZJl34>_uVPv@L8AkM>=2f~Iyy04#P#!-q$6}k@u}? zH6SSYAX8>4ch<6yDGHl0JYU|uf>IaoSv#ov3_aM8oWf~?Lg3p5Hmz>!T3@^m{xuGY zSfJ3a(m;uXZc3Aa(ui%ph>LCye&{d@6Vcgq9}?c6Od#7(iN=+pG|fZmg9w5+C(2ol zi4%ig$;u-&ne&q4j~g?Pyp$7}KmR|zzB($(_FEf{o-?e(U_l__Ie{t5K&m}q&_^rip?s=gpJ@^J15#<&xPwe@smS#)Wx92 zGa?9bLDCcYBc-IlK9WGyz^34J6$5oZ$#Lq$#Un{|qMxgr z^$)B9DDM;ykPKNwELQ~;*7 z2eSwkOAPz2|=VjmPy%AHvg|VpYTUNlEhl9*3}xIwtpK|2#_|ywLX+paG0)MqnYK*#?WD-k7`lF}uOX`SCnck%LfJ9y;ls8F z*W45OnghV3;6Bd>lc9m$j#6&ExU(U;*h6e{^3O(>>FM{wML|UlN{ECZrav3-ity-g> z(k;s;_4RCw-hcF++jsu>MQwO*L7PpOZ2{<@C?l;J9eN)Z*SR!{%O48paMIpSPF<1_ z@?SqN>zqMS6a?X|&m=psL3)n%4k5@!pdX}AMuEBBFZn{5k4@xA zoHVIC-Bf<@f%p0|@@h^o7b+nR@|YD1?Hg_1pzXmoMvZ!lV8qu;^6$`A>~CH&8DVjM*iv*$XO`MOZnUD3!X6u(SkWjg zZ3v{CgTG2iSf94$tF6lDCk0&|ykf=F);8J|M*&#%Z>*$N+WYI&{Y--V>?K*kwZVD^ zyAaQFxgHU<2@1iYCgJB6W~-Lmpfl>)AD%c*OD9nfuqtu(QN?##oa3kKEb!077+s5_ zs9aa^bz7F+YX3jBPrma!Z)GT;j_=(K5 zJA)1*8Br<~F77R`uc{GovAr3T=S<~}1)#Xw&t0V>=Yga5ZrPQveAt+s!0XA|)#kIP z3E!sUs{7l@-|D|1Rk*=f8q(ss1Xk!wif;Xvp=;5yRQX|MH*{1_Kg4O$i3pY2aABJ` zL;A^7^gW_tPB^T}v&wGTquPo$HOoUBU-SjV0rn>7p7q50G*2^tfDg`r0Pd69wS_6W zF$zWxREkORP1+{y^$eyPw6bn5#cZ6`-1byck}j%#2A^yGA8ck^9t_7ydX~-bQD0 zjL#Eui)62{yGEq04})Jk&oc~fbG0w^Y8%w2iOi`a1+f1?2AZ(c30RAMa+zU5^F_Z2Ds}=fpUq=y0>V zUeXV_pT8OlNL0HCMC{QV&M@KDd|f={%wj`M&Adx@;>|cu(lV=k#XOA;7pDGV7v<;X z!Kb_D_Rm!2>bMibJ?@%AHlb{7?JR;thgJZZB2K^A(=bbBjgS8_K-PHwZUo>e-%`xq zSEKtNL+61?jcWXHuqxcH-usNl&8Bg6I*U9GW#}?{SZQ-WU9v;)mI3ZBqtjS?eGtGX zH2!QoB^I|VnYoTbT1b<{ZoW+JS4w@3IV<pyo zK}%4Oc8Y8p|1CE+TTNb`Dc14GYxEav-lz4gL@R(PhcgfRUi+bA)c3t9*hMjF|MG=! zItio5v-ZV+Ow@=FL^n;CAMIR>3DMFgcn&kSaVVSdC$qq?wa=*$ZZ@!+nD%YfF#Gw! z9#X@!lrcCLsGA48v_<@tMGY`EK7wc1T5#`m0+uG*;bjZ@H>-SDgSfZwjAqLsgy{$Q z(tF#=aOibXAV3~#r8;07_#91;A&NKv!|9=|1Pm?v6;(-`aM>W@S0|Ciq^HQp=;qpn zho^%+HzKwBi{Q03`zNj~N6{!C9$tCihD!q<1f8}pcm$7n4)+#M6*1;IB>^U!hW!XV zkgAq;sV>KD;Bnj&6Xegbu^8mfkbxRS)2ELPgc8r=%b8=Jn`zXH54F$NXk)+;0 zT$|g5k&dcsdQAGyd0SMHlr}0dfM6#}PL_%g>t>U!3ODHn{xpwRL_tAEV00aj8B-cd zm=-Isfd}OgPZnQ2q4s-U1T6U!Lf%D$)UAZeJP&&-KhQ4<+RHpl6Zo7Z2809Q)3`DN zMjeni%gMe*ltmCgNSFp^TF4;UX@XG}inKXv_W{Ynioi&F@U$LgfZh z*e4wMbR4Ytym~Ga9~wb6N=w_>@44}GOai-a7#`z&^TJp3#O4fUE~6@s7ILv3vWKaHoAy9~$b(+u>D zt!A??2UBvTv-l^+Q0bwh4#z=UK=I55PxsHXfzI0V?2E_?pSea)wZU+-DwMuN4zv%< z=aOFP>!S`m-Q9h?( zhWBd?)V|;6q>@PBmme)eyD{CB{AoZ?wmYwQ*&M|( zQ&YviqyzhP(>-h#RhstQ2cj*%hQy4k^8x9O0;K%tj{nrrT{?%~q1EvH5zV_e(Z45t?!cq< z(A1%tf!5RA-2q&kDWx^&X);$d<#W=vMrLse!#^H*R1}mKt|faM#XxVyS`0kqrLr{E zQS}jPnqy?%u@$KP>X%yGAzwz?p;a(IIdJkY8QOv1rmah>KOqix%2#beB`NdZU|HYh z#_Oc?d4_c8tS&v1pMNGTF1+;}4O8rcE|jDRphg0T_mlnbAGxF%#Z}KK>gdrd8Nhc! z+5=6eoNiKQQ%*GmB_6G!$0*LCQaJ?LfX^EqWUv7%-qqCfps*%2b?e)=-KikFa<#ds zWJG1!-?Emhc&$EEq+p|(+Z*mVH__we3?D5JH@)cD?-XSdIk4V!;`U0%0z9e$rws=t$~P$If7`Xvw)T?go0FDjx&L}C zgE1}$eD%O81hCw$?-|=BcR1Z~*k^1of=Oy#q9yzh69rWxN6c5-_CN&P_5drq{=G4G z+X3@$S0yAPkX(NVz)o?~*Po?Mx=nS>T=Jc92nMP(5e>wCJ;fX4wdko{t-nv5^G77Q zH>jQX;G`Y;KtgB2Z(mapF4$aHZ_vn5yj{tQ{3U=D1nAD*>S!}OE zSWQ`b1&81%+i?z#xm$z}I;JH2a4O^S3jF$wW0J_^GRSy;k zHfwtTvxOwcj~P-k*wk`K9wwIEF>uT|_#>%Fq7x$GVNmMr5r*G=&}LkmZSA%k;w{<>R3i$0HLjzI}(buQyQc?oGR!Q*C3YlkLUcPP)OAxr3FEH4I;&ZulobVENX|Lc2 zqWBlhQ(U+(Qz2iNq7*yi0p?dr@^IS>d9UA(X4Hs=*t;ra-d=90Eu#LUkXFdSc$7sY z$ifJtavKsd!vixwq6>`rJ)Vm39dDY|?9aDELV(&2JV4UMYo3GRcQ@?Oq9UGap1xRp zA1D|P5CcU@%41&vxH97x<&XH9-kNcc>tx+Va(}EwCJ?sd$_FA}9J+7ivU1-OOLA5M zEq{%CAnh4Ye_?{O@>H#Hb=w)hl}27GD=WEi%qrZC-K`aFy0nZ_R(^Etz#X%_()BHt zGhp22#m<}tIEv^qTrzS3m)<_bSA6TqUwEwO0D1k8_ zA^GgD8(cQ4_CmOQ@4_&Dq=o;89xW2PiE+BpVp7-mhD5mJk4GDa?!#+~rBw(G`1ba? zKDz@d`C!uXAW(}yLlt7{QFJ5xTwec~*XEjL`>h#}GlJvA_mBYGDDO96PpcAPt zQ9m(k|3N{ZB>(!EBv0J3K>*eWHvK}Km4V4pZClY@oq*l4w5DIlrJRYTDk8vCiI2;@ zihy4@s6GNve79C1ZM*rqo^5+EJlL=h#Y1HT9w!u_fhSi%EITory02cwioE5$+si%< zt6r_(jOi`qt^4jJ3kx#D2%Lp8%9wnzTa*u4nv<%!iI8TM=>Ucxp?uDPL4z z`*`=^f&&5P-PmW%*Os>L3RCI_tC00EnaB-9U}4e?aN-Bk8=ssLNZHXKa9%gQ_uEN> ze>yjvqrSnzcXmi@7aV@fa>}a$H#*RHbT#QFj#O?hgL%p}=f_NPPb(jBqv@<(KI3KW z|Irt1<8#?bikS^2lTs0?3@SiMN+z*HBRT)vQhRm}-aiBi z4I8j1^wU)_XOcZrdDxu+4=rG*Eq)ZBS*HK0AD-=Ao(I9%5Idlr=kqC9ej%pt+osta zl@RHoirPS2M8|jYA6sViuFzIn076=7q}04GpqprVo(Rfl00P0ZjZI9DSPcZXx89rQ zg|ADu_In54HMsh2elYR)25}&Ry??Yi-CLnRqk}j=;(ORQYqT3b@vs^IRJv%}7c=48 z*!X^!;@s*hlWL1z?b0JtCV+W`bV%-xaofgx@SGU=7KORaRlck*-c?!SN4rwH&<}$Y zNoBZ*z+|IFuP(T?0|?I>&nBohB&SEQ#MXgG?gtey5(tCp)O)aYe#KK*-5$^PKnVR~(Sm>5qwD zJx37b2>Bb*k}LWaG5gw0`BZkXK|63@;7HVNcM1*XB5bZ=pNHSuvckn0&dF+JaMla#l4&z-Bz<3HVQR3CBFa1R7Xe8F>ol%+o`3Z*j zVjv~|oWDu%5+ryK&_<&bphByjRzwul@EjVu48N-ooF9Af-W6-O(sCRfrFp)v0mXW6 zW5f$UnTrFa)trf{OEPRUJ>>P#b@dJyz-~tp-)|$q{M6YFvKQ`d73s5II%S zLL%Jfem-%5`Ow;5Z2rP*%~S-8mD61(`s!-#kTT1G<`Of@V4|^vXfi9?NKWeT!YY)M zI%!WdwrYo}o1c}nP)I0%`;FUkXgP)<7pu>{$now3)K3OD#ZcEjK)}wm&(%3eh5)J2 zp;EJ9ehd2E?;h;oN9;NCIZT7jRQ_NN=lDdi6?D-^#u!FlVxLs6aCx z^LbHayk0IqT-HgAphcj{c4jZOkV_5&ps*>|!DhU9vD#VOqvx8MALi@x^3C4}%bN*+ zDam(a4ii{5m@;dF{i6^ zzP~p~#5hPv#k1C)cK8(f0S~$n*^HL~xL?chG2ilA(p-`})v7GcPtyxz=B9PNP1+~J zV;6pBci0TVKr=wW+M@ubt{mjkIcx)(A&Kxv1YV@1BBKzXoFw z+MJD=-U9f}C%e`#L%;~+=cc%n(zmn;4fnIM09sY;QqFwl5_rD z=h{Glx~%wV7vTMIMKa6mi7o{CGt`F;bHzhAb-$mDr_}Y6?~w|aC7LV_O6_etHO4!5 z4j3tax6!xWvW=T0nfg=vAc!8Q@VQGe@?FBp{EUTVT$@f)GIR&AIl??Bo~R>mYRAyl z*F}>}hn=(0cjr08kz{(g?4I-A6H5Wm7Gun!jQ!Rg?pD>5*><;t1F2OKK`uettE3{n z+#b1K&y`&e9wiCYfW;qcE6rQqq1Fkda>!!{8wmlG37#aw_uij;zi~}yPDcFZ#4UFEdk6TFF+*99{G_USOKx`ih1q>6%*}!$jwV;>&>5o{GY8F?Z)xK za{!qXr+9h$AXl5Y>;0lp?R!*dlMqaQ8yX&==II7P_y`I)5m>p9fDmpL8cm_^KyiMa z(G9xhOCtbiqg~ZqG!{u^N*e+5q)WVvXV=_1G5>9L4)QyQh2+osnAmkRuL%rf-v%sM z@Qd)KNoZ-gXvF2nX1fQ_A(3n<03aZbJ?a@iwD?`b7+@)ItNclw)#H39274dI^9pF> zztYM;D;4rdB(rmCLlh+~Axt8r2VUE1UO*Rx`fXXg_SNyI3e{H0o*wwkP-mX-(!f$V zEnn?Ya_IL-to9{bR1C$K$UXc=f?>573;C+R>{TpbthtbKe)r41JI7;FuD%?limJ1`NbN*v@VTH1{fSN21L?8w;x zzo&I%RnUO=u1)ep$b@{-?{Ds(9vUbkZz7K|Nt&Y?5>Q(n>%Ii|-%QLoQ;8EyFG_l| z`X@A_=i~84Z#Dz3uVkRFHEdtTGtr|)R6EZ;Y@=R;;}@y<2?-Ec6cX9u=9fB&0wt}|{2chphrick!Y z;CflI56Y2m^aQ2cQJJ61fw|1~w?X=9ltb6A&|rl94M7vPEcgvB8z9f|)l4o*c({P; zwQj?EJvbIeR6JBlQ0>(Uy2s%paPl%tI~D%)ms06)Cr>Rl5$_y0sJrO4A8zjo4LqhJ zZ#t%?+<1hsJ+hXr+#1}jg%#fAME1PqSpTeTlgiJsvyCw8UQmE?{oWd! z7!uCJ9Ck>xX*`Dp54~mnd+xIRAhn9%f(@j5LH(SB_#%h+BMwiIiGk4PJKF!NaQgF%poa;fy<;%_SnvsFJ}<4Zj^$~>Bc_TSu8Xt zeEB#bwGCL2Qd1vRJ)`9SZ`U~w!vA&vD|imAw-^ALLjOO|KAa*npEwhnrwqqC_+6`M zSInPtrvQBd?+}lZ|IGnsGm(;6xN)zDH|B_gZ!%$Yfn6Ut98U8!_xtvWoJ>;*w2%?X z?XF*G9PnM83aa$=JVUe|SMR*H{iM6=9_8krwZFe%t6@=%%MGkD&iL|mdvN&Y*P}Vw zOUdX!_!!7EV$6Y0f1f)*v?*U6D*f9hnMYe%-JfD=m}tD%jn|K6{Hq)q%}1Ow9fVh% zlR|v-sIv`A5DtE6!r@|w+la6X4XQ)o|9ffy?%xtPIMdQr`pQc`iS?>w+IB3h92%BN5sLzeh&3&&t zW?nS@?DZ%5>pBxYF%O)}?mijhz&xhWj9SqTUuUx5C6wnXtlMirg`Wf5$ul2SReN$X z5#>lnM}@`pDJQ6~w3)+iabL8ES1fxw^oz%R7plyy}^(~v9gj8Liw zr>(YBf2l+|4++&RL|0gKcKn$;&R;gZ!22jj|GT&U(aE%~bTPjqZuAgw6dA3Do|AvG z91^GTi=dvteqrYW@aJWVWO)(T#sI2+M*2KfscKZXUDv-y*xZf*FckNqn_K$ zwEf+6sD)AeOKvLx=OGD~sKKs;)n-2m?#8Y*1O#Pu%`420?0@_^KYu}_cpMVp5X|#u z%|E)W@Hq@MPGkdwJ79sg4uAm<6OAHBVaecRO06cz``OhPk1XVkVjgX1Q)0RUj=$bn zjVHCciwh3&nW@6A91e+00s|SaTcAepnC5%-tS3KaZ2nY*8gl=ZsJxAVov-p&0lY3C zLOp#m3?bytm5ZWqsqa*HcDH!MSyM{JUkj(!@@xKX3m@A{K}d&Qm>-=4evZ=DeyiGb z;mAN(Q~zajMWcIVp{&`XWRLMY7ktLB~@i*3}oPq86QzZ zAsXOFu-A6Tj4~S6O6)AuRDaF$@A{|xQlNn%8na&5uGz)jgac?fp*C1;lF)Y-bV-Ys1d`WLGx|&&jMf-v7N+So%%5%AUkPlhTgmkzo4~5 zBd^Dc(89p&7!EDR(zXYuaOFC&JH4oxZfHSlwN#c3dFGG8<3#N3yF{-IjE(oUPp;D) z%gdnC3z{Iol=VIjD?qF{Uu!nL%v>gPu&eqq1pUo=xrHBmLOqi$P5@f|r(Hv+qXxLZ z28d``Q{Yy`I|zq+wgdxJ6uMO#HGwUDBYO|Kza~Ujd(j-^)7Ll`Y8~!uIa^ix_j7}8 zpk}H!Ww-?PMj=SOZ5=|j)-xK0dS1Q?P>@v3ZQ5B5L~cnPTjZyQ^YOD5iUQl0K9~O z|Cj;;r0h&MUP^1SNiy+qs<|9(6?jaqpKEglbYi_BjwX1TzJaniU$atptKnRq;3e|a zi+V=wCZ|8%qp3x46aERtaf;mrj7fFo;RSnJ%^CzE2So6nZKCgcIQ977YhX?ECyH1x zK+@j4y`#H7x12X&xGx37Z;>Lwc05bMvLdh{G52u-@d5p;QQ|dCxq93nL)S4z?erB|D@6Z-4jF=Xq=07ozROW!pUNpPn>Fo zvJ>3|mt|Ej_%;^Fs{@r27L2Ueps3PQ-YsGVIK}AbS}Jf!VHsXcE-rH4OR+c(_A>*L z>&hic+1bWyJCOcxY$NH4H{l#Ozi`b5|LI*nLSjHc0grzw3J6@Eoty)U?=opOTbdC( z*|pLQ%R;UX?!QV512$$9it@qb!ufEMvYlv;8KiS9z)ANLPv76Va+ zQ?tPA!8t+6*TH{`$Ydu;3wdPUTsq`W$<;A2Oy7UxKh!Nbbr)u!y)oR9dPO9S5HVcBiIKeZ?j{8dJe@G$yU`x6CqUsZ(&27LB zR7I!}2#_u$bKu-bt=|1}t*PN-F;f$ggUL!RWG|$^^nhGqXTAk}T(i!xEprFReO}5Yj^>bt>$4juIL4wOQJ zQIs!!nbHM|uA-B~{7D-dL2-o!^SWifQ<^M&Evz#C?ym78IX^M+tS^6Yy2WyiVgPgd zo`*1yX3JiHYJnF-E0n*q9$t25t#J>ScKvPRB+%ha5OK-LvuMgl33}*f1h9QTGa@Fv zTr}lPJI8G=EYL2;r!X&n2y4kn8&20`b!qTE0q_=gY1=r6tt3?<;nkj z_3lFUD^${58mzvE_SVddnNjhSw0~+Km6y_pLcs2FC}IG}V*BR=mLUeFu59-QgnWI| zj0`=aRWV*k#9m&B3;5hxx0;xky1Cs$F>+Iln3ZXsJBmK1R~(NNvANIA**`$GT-+Vr zf@tm?pd{o57z;kw!!LU-bYlB_q9|T7z+B;v@wPC!=DMMF*_nYmMyaHJshiGFI#R2p zFWRk+fn7w0hu5d!h=J(ew+8UgKr#SO`QNOiiN0VPIIkgmIcp*AH~jXAqx3$Iv=5R0 zpx8t^5BGQZd&xo3{VQ2;udQTO{E%ED~z#wWy>&JQWfjJaqiuOgr9d9tt_ z=VR*b9dd?zCkjzE`vw; z25%t$X_%ZPyd6LuQ%V3d1vH4;-YKk3s7mSQt254s!dZKO?c3<^!#7jR;MKEcuMV9{#lSIZ430;XuZe6!$If$wTBJ<++* z+%{sWYU?A<38ES-q%$lyu77UpDKmBr07x5Z1g9W%QtrJiM$>GXdUh|#-z5VS1r&xG zI5d;$#p`crZGCFOb*|#ToSwkKxP5wnX`LHG;F5b5Gfja}b{*2Kzzgutcuh$OS>Q)T7L}Lxp65^|SpH=^>p7O*8=~jifaJ597fXx$XKO1R^_;^C z+f%?Tuaj@+~CrF!GnY`D4f!8@o0YdMG9;o9=^#-q8PWd2Qhl}-1 zJD$p$iq2=#5r}>Czc;U>_k39Hq;AhzTyFJ$$qr=x{g@z#ym&aLbFfX;q_C&TR3n1* zPCT@T;e@wyQsK}JHyY`Pj{IkB=?2%Obeb}ize`gK^bC_zc?T3n!x)d4kL`3@84-q#5OMFqnHcE%N^37EFO$rC$U}Zw>2y@ z0wO6DfY`QX9FOHkJHIT2xNdZDUut;X8E4^R`0AyJLXF7;8ZUhMLE)zZ0`|Uc{kOt@ zJP=3~bj;vgTiH{^)-ofV-vtTu57wYM1WSV8nIKZ&i*HB6dRL1mB%=RpG~jCxWmvxh zgV5*HM76XSXf0qDQeJ(6e7%|fI)=(LDD9SC06YxG z-`8moDIuW5X`+z6wJwBWcY5-fSGnWhXZf-jI&s34Uw&|<8 z2cUsJ#3x9*Hi$}?L9Dd;d!uOI0KY0T+n+*8`i?H@F&Lm*Utd(NnS_SN|26COi(!IT zy|{{#$6&P!_!KnN#m{n?e_R#$bS?6uNHw0vxd4@Z70x~*x z7bE=cZ_BV@1vC;?sE$>=$+72*sj@z(pM+;`0w>G~JhoN-@L>o1kPRjKLTeU*1w!a=Q5$?aV6N{8kQE}FtcIgxT7Zc^s zpcL5T3|dLZVy#@*eTVY#81wZXNVM*0ZNp{ec}B{G#zievr2#nvazhlag*$)3Zw9o%{-N z+N!4Y855C5yZPjf-_4G=m`d0X*!OMjekej<8b4&a^61%%LdH{sa&RE?<+a@%i(Mm9q;MT zOVrg*aKbkmC&`NaCEnl4gWhW(_zV zTwCAGEGz_5WB}sDqmIwmtSH+e-yXUa0OVEz;1}w{6d^MB(DCYL z>oa(Q$k-)bi;0&!KHzO_#v)>IcNKuHCoH_gK|_;Cw?ZaMCYAyj%sLSxC0bVn5ivus zyV3J*axb=>xq>U*3NWJo4n7`F{en&XbVT;!xD1|ueBYMoh1zDi2kvHHXfB0SRo-T) z>RE|rQP>RY+haYx4omiv?Grxl6LKf~l#C^U21e?#fCag-Og=i!y>H zYJyZ3U6n#tGcNExU|dJt$IbkctX>^`*s~WX@_pY?$W3#&kXaXw|Shj2-a2s$d35;Eiu4v2)nl}@s5j|v$z;4{c6y>yKiK@ zDimD7g0Mdf_zA554nN*DOV=z?e9ho3KsZb*+yDCHHYBUw2Vi4$`f5#TqOuy;T+A~w zzNYsvSx!kXE(rspZl*Q;0CMK6(~;89KnVfW>1YSZos~qZ_Y>4b?iZWelfFF~YI^1F zRsp?y5!Nr`uP9YRS{zWK z@B}?yh2h5VJRV7j=;r*q#mD{XN6W@|QH{by6JV-9i;b(1AROM(sui#)9Yl=xN(%5RV@Qvd8ozI-A`lezo%Fh)>YZ@k- z)JJS*WCiALi-?yF!UK&Iwv6^?4uDv)dG|$Elhwy~J|+!IbI~+0sdS7%CelRZ&2OSJ z=?QW^NP!b)T=u2|-Q+M#>B`|leiTte9OH*pFbQmuKAQfzQJ%L^RAzK(9h`Aah@#Su= zy91!6Q!_%{C{%=hS_LozO*%zts_hk1mxzh?T$@i>$(O9RW~;EStdz4o%9WQNrIxJT zRE}Tq6r6bn%_CB{RqroXGk&#%JvqS?Z@RCz7KhaG?>1DH1NmsZ*_Tq6L3ij`MrB4N zKzGarTV-HH*BR5r<4cN|w~54C&&}mEZ8&WaV0q5fOd=;@eE-5_zx4~nT!Skwp6OB~ z1clIq6{Y>n>DOLg*JEcTEUi7=lZ{vU&&9b@t=0Ciu?u8K)$GI);ehk#xgm6TKnq!i zil?4gYs%jOMhNW|TIpzi&mq8%rZr`af;JDRUHFkzGcx9Re5{Ee3%^Z%4oA2YlkIVp zyq_u@CcWO4$gpbF+G(vz31O$*wuyhX!zKr z+B~u`Br11T9GY3*o^xE^D|?81&Z4R(K>uV{p=&sw}27SeZ$l0kiUbeKVErZ`m_+5O=y4QC^!I^>!6sU^F7Xf z@l$2r4VqRhd6OC-5#bJltlazXmHSbk671k$>UKY;kvy!?#L@`g=e69Eu$C`h&e~f@ zy@3xc=g0_SG5dq=5D?rJNXd0zZh^_|^>b$^1ujB9mOT8rnJYfv#mKL{*+k%~iUCeK z2d^F8)wdnD`hwaT(jS-KGkl~-B_hf3RPSPUo>0NaeG}l!2B4kd_xC#1Ra{ zg;55UiF_8jq28-MMG{72n@gI6alrd zhGti_Ywrzl#gX@6{A9ZC*+*bMlm)m(*EcLjP0&6Nu?-zIDS<73QH{|40|w-N3QVT& z(tj7W^+AB(Z+P0X2&lZ&c-+`%qyj^%Y{;%#ouYsqE1mz%azSGcOIk!z_DA|9SI=pW z8*Af7H|^)m2%K16gk5yrI@JqalcZ$yCxxU|qkQ}m(ln!fZTWs)wiqaJvaa{r<7?rx z8tpl7{AAC*yto#om~CKyJPihJ#VhP+M!zHxa<{zHU-Uk4k;vwpZF+a!{DuZ@>Gp6|FVZHY=7~y}9lTMTF`W721P_o=YUw+!FvX-S8^tV{xx8&&TJr+7MA3{c%6IR#p$-L zHLiKHwtxQls|roU$y5cH<^YPUMD*;=#yvU+cHdE!B7}`i=D;VXEtul4R#sG`cQ)ho zWPP>zPYh%(arr$noF||X!jVXX|K_)F2?*O3VH9vtfF0@YBk>HcoNvN38gS)*wr2r8 zK0*+23|S?gV{Jg^_bZuw)=CDpjJ*Q2db2%7x~wlN2*ih|FeIL-P-j!2bFcJr5lk@? zd858M0XWvdZUizqO`&eT%(Ie$9;`C?%ddH73_00#R0{0g~ z`7x9)Ah=XA1s#GwF}%3QyD!?h_0;8|_%%oA8IjVt6s7}r7v^n~|hT>iR zP&e0J*?xw{y7%G_X|jlBz*fDjwsW~H{;M5AMJkl8f5`1Wi(< zCJ?;<;sqc411V~5E}taz_eI)HUk{S!b8_syKuL_pQ~?z#A_T8SP>5Ovb_%!DTJ(xL zJ1W1w0k*8co644|sV@NEZ%5?t1F z>T5k&HqNzOh);K+Wo8s89XGTO;v9n929Kl$RrmkGGYzH756i?N%7E1y&?}$V3KW1OY6BDNj~L z9fUQe4_UcTf*VwlT~hEWdo@Aews!)Ae}NAwR0&aial!w!<+Ml4?I?n$$D){9TQA{j zcAj&(eo`CXB|PU#D7I^>(@gagvDvpZQpci%(_llefGcm_5W_h=8<93#eGx2t*7o@* z9iATH*Flk(RIc>hS)#b~En+)hKm7w3(ybP?J(Uvrt^fm3TwSP6|Lwuc$)!%o>pk-t zna3Ldy()ArAtb9g(>=p{l)uc^LP&=cy`HOTKIdDbXYLsduTeo0;7iZXuZS!^Clv(u zjQ&6o_wleE{{UyR$Nqz$*v4%Sgf51r^Yfmv4!x%ZH={++3|@&9O8n~HV!fL*s2VW1 zt#gWl|MxKbUHklVHh>>VB(n4JuDWBlOxlA(l8M2?#f3qo{nR_^N9*DT?ROzsVs$-m z3OoLYAlctW+whO`a0`SSDE`Hb{_}~SG2VyJP(@{BDMWyt?P-!IZqJPfbNwYQfdDhk zd`&TH0ebc7BR@H#aaNtfKdbQv@y>rdT>ox=LsAga#f^v{>o4Gbg;HBROx|bPNt9ME zcntr?U;Oi<9}W%9GhOIt;;lm-101J0G8i@86(jbaCg)$4#J^7fn*VR?Ri0a_Rss0C zfeeC{BqAL1Ox~Te|NXB3P52*CC^q@S8B_^+hg(s{W5mv}z;-Vx$jVN~ao$x%=-ce* z<5NIE*g0*A_9qR3O2k_={eO8`C>Zo-T56L6ad;bFr2rc}P4RQPf^bXVyI=HZFkRIe zpc+uSSn~cMwiG_2|LwZ)pV#j1mEa1L(A3maR#u);fCh7!Ff-ur{?;=npb1*u2yy+r zIsA|F5XkKZJ_KQ{NOu(eC71uVlk#7`3yDVj>%yMjE#&m8ShsSbYknGdUr+@A)(XZ& z#P^GQ`?L9PWBKo;{_`Z;0^icIpi8aA=QbH>u2KzgV1evUmS!5?8xw+md+q=6WJ%(0 zO1rrfnji%h^E%GfUpCvAMeD`C+m`?FZ?Y)>feA?1kEH)IR`H+H^7qiSJcKw;PEg4b zCqQnOyE7D_IH0a*>JZBE5ken(o2qLm7;&=Fg_ zAAlzUs5cU;l%EsrW&VuutnlP?ixv2I2T5>YJZ)Gyo3gf;7}3Vfxg?D7$b*>8lou|r zFB&-izTWTGl7#$u@xL!DHb?XJH?LPJ;Gb)4gcN@Le|)2X&q*gjLSO$$Bn_L3G6~lI z|D*o%X_CkT*T;cv8vp;}ZV=nmf<9Cekg83rp2yrKkvmPC$x5PywZcbw$NO z0Az@{}bUruGxuwtk=&u~NPuWzs$3ZZ3 z_)9TutuSDzngcvCt@n(#t-)p?OWukeo@)kMPvuMGDv0N7eM^ZW>`Q3tnO)W41x$!O zrvGoL5>*2FPG_Mbq4vk1Lk4zKs!N#lmGF4D@ex{AE)}f;ScX_S}QQ z0XUq=c4n8JD==JKC1^suW3=bTi&tyVJ0VRMxoO|LsU+Ew#RKv z5)h%|gnVD}di+O>TKD>_pHEyYIy!kKf{liD+-1ul))zY4IbJP6oUjKOhwU$+o9IFE zS_OM0YOZrL*7I!VozM97sRh0a8)GKYsu?l0UTBaau}|jdfwf+PL(}13kwri?06PXp zocsV8!aViCrf0S9MFyq=6AyXv;dwLQ52!Olx3yGPtxH_*5dnV~f2nb&f4Re`GkxI} zfirz~|IJReQafegmS*wIblgkQm1sav+0bj%0kG%+fkc7Ze{InGC54-+ddq@$Sb=9e znsx`>Te+Htu{}8SW`s+h(JW@)h=rm~Y!H92FPeBoP(EuLNXR|vKDyuvIj*iW1>U-bh5Q>p0b+)A_CmWd5)q2#{^MTpWpE@u*t^-rLqKGumIBA+0qd589U7L5g zRBz*&*2!FhT+3%ZjpPbqWP1uXkHr}fNxIe9O@!oCKiVBJB_?Z#ojJL58d-M!Xy!-I zgijMye5r1f=%3YqjHLp7{tx zLr%GVOFl+I(rf1w%PMkkFsq^_W{>BnQENBb->wwvbC^_21jklSfvTKQO__phjYHY1 zBfvNl8-pzOhm{ovlo@~JG68`K7UQcqSC64U1232_vR~}j3#q1gUc!22*qV?tAceE4 zeyPP_JuE#f7PEF@(#DSp+Mm5S1B2FLRyv~YZdMjF**)CQ=v#V`9FJb@`=vXwg`n*$ zx!Hkv!lJD*V3EWU+?n%Y=3dksY0RV6BFE)*a~BnU8@vaTh(f3+(R38wbCt}(A&Auz z7zF&LbIlDQGfjM6d!!S;fdl6@>^W}M^<PCMm*zQg7Ws}jI9qm;r^Hm2;Qey|Us zPt&pY&dOGC7jYIz-bQ;@PSjKRn5D~Uw&sKi;WL9NN1ILNz+!d3 z5Si^0rszuPoG!5b%NKXO3t2wxR!hVfZ}x4~EDEN`ce%~xlM+_D2Jx%jnIg$qW8@=j zEpSbe{y7LerNW{W{`(c0?=5%nAaqY#BtO3Ti;5ubkMZNJ03;;0sTlb^DkylFLx+5_ zl(Y3vj2DNUng>cYaU|X(XZ*l`e}_DRW*MK2$VYi~4CMXfn-)dK$%9-g@m1Hk$Yt;G z(7V{VeCQqD(-R+v&t(f3d+p_Jn9C4)!7d6;N_d+m^X@10*M1YS_vd38RqHnC*XiMM zQ;T3R%*SI7EA z6&hLMY5Z4SyOktF;wB0-o4cD2i9{f`5akb-;;V| z1>?TGocNM7Ruwy^8%xd)IH}+9%;EAe4AtYEF+ysDWrR6G9=9AS%aD3MUHwL2Vc#+P zZS?ODG1x@-^1Y3bkFZ}m-4p9F4_AObV$E{&dM_YS^a31{T4KP*Z1zE@dTlt@ldLf5-7|HKQ((Vx+@k%H?j?wd&x>9!nStf`_wZ}PqF$4Woqc<5YO?VIO6G6MA8I?_V479_ z*%o+o_^_eALz}ToIj2xAdxE_-xwIe7C&feSli48T*6lx&`ZT_GN!QCvlh$SU&4DnQ z`%iPm&K8`9sRejH>Z9yXq!0AuIG1Tqe8G^lq0i2#Gx#qZC7XGKHQowdRJQnEF zFyNL6T^=MP=sP|W9Y-W3Cqvg3E*_Dj zdi7hMPC4vq38&o>N%JV?_+P8foZodZTE2(uVHXg(;P;_qBwA1Il205y{E;@-rLo~v zr!!1i6l3Yp>n?L>F68MEuenF7As5Sd;vffNPQ?gZkPZ0m0vRVR^qI{au zcbZBcac1yy!$s^~yA^nuYX&yqpB&a2do~8FhqWU!$`FsOoA`*3FB)?91VJ4>Tw&1C z+#Hag&4VLLo;yu#o_cMU!$krDC;;G@?V{l9H6`J zv-qL<>Qt)L4y5^1*Y4jQSIR>N`xu>_gPnufC_3;RvTCKNr>ZHmDZZzQZ#86N&)VCy zZiXA$-L=WC6z}E6$px~GBB4gek&UJf3-4O(WEOy`)fFjPH&M9Sm{7__;IoQ^&U qDwoag#t#U+h8sXO@3JbD*$u7s_(nR<4wD_g&)m%7WYLMMA^!$5t)&(K literal 0 HcmV?d00001 diff --git a/docs/images/px4_nice.png b/docs/images/px4_nice.png new file mode 100644 index 0000000000000000000000000000000000000000..91a1bae612457f01dfc3c2e4e1ff56c61c4e568c GIT binary patch literal 110696 zcmaI;1z40@_XiB4D4@XrF9}}4!NH+ONs21M!97ofgM)WKdJ2>X7Ax!l zKTjMKC4}M1M&9fI56?`6WQ5@0DkG8a^q&LIFTO~sJHWxAc0T@l(rf#}2oCPyyOgNV zXIGv5mKUDbVvUza4`<*@(ALsrx(D#Jl#DxLCyprbo=05{2LnS`7zaZVNwcrxgS4pg zJKu)4q#ttqa@RYysr-D9b0gNMg1E_iLuiH4kb)Xe@#FCE+wU?DcgvIt8k=M@N4O{{ zk3INxg)<9^n=+NAv=`5Ll&7|!F(p4$%W(`LwzZA1S+y~9`ILs}F6Qrdujh2ST)NRPT$7ADua9YX{1G$&bG%j`CX%3hs} zveGxQ!aAha=&yF-w{$(PuLWB7eM9NF9&$qIuTI2pwLDL*1t`4j+q)5N!b!{s-E`3^DYB_*_;GlcA&lCPMc&SMTdJaJ_10HrgI9h#KBA!Dxtyqie3J63$;VGV;D-7i(csVQd44h|Eu znocIQY=hOc*d^a%;fnhf)Aooe9mpUCT-56k4<_Zsuyf>T;O>Ky7yk~1g~ z&JBAeXC|KB6XnubBA@3RI-6!a|DgmOlsb zvxgCK*mSstpLB8FAI z6HugZu1wB~5Q(S6mZQHN#3Zu2TWleridIab#nI^L>UAA-GZ1Zv5NYv-JKt?KDPP}^ zz*3y!6_E_csfTrnogK|O4@|%oE+axnP)tBjOh^#O&I*}-YnW2BeYD+Eq!6y0n;I~^ zw+%~ipKsRRPC}Tku-m_q!lcl4nldthf@#VcL+T*Otaca&f_^wDKXF~ zxlMRy8czu=9-$^wlAlS_oZ;1THGHU2cZf(_uBIeOx4^i_O3Px*5DX@b?jQ|`@l^s6ln%L@nDC* zNnGWrM3so4L)DA~?UX28J2Ca{QHQ~`vw^jn>33*lqlB!qlwNxF7E;S;DK#OGx!<{7 z*tyjM;suGQ(t}02nx9j()M6Ds$Hu6-iCMt9Rp05j_W#C(-3=hGE71=Srm3))v{eK= z5fR@?K)qCs?0*B%Vr>2il2HO@%Up{POwjBq4fNzCgiFzv%N4zeWolrmZ+vUq_k$)d ztTD%Z^0%Kw>>0wPEKyRNZmI?|bD@!uhPn2x&nb=9J;U(!Wpyi;fXtzb)an?&ac4PI zVN0{C+G*QsyKX0Hc=7ziu#q>MAH2r4C&yn?!|#rVNPI^nNN3GrZv|Ov%^gcScqMlI zF8GZmS4y0&#mCy(uu%p3o_J2v$VyZ1;;wSkiZ3v@b9wd^o`C^>mIu5nrxeQ&EZxGK z9+Bj&uBdUuFBPn6@;(pR#QXL-X7EPqw3>$DAUzFz1|&EV74}5gt2huBg=7(IV+4!J ze*W|R_MMSVMpAOrECXdVGbAzdv-}*`-c`(6WGCn*Wp_U0i3m+-Kv*7HZt4$>A0!K` z?pEvD`2h-s1mbM0(;U$SKkfF_a-<}5ZEVbJ2t*Q-oU_?1qfD(>tTp8pBEIj6`C)9c zT80tvh)WA1*TlC5*GhZrPk@i%eW#1@a+vh3 z$sI3cv5U&hD8>Z6)S-uzmi-Y;EW<&pr<;~WW>-m9&97E-E~&yfuGZ}L~?UFSwY_H)=?-Wk``Lut}gEDXb+THf*P#Kg4VlcpZ|%D5vjwR?VikCWZI>+w~an0LSw8&mPzG-YvjIk_5U(^5+sAtz?j6Qt&R;9r!Jlw><0wX2x#qfjwKSR*}{5!7ua8cv)me zDHfS+LCetOP@}Jz+{<7-mX&G~MGOXtBVYbVkDd!X1?HE6p@NLXy#`NCEOxrB;)k^u z-XYaV&4gW)9dSyQrS$(nJC1%XLRO^_Q+JW%?8U*t!?kX!1Sov8agKXY6J2bbL+*ZO z!4|xDdC@*JqzgV-TM9gKbJ}w_ir&hF&-^uc(=k+>@g>^~Z&AjLd4 z`TK)Wuo1=Ck-X-X9NBmMrM52G;RZVm31q|E6^b|QjKva+&Sp1&aj*X1o?4K2DZOF8L5T9} z+JnXfh!dAziE6pd2eI{fsq@qjO1^}p25V@EsXYOQ$&~GY?fe9W=u{dF1AUuM~BEO-}^`=i+GQXwvhP0!F07T}?E6N&99k*=`;~PL!k{>a
|sXH1!6X_by!pVP}WIaR&EqbI53p;1Vv3FTjq^EYx=#6lYTIvB|ISsE3y@;Wm68?6G9F4 zw=5VzJ3~hEsLyj3lM7k<*OJ>%N`uo;Df23lUf1gRQhw1qYg@yR%Q;73%9#*A4xG?3 zP&=jY#$0z%%NOfR3Y4%6;ubd8^W7i%T*UY<-3Z8`3Ya5mRY?ZQ8&)1k66sLx0#y->~v6kKiAj%+B-2b-qx;GezKr^=Om#`5b(2~*P+ zXJShbdA6?#vo+nOhPz^M)N^`$m->~PZ*ns2m%zr##mY@?x=4?Jqh*T9gVjkBQM#n5 z&ak_$IIdKI!>$eNCUgF8cq1v^H^7kNGSYJ`$RJMOv5X31_(_n|-%=YiC;%Jegnb zPMhD2<@%<8oW^-`*`FcUqf&E|pAK=jR)aB)`i^nBW$s`=3w`DfD^H7o!xPfu%yZu{ zy|d&f)>)v)%0F#=*+epwcCz0?>0I}4Jr*9Si?`gIam`0Xuz^9iFfNfQ-jv~=S{W1b zoST&ebAI?$QEFZMHf{&7-zLSnYC8h#4fF+U!r5Pg*^{RXnYhdB-kcS4Tah71=Gz)A z`UeivDKYyhLNr$a#UYax&w|SW?m6d<{moT*}8QVUtlxV6C;(-e`1zJ%P4(}Rs zR(T_P2Bt=dr%PMz$I@MF+GmlQt*^lKY9ITMv)h?9VD^iiPC7|0zM>(fkCswyggx+>;96 zC-_5E{o36#g#M2^J^TN4r!DUPx6#D^zeefE|Hrwbu^1AE^Lt?cIre`(?l0w8|NA%G z*x49%IDbw~G!<Zt|g2ObleLRA=A-=iU{SVB*DEZ|_#)*zG9Jo3DICJvDS7bI^J}&sGG9fO$u= zM~2&;d>~W$AZ|HRHj2+SMxr{~dg7?f^6f=Ra6U^bh<_9N5j}!~(S(-DpGu@7x_ua)1oU5URnJG3`6H4|cmvN3C3^<2g3yY%yESH{YD= z(qVfUfqTYt!h1~+7+Wdq&=!%Hkf7q_Y|QKxwB5F5|89^l)WEY%R!dxE2#xxb&vS*u z{r%Y@hsV)Oj6&swP0t>s&iK^rh23HN`!Ct&naSdS!}K{vB=LLxq`0Ci`TGwE%Y zBVoVOp1`C=bR*YLP715us>5yT)onfKppFTvG3VqGjkp*y9l6fQ(HZvp9A7;)^XB-d zAeX`79U2H`hTcwAd0pt|$nJeP{I$16i77vbp@>MpoYydoNwhdslGfE#U{4J@#mmLu zvgnZOZFR=YaaS~lin>vWny{)p%5B|x-&e0dbz3sJW#>ie_kV9@(r1c@)4xaWl#%Sk zQ*gQbg2Hn2YbI#(huhTOQbr(rJu~aVm22`iPy%Ok5}5Z_>)ht>Y(d7bQJRR!ylm&C zP$CXhSTWW-V~KyA;N!A!%RM+<-go-fs+L;vcsHIkfl02{opxZQIbn*BtlyKBd;C}2 z13BWSTHHH7N?ng%OmSt-LVM+Y5V_rKBcq%a9eyo~P-Zx~-M3_?=&>!3BYtpvNYItr zMKu?(@(4640DD?z7~4Wf_X<1R;g*RlJrt*^sc+sz+;=YBk1jJ&GgMwDca}s3SS@>< zUnrW>{3S>@;k+ZCY&SX=ghZAi3ikw-AS5b+6ZrCF_eq%4&)fN}7fysV`Y%AYD zGMHYNGvJ4*9h-xTqaS8n81vHl{A=JC&}F?Jq2~DTuiS0$5}4wKTt?KFnn1MO`smHW zA=H#X?uaHo_|1#XhpQLHQ-D4xA@kXF%Mp#A9*=_eE|$+QtGD>~GCQHresKELY2Q~g z)Hj@Wb9P?OB5jt57am00ko|Ielp&m6Ykd)Hq30RoCt{t6HnZo!cFrkmuNLwauu&FU z56nC|#^jm^L5amm1w$AIyyxLu;-Tu7PHKPKdsD2Psr4y)@$tT&b~ldM89O04(RE*V zYVky>5BKb%lIo#sr3LLfvAz86Tk!?#{Iw^w+9Z3iEZ(zXq z+4U|vd>p_ZUu_atkjl)qKLoURx!gcqaHh!Z@wBa=J^F&T)3zloi^JBov2je6j&2_( zXy=z*_Z!Cr-%`+5TWofMxci_H6S_yBp=CMBQ^}B?9fqZb@1A$N_53D8Qmyy9v5R~8 z@w?S6k~oAR0X7A4Z?2W6`Cz|R zEwD&sgZiIc+K>kgL71DPeEZ#14OWXrvk|rt@a^QM@wiI%IJQ`4CC!z~^4)m@C{EbN z=?E|6>dA~i)6rS^5DB?lCNHetV{wU6OOf?PcJVa%yME6>6J`@=Dm^@>q1i3<&Wp`J zbc8hR)=UyXtTUmDR|M_qqPji~v#AHIab2!4%IRiL8%ff5|+aB}QB~RgI-o&a!7cCZ(xja9VuhXF z&@zQL=x<1-T+HJ-ay`q8@oBMNgJu^r8i(MAH{9tSK)f4WR8#DJ#%6Gd;?}d%jF1k_ z2a)Pv6-2f&M)P}n97{cD71_a0dmcxEk6_9W783lzSD|cTe(D@@W%^wvj&(6g1Anc zSZ+5|&q{gGH~9%Zjf~Au%!d%jv(nB|6V!#H@a@~EvaX#bAVLox4$FBGoz`tf5Nswx zsAveh#t-M6d{4JhTP_PvDa#&?_{W}w%jsrNm51QmH2=if&YbCQVVT{NEn(nh(!s-G zYatbca2_LRGoNM`#>+Z|ib({?h>6tO@?7x#qO!(*zQ!E*>vTF%0}d6NbWbzyxob&F zDuwUkVF?@@UqFfeL{gdp;Ks#f%B9iJ*={JXQCCUUt3wo1ai#6WwT7ouQFq6c>^QN* zk6^Hq&>7?N;K2b&xuC(mag&IepvN_B18VQS*;SX*zHD%|xQuG$9x>d6-o3m_q;Lt* zbH1Ax%_%a&`zW-v!=U5hiTp{cow+6Pp-_ad$@*A!S+i#EstIfZR)A7&(s@m#Sy!Jy zgCliXsrA^$Hs);2K1jytguKo&Kdk9F>LeAVLx_^%op zF3WFRKU=|3YTtjbcD@N!%|{-Qd@Ub7JDPh^4<9+z4dW#+dUOY?(>5s|JLPF!@i=W$ z4?@fA?p1dRthQVz(ZJ~BN2X8yT3MyE?3pmVX$5ZW=CC(uts?Qyv=y3Krgxrt zUaI-yNTwv=69?rjt{d+x!}qik!MC^3!-Vh@DSJ3#Dr3(w+xZ-MJR*q z5mH~WdfXJnRWTV<#Wkef0R8KEM)J?o%n8*~3w85yAOE!NqSQ*I^+ zX3ylWv5R7Vvw~b&h^cxv`4&XJ-2^6bwffQQHW{oS*7<-#Q6 zhRHHW*c+M2$V$MXrBR$RK^d{HR;`w~Lf&e2HICABg_H~ziY+FBd|8RNeTtr_&2O@{ zJx*ID>zu)Vop@o*ux(qtbU7E?#(Vc@4SGA8!GEos)I9h=xq@oT*lBFUV^75-4l<}tX>D1PT-~S zU)O`ZPXS5y650!XTvvJm4u5cZKuA^ipx`eP`&w^Ny%kki=1b@kv0RV*Atdp&hC~6D zr*ZqxnF9vi2K|{{N?ED(u)jrEL2h{ESezEk8)}yMWSj5@5F^~rxL1&~$SqVczLk4hg=8<}v_@fJNZZ*~gJiDta}7O5`F6;2O{&$Yc+ zTGj?{_k1BiNz4m_otJ@;3f6bPhi(n2CYobGG-`Exq-i!@GPVZoowwGvde15WAFeUQ z=k|k!V3Er>0AoPTJOyi_=K8Z*O5WX_4H4|>D@$bY+Pwt6yN8F7K z=CP^gVpu*m=9uNt{j$0AX!r=ZI_xUbRlC5X#vsh(qeUg)IA{X5w$Lt~;wah_MA+=s zU7BH3{xE|E4-!2@O)pI^F?}dyhEPm$+8qbm+$gB3(!fsU%5XE?Epjm#4q;0O9OgE(O#%-3zhLucyNDgJ(?jznvQeBW`T#X}M z;47hsnHpgI#q2Ku=!sEjIxO8%BV(H*cw7vvdKERwcn}~#U&0EXrEnW5*5$k}x&=(u zo&H4N*Ib2XN-Z`lYtZz@-z;0YxlL!KWGC=Aw4aAHlgFWJtM}l84BfoIQuF$UVf8w2 z%fqp}`9c!eh|3hW{&e_+u2s5?6ucl_5J|)FW$Gb^3F^52r85}T@R#Tn4{?nsj_;S8jzsC zxijv|kQsh7v=*28TmRbB<;?66JQVh_HV3N_ByV@PwUhsVB200ETZJjP$O~=6*P;rm z(z3xn&P~N~%RYUIcb*c<`WKY|QVoQug#mm!DRZxzcRlCj!Gr{)rqB@*cQJ#;n%FY< zKQN2zXf5V(*%3y}t^%#(6p!!aS0R(l6)wXoQ0_~uKi~|c@VvFgR+-RS_QfbpS5GaC zh#K~n+g^`|&)>uY-=wS8oK>!av z8HiXY|1^j4GVcB-LIcY9{=X2FOo`lQekBfk+4z&lm{*QmL z9zGV~zh@(Re)BKw{|Cv5)M;@~pD6x0Gw&q#FTexEg7Op4rR2PoBKmuX$M4GELbFNX zKd_$2_Rp*Ufb~xc!N@0nlKH=Yj!(`XjOYbs%LG8Jf4cI8W_hvV*z9f3PJiHPscdbj zuJ%gbcvgmgy8RXGl5#O~5Q-7NYoE2gf|+}3h75Yx(+tgnQqYxqUjtR|3!YlrF2DK3 zsB!Vnkd-2FSm90wlSsC%FdDoYfln_}H6`>VYr>i{KH)@ed-uP-mZbM%&*<*HtxqWr5&L2dx6 zTSj)2_f#Nb8?WfqN-RwWbChD)v&=-FdPxT9-|*t%h~w=}1+O#9BP1SRT&21J6K`Poq}llES?{>9G~%WefqPyByG z+;K4$*kcI{A zxR1NV7BREQm7Tc3x{9o}jFPd}H+M5lBMwI=7|o_wC;DUQ(m3oSDdb|=lYYt+G}qUJ zoNR89dBy4prSNERR=0u|QUA+II1WH=H5a_eb4&S=CBt&1c3#<8-T@GIH2=F2d;!-S zYI?>zA{99(2dtLJLPO$ff_=qBvbAtuFCCt8IS5*CDN=?Xr=dwd#y)}b^wNYl4v_(o znsk5IAJNd@CF}ECija1-2pg`luf~DSdCFm#`Nar7$@48wh2~f6CL9$=T_znxh$`gR zEt1OEHX>5UK4RCztDtI0^p%*s8DvFzLhm-#@k%C!(M4DyIh)Q%C5)hqgd5a_CDQ@K zL5D$wjWw$^BHsVVM6g@qK%4UL*6d4qhgF#pq4%2T^bx6``q;atZ}Be)XAk7hu#v1i zGAJ06Yec+ghRrYh#yPupX8^D8OrLgmfUsrs* z+9s21jVG21UjLWh*eN;L!>{Ihb90znbLJL=_X71wVq$jO13??#0vbd>Bq$aexDhG( ztmpS0CjCz%Ew7%3`?SYBWkNX!q$N$Rz?Lfy#KX&5T*4w^MRKNP?l<(Td84Z9JSEim zEk{3d=rgO;`BOU)hZ@N?JRE!GYd^)2^qmqjBtC{op?}RUI`Jp5+&Kpll%@Htb%{QF z#w*{qHLLLR7x^h!kq4w`L>&)vpKJ@v%nXFG;M!d*^Qk9qjJAXOJ0rKVXw~=!JSM1r zWcFR=c6#I@F-CXTJ1(qiIByHeSGMsdGp%)cC%m*1iG?Hbw=SM*#-B(jt~$U%k$K5P z2|*%w_wU|c)h}g=6b~It78>4RaUJz-H<@|WDp)+EfcG?RNe9A+&WcRr@PKe?2mcuX zUPcJrdQDHCa_#kwTC-sgZ{~Bf@kWke+t-#wlpl*;I#@t7B5Yi=G|zi+3{770D#Y(*tgL4i+Shj`>__dOG(2?{Yyd+XVO5MWm6);!YStasN_Rp4o-k1Z~OVfEz zkBy@J6J6uVf4LpwnFZ#iMu8oP7AGS+!!d|mk>CjB1*eVAFTtkqIt)5Wy7e-N$?_{y5G*+l~}&CA`Z8rR!_O6#~9v} zDf;jwNrHUX^ZAQ~)C&boMzr?8oG}V_?u!qY4=P6N67|n^mPNhYLauH8aoKGs`8nAc zf4Fec1R(x;yufc9qr-X}4U%s)oXD$t`M zh?)GyRKTGR{%hai1V?idFUm0g2!6H|wry=u6d*yN(%TChbaZrlOia`~Je1VbTx`m> zlHSzs|6#P?JEYDZm`M2l6a+CR{Sm|cpMb{o&-gCOqrFM?pMGO!f7;)_Vx*BTF^c2N zXD<;xqrERm=|#ck$ksosRkG1$ciOQ&I|2nYn0G4G^VXh}m6o&EEMC3x!uom00XC)< z@jXbm>P{%N%0wohy-;Z(a1oGl7MB|S`*_HhkbBdpy!rIubctmZ(a7LFL2*>Pb~wGGsJjJ z^LSS!lgT^EuwGLqUYT!VI2$nLS$_RZ7_VJ#qzbij;8%)>h zUz6GHgbWqucfUu_8ZlTTQ=#5nAnVlFVwv^&^%A`NdYmp2J$ILWysAo_QIVpeoWWan z!4$5NcqQKFGxir@cP%WAxC`njI^N7e8`EXqxBL=w{K&z}aUgYPM_9|Dt2wejBc30J zRkft&&2Qa6FWj4#)H~{m(PBv6+7-tJX#=NnE!BYWGxargtYK9`4?r49$Q%P6rKZDt6@-`rIaND5=|rn!LFV z8^vm*lqb~Yo3l!MFEBHsXb%L!u3mHj?l$JSBWgDa!^Z>OP&?uYoA`apHW45iTP>TfIG zN#mJ`LVv#+#c?)A2fI5UMkc@Agcs0OXQM~xmu7!?&h?OAvc0oVS>E#$btfiqWJ}6& z25q6%rEiOf?Dv8*PPup9m!-Ro&C0N}#@DU$tHe}hR+~I;KNi%*)oRIn9!(W6g83?N zEDN(PSK9BVgOltZ{JO%}z^T_wy#@SN=(n7QxGobPXkw2%eBQ65qE8Utgf~q6(6lkW zrL@4Q8DHfzrkha56J4D>G4S_4NR+|<>>UuT%o5g$OGBzcPwODQWbH>TubgRhc7jii_vRgHdu$8I?$pSd zy~$m>JBm5$IGh)QmuD{U1xs$oG%6X@&dDCt^!pohaMRjSJ93Jb`URVtb#h$Hhi-K7 z*|)PZ`pHABs1Ni|>}k+xvTKGKSo()#!7~BOE7)9NUsX^#g5ylS-%|a$b>q6UZgv42 zpsh&(Me`jYyN&%56j~tiDNbq71Ff>iXA+1AqwPV(EvE8ZY$EOV-59>bssZjCHa0k7 zbZnA4iNvsgywIw)TCtNO11uL)KTr3t|i9>`ZQ}wxE|~VXc3CiJUxTo zx_i!&nUgP(rnir|Y^2z}}%C8hiBcght+mm{~$JuoB|O2lB@dKlfiU1_@kO)jbHH~?N= zXiJu`H=pxaF2xlK&p}k#VgN6?3=ie`!W8}RzcjdaU_V1hRA|U)e}*a?C;JYvk;0>D zU+Vt?g)HWS(W2J83Kn%yYHvd18?h5Cl~p}m53k=4 z^;$v%Mk38e7YpC#IwLiOdk!RlNVtQU9vKAWF)RaGZpL@t6EFCWnvuP)I!RvF2$J+u zzsEeuF_T|>O_G_EloXeo93THX7bGRszY!ht1a1;bbw<9s5*9mJ=CzXD5n^FZ2h8wg z8Y44B;bxphgr6tjvpf~M?vp6MR|_^!5vqgTkG%WwW!x`Y?+^v9+QAREAT7IY?C$RF z_wV1oc=6)lT=(Jp{^;QrAS409K{x|H?gMJ(D2Ma@ED9le^X*}iM8uo97LUv7QGO2N zfyw=St8D_fhHU#!>(&g-4Vx>gFJ_jLViKtTf|mq6EySnVBiEG_&ja?Zez^#cR9T8B z>RGa{f6rAZAm?b+D5R8iv$Bm}S8>ep`z9SCN=fwH$hvg<1vaco7VwFGOnr)a=k7avC9;n=lZf_{7= z`WC3^!zsf9^Ou#jZ#aa^Mo6WN+c_lCsf;5iQV={wJw1JW2yms7=b)stw6vzC2J|5O zcuZ`nC$k8w|uwKycD7HpnmGwOwpv|!Ij!azEi4G9)n5o;Q5hv|`yv7H zA6WuSuZ>Y&d zvk-CloIEqeH?0vA0(N5L^2uw@y4)-uT4=pUYckU{Prr!(0VZh}pijKb5Agl?=4H*y zFag-Qzy}%{TzV}|w^JjjnXJem7T~QB(ESXkp1Hv`Kmy&G#Zc03m`k`p{H*4f%VECe_?-Xw&8q*%)5wET=BKlt zv1Y+-hk~BRk{0}T97 zURfFKmG}I{_4;>Wb!2dGFo3<$SbHD3ZT(bawRdo+x0*8u!f6N8h>nGYg&x(x!l#<3 z2o;bDte+urxOp#ej2T$8PgE2(N=u7%jjgSx6MAi6H+#ibCXKIyIKMgxhdkrypH(=w zPIus*Kj%ibwH*uz$bX&W`)&G|-NlCcd@<#P<31|ZXULcatjF$rvn6?UOx<5QS$7O< zP0IeWYgOVh@GVF;;Nm$-u#m*0gs2r5Rm@C=!BZ%}I&I#CqmB)keg*x}-Y_^EwSbMg z(_>h2(p;9Vft~-UI*G$}=^L(2pC}52>D?vh;W7-LWp-Y_GXNrCe&#Uh1OQU}{FOg{ z&PCDunp^7*#l!#(hG>6HLn=#^?dQjezH3r(Jwd`vcDt52(*&JwM%0oJr8n-gn?0r( zK8PhD0dw2&{JV6TOLAY?>I&ZvaXT^|_>Ct84+m6&ge>S1TONMSdI?&rDh+(?kf>An z6|Zbi!6VNo=GR*es*&3tMWJ_?)i1`1nuw#!<6EF1u&MMUIuN|@mDbDW>gr!VDM#Ua z25hJf>A604i*7)Orz8(2e&W?i2*6d8cU*o}H_#nmdx1Zu?%CQNV2VPHud6t0ewmqJ zHb7d785s6P5aHt!FRiSo#C*wW!VZsbdVuwZI>p4YxJ~pD zd3dWEoh-1NKc{o5>_#*AmX`BX)O;}r2zo^iy81E8z;^Asfh50LwgBlb*1-CK03$|G z@%vwx*9r!qm>(VQormGgtLk`ZYs0hi_g|^IU%wPKn2xH$Brq!;rCAc7YJDXJaN}cf z&g&$KHzDGBXG{E*N#aMn`VX6lZQA(6TkQ;Am*0O*Bd;Mf2@Mc2;L9Lno$86xd-fIq z&}MzWlU)aog8P6l^e%cGuq-nP2{dZs$Zlh$@D+N6x%3gVxGas=j{dcaNc*fm1E)cj+3$SdTs{_yt=++uCb+i`Epv} z-K&$mv8v8@Sp*%pMpx@tD_r|7A%Tyc@am`eeJqN@mh?#9iNM2|KxY67izu?gVb}xg z=wY){E({wPS2l@p^>+Ee#oVDKGJxSnPPErX-)oWLu`O5{n^Jm8{cejtj5E$alC|rd$pp<-Aw7>$M`2ns?T11?D~{R-CqgtDor}{VeF4 zjm-3^rEwu7*`8nst!=?4slDIk*~paWTNv=jxbYRJtrmTnBl%Hd({~E3{9&VduK19y zlXB4haI6%^P8FwlYCN&d%%;v_0X3y@;vD ztCYjT!&cVn>T_tID{}L*P|&`Ci9EMYp2`;mzhvc+N4N9w?U0RzuuIbnCc&(!KE7W*lgvb9x;^SG@&|=%R?x%4Y$F<-cJu^ zgA4uYl6y=;PzpmOY{W0}r`9?C?R1bY`+9}7&LE%2(u-$?vq2OCEV-9sXSMKj!uBPK zmP~{6p5*GRbVn7tAY^QY*-#do^VYF_Z1^*WXqH(QI!7tUe&;B&TkY|(F=+}^UW{DC zRW8J`2XO>bA3tIh1eQVf2P;s>9)y0?6s%^5LTKbb$X;_m`@n zp%Rk26#*a&>B?-7XT`vbH66{cW^H}W&^Ip2d9%1hE_h4+y(^QafCh}`-&k9x6 zXNAH#gNg95FG2zwX)9;MS4P&$7nZUkxgq?rOVASuhUrSMiGfVP7d)q&w`J!v1THO? zF4p_O(QV=oq#_kTNDwxVlC767{d&Uncr+Bm%qImwM^KuT8^veN>1n5o0U~Vtzo?et zSh5Eog!iT!4M0o+82QVp>S|3*O_V3(V+g2ku0|j3Mq4~|>8&L`EID-{;@Y<7&w9{ z1zq(|;_}0`53D5wVz_0H;Ki+0EX7WQGXwmlEzXSlLIPGCfk^99R7!NqMQ-jl?5P-% zM_r1}FNolNqVRYa7@Y-R8w5gt^MxLIU4vj-p!?%M0V^x3=8JjDDbGbCy<6902W$PS=noMl3Jujp5S?OyfMe3&k~7W@>?T31Aht* z#^CID6n4mSR6}(R?XU_Z)-I#9p{()BzTEydLqo|z>l~hDuC123gU-b=9w!Gg`L5Y7 zFloQetqOOU&=H#Fcx_;UyvLVpoPQ+^AfzV2YhJZsirhvqZsMSjdHVD*-;Xqv=~k=Q zKVAhUeF;R2LSKPR;s2QQ_*T6HqQ()Pqq`#z5W6k|Ds(UKumyhD0(oD_JwW9iP3uze zjGL+sKEwA7t&FSK6)#r2Z{NfQ6X*8ae$ETscJ`jj{dwW}3mtIk*LL!KGrY9%kVq-<( zLu>S{s+{(Ud!K98+laK?;W8VPzho{j$~bnp91FiVVC{G=8V&eom3#BljmL9cK}TSp z`#z?FNK89Dnl@^dENCVrc86~CCJ5M4Qah>fzng$-PQaB-JytLe4;m47jr;lTuV23= zC)+Mlp;WU}XiYN_KGkul(*jbeRsR|Di#)5%0f_2YnKW83ZAYm9$Z?SY+g$LN*dQsWDco;o3dE%`N%n;x z2suf(yNjEcsMy=v3keAUR#H6RBKl78Bb+OFtdS3@AL zxQ%}mlU5mkD<Y=Iyc9>!`G)_fwbi+*jVWFMq?d< z1y{D7wK2iCPsW3PnzrK1KCYtAu5_+(W}$uD;xJW5$V!&9WUxZ`d*Wm!MzsAcp1aueupy2n9hQ2z#I2UO@EH z8S=_kmg8G@;iNICbnq4|dgp8U@tzva;XI}__F-xK4*g1m?@db{Uxy%E!;E=MNMs>` z{b&Gxe15EsNr-%A4cnotVIt^xgQ=x*T>PSg;tgH$TPDUgH$um)~D($)l>Q*1K7iV+GEj(G^sV7Io!S-f|hfY>5o zdBVQ^tv+$Du~B5I$0VHlSp2v@5YT?5R&z~JQksnq{yzHryM7@06y_moBn=W(PMiLL zL-r1Cg3p`_8t*f`N73fwUE62govL{XS8YTRxtn{jGO|#?Jq6MbLy)2_z=@SGN}ydE z>f=IFZk?O8x$+h4dr(_O4xD7mHGtBqo!1OHk9KCnHOtH=>v7QWAsr_MfVYTVlP@+Q zaDpp9OpCY9a`R~ROyT2?4y1<$5;Q8{g8pj!nJv79{(B-w^Gi}KB<8>E5AV^{iek21O*+_@Y zdTetBgSjeCoE9!DFRl61+SWKMl`5SJ&gaI(UWU1+IvL6|#E^Q$W zoCbgZf%u=%-&Jagk@N8x?oI;GQ5xg3S3Hk#NRC*jCx2!Q9UPx;0=5gi+I_`ex&?Ii zsZPFKo>SJ+Cg(EzdPd(c8=n)Mkug`U3tsPyBpm-%ozCr4RO2YGq0v}_2xpMVqchLz zIq%s2-^)OzEHnJaV?YiQomScAh6|en`lqHg84m*K6q1RxwRLiGvYlO$5K9-J72YwzOTPzKH$b6#5qx!QKMT!c4zxggc$-YF$Kxb!iOCyB5$fa>sdS2Vxg@hCFI2#!meY~wC7so;osNcUTlKv3jk-|=VIQyXYty_*t zJ6c-T9eLSx&n+27c^YRIs)DvUkMR+c9zxDOwCqybheqRde6nh#lw>tOaL(7 z%))|fv_!pH?P(Rj%YyuTU=H|@fNnWK$Tq5t#)DDkuj?4h$I*a~pq1=*;J-fsZHhzs z`0Y1>0BRjTBPnd5!35>4Hy>hILPA337Z$>?8l#ow5A47kY*ih@7 za<=;2**bX_`d^!Jz1|92AwA_6-VRW-y$kQ$@;i$ehMP)0%Ul6RRnvk(6*KaW&(OT~ zXCGEpG@U)W)6yv~1l067i7qOPdR29;)c+sKzB(+c?P*(4kdy`i=?CeOl9qk|>68!w z>5`O20qKyE?(XiA7Non8?(Y5;dXDG3-}`&N;6JZxU)#0UtTl7bJ@?F08D{pD(fz&l z!q<2$mzypw-PMa1Sh0kN>YVv7AxnR8L4S&!<(QOn`-A$O6WdivtdMedfBfz|tM<+? zN(Fg&n3Gfl9DNx?sWf;+*4FZvu)^gM*bi1!Ur1^2wX*ZmmkU44yiP)TNQta1 z7)E-er>PSKqLo%1+J#}1^c1flQhdBAWf_Om{dp%A;0+ZLlCBfS8*2nLXw92t^I$?q zdm?KAp!~C$_d-Iyo-ajqgvw7NxA_p^YD`a!@ZiU?o9W2IaxfUHE+d!B)PBg!eAMvG zR zh^B1=e9#(eI4nwfigxXzQL&b&V+9QyG;9=xq&+<<{9@smB_mKT$@}}B-TPK$vbibL zF8w8L<_D;n2e!5@O_UlCV7R}{l#W*`dFQLtOQPQ3>>w}yEeo@eD0u)@L|4}P z1TPivR-cr>W|M@O-3&aBg%tCoobm2GpNnh$Y8AZtJ$xKGK9~tQFJ5N8NJ%F zW3xZlydLO(ob%auM^?BPQP`7`@0P45lJ-}Gy}KYx0F~TDGW|CVOS_^BXTIDb9#nL6 zY89r@vso$=8zZ@g2M1|p^zeeBFA$#C!hDpxh(K1e-uvU}0M6-9xM z>LMQB`}zv=^RefaXeNtwI{=LX(Bi_v5(JZdVsIm17T4XJT{OxzHj?E_pvfrG z%q4;>`H|iffrO@9sOHVi=_C^UY}HrQtG^N2-BLr=Kg`;0KR^}lHE-R{!jzVfn9HM^ z<2{|W{`u{GD#Gl9!&-mxNUqB2%1TBCT*DmX9-mrTn9MewIp|!q*FMQ{%4DdO`r~WR zsPhRdK~#ena9}ip*J)@7{2Y&eE|PbW;PzB<+FRqCHpN3!3#s@2-7h);StPy|Ez z;K&d#ZFk!!p_Z|9$J^iikrabsE`TB7aWieOxTiZgAWjEoSiRDHbsYPDU$S)}Sw@zcc z#BulLE)klb*MJv!5VxGiX6_uvFwf(?N7nkUz#{fv7< zf4A(eB??Ikr+JY-f#_w^M*XFKt_j582#>Q45QHzBsjDzJhPSI&HMg#DtcfetWJ_ zb`tU9_&Y$L5b~MT{ITCpuRAQE#vy1W8s>iA*Btx*P?u>X0T`MwFYD{y5&PaWlha7O zLgdUd&Q$T&wiUE@IHpvq(X}I(m?I6z0N@x!qxGb+G8-e*d#zZ%Q6j}315~Af(qs<5 zSy-I6?cC4MGtZ?vZ^Oc*+M$u|YjFl*L#PwHLX-@XUDvjOJo3 zL!21}5Wsp>dQr$=6;Q=r8MPRsi-EHV3J7>*#9!Rg-IHirSIRTCK#7(6Qf3*vl~Tj) zp9}mm0c77mX;QirfIq?p5+)kp+TR(hmX(*|sfie@ex+9r4GRONjLx!LX!Xs=cy`bY zPy+=Cx9gR?v2jjW;y9dN`$XII?iT*v3CrDAS5Z<^90Lk`4;xGTW=)nE!f#I;xV5!K zE*A7e?K9u$Dp++?*8WCr;d9Q^tgNj1`Wa|40cZO4(QAWehHlpCVjUIARs|NjrdkFU z+!gfis2v1nShNofw05T|ZiQDngI)P=VtNu2*_DYLDqbY_v8nTI+JC5)ncBE?L6G>Gm%fa1Lr@Oarn^XON(#B8!P4bfacWvh8 zu)03R$9-j5{LJoYN%Vb1Mb;>I!8;^jfF5RE2m8nMy&Myl5O)FUAfpCz!{?C^wNZGi z%*+laTN7SBB;z0uf2Dh^6T$KwoU?>*ET)ZCMcQ$(@|0w^VX=fgIm(Qb{g3P=p1w$R z8i>8-s^ktNRkPY<4hkKmI7cXmS5kA z#Q!H`VXNbZ`zcj=a;%tjB@6Sb7n4^ayk9$;dKqrfhED7C<&Czq>HfEd#;4{MbJ-|F z0~sT0YcJjrS_uLd4|m#Fn)~la@bl9jRvbo8=rVCAm%=AS0GxYeC8b0z+b%Tv@X_({ zsE7#q?N30nuAK%*_;5)Iud-w#;%?QLk8+eTUy`RnPVD$zdofY2b@#-qXoLSM3p9e} z`LV-hRm-5a(ey9+$Ut3d7IVYP5{~V(|N3Mfxk2Y@zz@+~1m<;Vr>`F6pcELQ{U+ju z+8##yO~j4D5SwCvW`~bdvVeI4)o{o!istSueRsggb@VA<{Bn%_J^E6cI{zo2QPzup za~k_lj`d_`#%a1Ng4T^R-&S-pPg^)6n)6arw(JvqJ9`YCh2VXI#~?&+eSIwV*E-*4 z46-)b{-SNt@Z=*1+*1V7(vEt%4rZ+Tcpp7}$~1Wu9}lL8sMR~#nwy&&8~?nNf>GT~ z^lrJeQa&2EH=w^$e_EMWrSK=l?Y)X&JOw@hDj^J;hR1{AWSh^T0Q!vhTh7 zl3|z>4EKT?Y?BK(JZGNoe$ixiUq?cx7-UrUi|r6ZF6aSdPA`sMt_jg}z1W{!h9@_9 zOcd1nEv#!EbkX$Ui%KWnY5e}gl8;PQ06U5p{1n%lc?qzFsWzyVQqI`>{|U2bqA4fs zVUr=B!FBWk{{G()XR2+C-O=YHEcHeFFobv3txv?xc)B^!LyALf?;#j(G>f zlW?|3Uhmx}rNVyzhfGIDH`(Cglo?-MULNuF>&dPbl^N_yy7vIWd&|T!{5f&L?teQ9 zWJX=lh#Do3GM5Rs^AMMWqUv()4O&-&YUCr(pWGdG^n78{EnM*(i)Ver)HA zhJs$6f)o{Wmo3{Vo7B`-bv)&-n%aIJaBKSzNRD2fvSvGN^-XI(4& ziN^m^sh6 zG4r3|=Do`R9BpmIRaCGG<*sc_m*`1?lnK-Tj3dL&&|9ll!hYK`H&2aoxp6 z?yFuZ8X98@3l8};(cW*@Ykuuqeil`c$ z#5fp3jMhV9pg!>-Zx=C+ifq`f_n#f40Zw&d)6zGLr4HlolA4flvj~3Kzb_d@F4epac2Q)03VLbE=za zxHiLFr643rOeOVR#N!9Cvye-qC=8qf@_g#C)Z{(C_SbD7@hWurN&3$@FxEKzu1in5 z6CS6z+U(B=a5LJ(M75IA2;fAX3nQhov9s&z=}9_)l4%r%c1(emp&;DlZ~+Bb@bI=f zML$oOnV3^;aXlav)}#Gj@%ue{x0aF4Zm0KDWsJ{jqtru3zn>)(grvuK+yZ|bun#_v zD3cF-xViGzI2w41g@Xew>??));T51#RaeJjq<*gkmOY>0I^qxJOzDjA@J6D|p)kPZ z+-*kcT_4#3WBv{f55XO8% zXuYYn9?10a-d_FOiZjw`v)<#=h0{zn!fErEf_;Gk#eX%en~#ov2!K>p$YLhI+# zKuTQWLqpFjL+H!z_li5Wlumz_VeXzpBL}6Y?O)8U<~${TeNir`cQHeq1rNacyj&Lk zv`EZm8RHYoegcmik%4%HoTj~V1#0F0_-GqkZDM;+GK~AwZ+igZu`#9e*FRfZ6SDW1 z=e#qW|1OfT_6z*o>8SH1C!_du+g{zuaixP_gc#+$K4A5#fr1i1@!xf0u*jFE&2R~K zx-?e{jrRi}Aky5$T(q?V)oO=LAXNS5ql>=*ZlMoo%|eF=R<*{LD=T5p$ioBkw2m{) z08wWODkNohBf;R$i zn(~!8%O=>>e>aVyE@tvqqk%2^`_J)7GdFQ(x3kM|!SA^BHW%*`4Z0BRltwd+e<3H3iu-t&w+ zWUOn=zbgSSgR%h-d_95jiU%bCky#K*YPM z^}ZM+^c);ut{}aaA$m8^fIMemSzKVs{O1G7njKcPurvmIf@Mt2&Doa_KUCQ7FL*u_ zA5fi}ooHbA7S^A6-19g$OvnUy|A@F`%hdu*t=(&-?6$i)<*&bwL; zEGC=?c^uui=saCO>Dix+K-25x-F5%}BKP5T9{tPM%^s5fKLKrq+7M?YruW1wLqV(7 zT-|$TXM8k=!sIUQZ%fgeT{@n~X_+{04H+cQB@-_6YEtrDFH)%`&A1s7UANfokC}02 zFxr_mG6andb_8)0>bAUV)#FDxb1m}Hc`wAikTDPDlxo~n2H;8=46 zqhdMiTWv~%??u!!dJsh5ETH;T5qW^Mk;HxNA*fZm&=O^eNKGc`nW6u)q5VUkmkdZe zM0IoywkAqZCSDfZA-mTltuzK-=(QSns5{MvealSOu#niI1&I|?(EU>8#{?c8xjr?; z{->4fC$ey&7Cb0E>*-zph4P$NzC7nmvNdJe^Qy}lV^rq|6@%W{7Ls@Wjg!A zDCTEv(-Hq_5hfAspPQY0Dm*|^Qfi%>lOq$)rRReqVPb09-PQH=BuSYSM*j#o4o@-J z5H03PJ8Jev%WX8_kNlKmB)l41=W%JV5(U<7)_?WAuj$`OHGuHCMDNFuXk(Xh;hXr# zNJ=vTe9==x|6gjEU&s8Vmgw3&sGo%u_BNpTq@<)k{mF9jQkFN>cC;v- zu;l@<+tt4145SgMfaT4uagt_WBPk0xI6=8az z8D#;^PJJGsLny>g-&oIiASvg?Y3m)De3*0I#G-al**kw8oah{MBXN_&Q)~3u8;T#} z)n6GFr}=IhlcPf#Lc5zl!CC9RIw<$jK}3&|(*uJ$#J*j9-JVZoZ8Fo0!a!wB0^)b! zc_XpzAr&Q#Z>@Dbz7(}pu2$@Lo^PZ$F*$6?%&d>ZQAqKJqG0)w} zLgLJmu1?>#$;H29^H|yL@ z!>)_s$SgDDVuJ}qmWcuU?nPy8Z-!{H_doj8U(DtB7`dI zDbGhg5?B$()1e0UFwu=m4@c#z#wt z%4Tg(9_{8byF)%wlfrz|i7VM2(6dz&C%_s^kYjiuUF)c*WLvzng;=`EUZCm_2)6jO z11VdkE-3~q9-a|anjn!C=xd;+{}LB>p09hkY#=GkmOw7YJG4lJIrg)^c@#Q|DpX{@qr%kzNxHdUFiabHN?^=Ms05Plc!BxOX>k_slc z*DcoT_S`aSIhpy*gObsUoESMi5X#jYYI2^3;(?enRZMTVjhkH)WE1)yV^1vH?@Px# zfsXQ7vTR$=mg`b9#(WpSFxHKY2`a;GBR?OJ?RBbM$dXP%5!!~Pe6xnk?kTf4HF(e_ zJ;Bnp&jl~qc4CMx5-ZstO$}}@_di^~gu(xsP_3`*^4cMJX^E9p2@_nM>9Tjv*#cZ9 z@ItkEeB_oTElhkrL$R<>yE6%U)%)qrJp@Cjnxh7vr__}|t#bCC`obW3oN$(92p#CF>xUEf*w*Adx%VDh<9^gKM@Ivu1<3kmra-@h2xnn+)EuZVr2+UF8yTmtO?S z+AMLqiI@PSHw+f3LqVFRrojH2`noU~23Ma^V)El>e!`H#Mq9>h>xu0lu)(~Kh?4UK z32|R?%BX*KY?Cv4X$!Ngnnfs%1&%7qtg(LI@1t6uBWuT3PJuDjP&w!;3{hmUa4~Vb zELPL9``&^Ur)tyEI?a=~w4|tntL4&T*ts5^mX?N1TPXKIyhv|BsU<^`mj;JS?j?3} zHzx`QV?53IND&m0`F)MqLx_-Ho+WQs2x5$*!4Y&aG0Y=;kc%DoeTH0T)qGhSt$>4% z_hd<-k1m!eTlygP_4Sm9qD2~{9YAe43UZdk!$pGVlxO+!LOrO*Ez?s@M9Ae9rS6rp zE*}ffE@;8_HyAzFR3jow?tqzO2WNE+-H$A}iwcJ^4*OLx)(d4@z-om@L7@ zZit3U<_>o!OsVp|drK#r@^;!Y20gVaa*mld-NLU-;=aGIm7n5cBD9S&bia2?Yksoi za-~NVI5moyeOZxL#vtFXQvZza%W;5YmCaXunNY2mcy+a^aSDs6}?J%p3qmWK%9F8%qk?7e3dDmRPsfcI%)D_@4MsozOu=i%|eibec(iD zJ#v$u410VK?7{R4BtzaU?~|lVi;0f^qFwm84BGHiNq%EImki=OfyY4~O~)ycC0=JL z;=gqC%0X{{t#l)Mg5Omqzf7X1M=~=bGqYU~f;fH_|Jk2%3D=Wp8}`ly{j)2TK@oAr zhTdgUzy@DpCO@p3(U);dW|m3h8^)o0$dx7E7d@=Pzd*D(tv2rZvg@+z1o{n^mzOc0 zy^3Nrl2=kvnrm=rJgs-*-K{%J&xcq3{AThJkqVzAr%Z$8BHQ4r!QX-czi(_0uZPd#}t*lTFm=(i8iv~V%1p@Lj8RFu?ksHalOY{iL1X-bG$>`7do zY=4F-J9sq|dPD2xtMyOp9;y6XS<3YA3a1RII?1-l!qL;xQcEWhEJqU=JX!bAZkcFB zbWv$wsk-hvm--agogLeiFRd;ifuw(H*E;36urbo+v|W+H7@Ck!eGq>j)rff3lo(WU zUClax84eH#7`Z^GIO?_%2WJ$4V#~=$__U~whLn>tT8E@>A@-T??&KO`vdF^6@CT+> zy(41*1pu6Ido%-FNp`haOF0ZJ!}O{b^-jE3iZrXA5L6;oD6uxjZ_s4BNEN#L;nkRm zk#t4A+Q18f9pz-vg+Oos|0{m>3zYkK~S_y6zC;r$Wg)r8xMRQzC6}jTiC10ZJ1`K!D!x%P4%a0OWb^rrAnW2O zZR$%CUuDC=t1#;Ig~(nD0pEt3Oz6e+2qpHz#|GW1g1>H8(P&;-7eSp3=oc*#d+ub8 zX%biZHMUAZYMgxj`F)Xvn}?}lysmTM;6m{jsAyy@!u+zS^op#Q*^7Bj3=8{$==zx^ z>^&$}{|tZH9g>tu7aAd?w{e185f!g~FDhRAZBK=U!?)BHZ;TBEU!M2Y0}8zceHqhD zvjq#q2;0DQbNqhWbxVrjs~C9|mONHUO6z^8FxKGg*FHv9Q6`tm1o2q-v6*te&MQ$DiLq0b6 z6L-@L;VL(C z1bZQ4xT{srpit*9}{Z4HA!VbI%1D zSaV0-k>G4Z6*mjNF9`QZkJ~e2_xHp42IgeR=Y!F;x9CNKVX+Xl>DLy+;YF-U`Kn*q zlP5oV#zC=$F-jhTlNB%>8H7K&`ZY4CY}9w$7X)dEjwuJhF>Y?eW$bMMjb*$$tCDk4 zPzh+u@poo>nKcWO87Yk;Tsk~2O8dBsz@JkURkLf?KcOp&Vs(7)N~(rIJlx5hokAyuW39aQ^)DVacX_P%A;W%0Qh5?R)E$ zU$#vir)p+;bE(Lcr+B8f+L1%4m%Tt&gHuhq)J(^PtyVd(Oc$gCLZ$Dh=z+KyB8-}akNEzV?5c#niF3v^Y z6A=o6kff`(KKRUqztxaFj`CB zn;IoOMo~JloYf_tbFMtXBc;Ul6HVJiFSf3z|n`JH6lhPmK%BEWc^g#Cpls#y?XBN*$k1b3GI&z@WzI8lW zPQcv`E$(8}53QHTIxZe+(Fg{58i-Um`pey;1Ib$1mkTE`G7OxTPcHK-S%{nSGHw}KJJkN(mWrNbggaEYWPV-U0dhq3tU&&yjOkVb-e49A7h3JYble_U zorio@Dtp{rrkBMYv;uPCMlmXQHW?~*Wvcm_6W&PaaT8L+k0K?DeIx$nhQm`~F)77H zn*0K|{Zreh2VYrSSl^u0h?!&$c1SS1k_|hnuiSVv!{tMyagcSb57tS=O}>_LbOx>kY& z3bU0>+gfdIAg>#{@NLG**l^r%&1hQ_z zwp8n*&$s@i;O36w={MGkMFxC2QzceM7ADSmL`q^4m}A)83Ayn^pG6!OHuA z_r0O%$+ys(j$m)|y7X7WUReJ=KKeZb=)}Z*NB%e0mxDbK?+=ATb zZ0IF4WH0kRhYY{Dp&@=Vc`_KF7U(&af3=?JUqm!e_EHaPP!)la%FW&>;XsO6J56{? zcmbs^eQ_J$op{YQ#Ro;im^DG*N1<-8s?W=7H#-!?rP(@;vpK*yqVj2VXg>6m@HRHG zj4)^&wB+xAh%~q7crs(mihCxw?pR;fe1VEJtIe2?kDL(L%^@2N!!2`y#0x8nt`!7s zB7mRh6|TR9hcgJOczQ#5gvu>hcYh+D@d^q+9R%g}gIK_EY8$lFViC*2(Fp-RVYf&4 zp%~X1UrM&IimCRet?~Zk5o|xj$J_w8oLSdV9(AJl@Y1aD9K$U(wVATpCJPI^7cT9F zt|X%=87^IZUZXl31T|_8VmTI3R*SqPXLq0Uel_SdqM~J7ih*_T{MOAIYm&*MTD$p{ zQ$$r>t!OE@<>+0Fptcvi=no3GQay8LOKnopbiUnfMie}~74nujUe%1%h~WfW{sX=3 zs`koJk%x!xJ*N2c9gi;5)ZQGMk0hJ|UB=T}70j;BE*;?w)IWBk@a;7)={Etx15mVA zhVjhqEzZpqZb?YRq^;rJL2elX&-!{c$R@R!2@bp;GYarud_cFQT9l0TRmTnNWBi^$ z-f*b4T!p~K11Fel7{~j8_B6zvoRl=%=1XB+U7QilyY=<;SHo|u+Lt4>W+x}Rlmm%) zFB)$)8^^sg%m%Pgx>N6`d>;3YVBkN!CeS<~1dri5OgTFcYzH2Hvhf&C9Cd-%;1RQA zVj-wlFxS*MK-4Sqt%wnJx$)bfXTn7D80Q^!?kKp9gR<%^9!hJVhL^JHKztT!fW|=ITVGD!z9;#f<;6a}` zD!LG~GUCyf>0S(*$s1na=n%b}`BpnA$Ag7^nw!jHuv(;wBarO)(fC2dD}(2a`n52P zF@k=rEH<{n+m8#pf{1MR!wIhNNT|v<`~vCyR}EBtrgxKBzW(d@6c;W;o=T5tRU227 z1!j~S$(g+0Kye)nADPOnJLazaDPy6>zvqvKV11zu#Mcb{2i&_@v&Hsw+YYNuO**=& z@~l+LCcm2Im0SgGMrFK;zZS7i>M2%_V`U!Ib(*oJ^^{jyWKU7%4Sq&;Yk6~3q7RiP zNMIYjj$M+WnY6Td$h~vs%jWh%KL1=q^QA}blji5?=w63W-b14e4aKAO=v!OvE@A|f z87C<49wKX~5$w!0Uzl3sSkW3(Kz`7}I0_e@8g&~kKdy9XAf(dA{6@UiR75fd$G1ow zTTL-^R)C`FbnPQQ&+zlDc?_B^gvr>~qBTG(&vM({pk5u^O5o9j$XJ&Z$x2Fv`KwvK zH;(fzIqPO$>MH;qMNu1bwPYC~Y(o{7nxkLY+?9Gk)4vve*BXFEXGb2*DtiodJ7V7# zF1#*c3H+McBQA#y5J2zk1Fp;ntRvrtSklim>2*EkD_Ot*t%I9U$3ZU0m=>H-e zey0Gl=Sr{C2VBo+ENmz+a@-)9!dWwP=cxHQ^thyCmI-xlgV0E+Ze+!#RnbBA#Dm}j zIft#*Ku^lDcOeKb5(}lQJ9j6uba<3@=CE^jIJDA51ERZ{m$AhRu;Q;w9RMTo+IyB^ zfgYpJKKBkfj_g5)iz2b0(&}WE+Y0M@G1X4w^QS%>CrZ;LHqPb=GKRLBNShaU+h(QA zd2C|WQii0QmtfBP=6|uN(F}#d{Tg7Mw*o}Z($XC79YX#sQ!GP$xg#>>0;Ge zeo6jHFbLsCb20qk`^iZ&Mpk5+&BAj7+%4Yc8!V8BAJaZUt-6RAFtvEz zT#P@8?0EZ~%2LSc!kUgLC)&Cjx_|-Ljsmyarxja>uSZEQ3MQ3`bvNy^Qy<|f|2x2N zP@NIqtlhp!;F&<9x6!R<`3~AZkR#0xS9&fp-7Y9ANMSoKaGm5>vuqX@F)=a2p0kve zlsF$TQd39s$UncA=VRf4l-#x^MDuoM&(cfi9c^xsIKM$( zv5#8056$Y_D7kxtJs_lLwozF1cM?(8N8i*z21oH1SL&S5f81NBlk=!%R3EIN%hmWrtFlf%^Vcf`!7_Hh1C(`g`;VEOoi$F~)v z5-lbxAS%w0&yK4wH`C8x7}ek?8{l%Hf@k|`T=<$&X!XhHPS+L zfT|*~{Or2)Z4@`>i=QWx;jxKNTTbiNynGwB0^a(;>G@BOy_|k`)SSZ+RCNC0=ydEx zXIRn+iP){fUJv>9!me73o4HiZ`a&#z>o&>AUiz8(?D2|E&TBo<$7`3xKp7gx5rj7l zc(18gY*Nb~{>!_!4jOMEf;ULgg0ZQ>{=(`BcE?#c8-paN(itp}Rzv-Z~YU zlk(wt%AW!dAc`e$@6MHdZYN6uxuvzmVeh9kOfJ=OG1!fwA!hahY`up5h7x+5at?TCjE%j{3Jf5?aRHE_1y~wnB}LS0Th7W zB$Fm}$ZV41ix@y_4)O}#=Y3Gsjp^rCsnl!*Jd6)pX_i4Yf)hPt_Sdn}oBRS;17Q&% z6Vu9Qzk3$QoB8JXgid8g!DfOIF3)`c)7BxAx9p4U*B)A}OEk_K#gPU^Qe3!CNVA`k z1O_k-neov!M3bSIM5+iE3N^Us0X5Qzcf0=a8SvDZaeYnqxm*d%t3S-ktQJUg2ieoBXwB zS>lA$2#VCm)u!p3QMaOwXxsCSvmGwiPv3&~>ZwBGO(*3{AX`)WSzKOqb9}|k&Q3_5 zwWYr$zx+;1N{J#PHqovwK`E8JxNf2L{KmHhTL3$7ZTc7Y`V6Bl?`Av2{RU4FfvHEQ zJBs;L?^_S4s4QmZv-cGhNl71jkZERJXUw;&ZR)V3_5H@cb8iMe_@e$JW=% z&Jxx6Kd$T3Z^CTE4->Kw<%b4apMAQ7wk8xjbQvl*#lgIskPjPifh;V+X#08|c%D|L zLu+O&0uLne-lb0;!Y!ljT1)yc)BcOjNcUG^9(ka%hE0h{ZV+ox^86`ze_D zLq!@pxBe2QS+uEh;_<+R6v7?JN9LQ$*G}^0Ze8EgpJSXpFeiU{GK`mzG7v zelvj3W!7bV6Vl}_;pwLM(f|gRt4-@0kIR(FFzo&>$&~G+I@4_iHR* zDCgBZ1Kd-gZAwm!>Q%<#vtdut(9L#ioaOysT4m|lO-+VV`=s6aT_tlj2cA>e?jT)p zm=H2KCMWaM*zjrxJ~K$j`G5-q5ztyA%PfoJBF$puXwpFJZ&zuB>1$wktG5h$H{c7* znreRM-_<2yxr2OTc?TX&EN)N25;Y{$ee2;thsS?bOd{QIBfsDdiFvwUA%M8HU^DUK z8|cSO{0%Q3js-xV@A>g5Et#pq9(aNNWKA8PZ<6kxPB zpv#kY5Xi6lG_KJkLC;jN!E2!$_~OQvWEdeni*@jRtvxJcys>_#Qjw|bRF!RS;CA{9 zavo)||0J&EO9(1}wFt5I*qAq*{mWd97_eB_ZSDMa*OQrp=)hpt63uUre1BmIMdjrl z_5N=4h}onJBXOfoOJ!|qJ=*);tuef|PM%}o3^m$1jaQ}(qrL$B7jtT|v zFAfo25jzc`sshz12R-y#Dg&~)qb$+5xLy=qDdLIiy`9c z?`RCIs|=NXqK=OGjjq?=$LY+WxV?6u*>`YI0C0(TKs+SOM+;boKvDT)z18W-$rmDU6I!BHaY@%;U4OF@d|3{ZB$ z6ZZ?Yfv41=1Uw!Cp~WhK=DN=FixLL0C|bZE#NtSUNdJWumy0#=gU3#ZIoZA_q!&{> zxRj{*0kD@05h4|aWuAm8S;(Z?AZeVBFvKEu_vhPw(rF&@!BT3%csCnPV-Ks?gE+Ue zk|d0I;`pLx*8IjT2sJpM(u!B}G{pgs!8grm2KP7|1oveXQ!+Ql8WhcH;x1bpIc<0` z_KEh}8~m=^%VHx-aH||wGbqB2IjP?@VrR!cg>n7~XIUm^nl8EhjuMofBwi`=FwN;g zo@HmdMCKbZ^OqzOv&m=@^I#ZU@J%XTU$o=zAn|gIi5YqV zA#4^O@ag>(Qo%>U-7X(@(JtODg2`|0NDNVYE;XcY;n@v(<7VrfZl@Zr3uy~{bP4<# z!$BYHe;#~xFH4SoCP4GV!kOlMo*#a;Ovaf-Ud-KJwQ7YrOfZ$_AuFqJlVmu9O1L3}2aohpdSE6;(ZF1YbhPWjCX z7t#8qG95zkrDqsygJ&e-vsUt~Db~S0@wE}Lcb*wiD04TKukMiHtn&7_@cjH*G?<7N zSjXXT1t>{zu&}Oxji!QKhy8!xdA>O5iAVu+BgdzwO}}G*vRmsX)uryoVSE$!g@pQd z>p84F#zk4fL{r?RVfub(RB6P>W#jeQ={3bF9&Egw^MZ!gkDEZ7lv=lQa*`-O@mY{#`?=U zzSM)9R8yomJdFP*A-74F1fdNM)Y(L2pm*kMl@mjg8RD^mW56W zVw|)rp5mu+8;xFO@eo!dT_qm|QJrn{p9i+2+QF?C+&m%}WtaEjy$4-}CTqKZHPr!Bpf3XjK z>(_oYT6_-M1Ze&NMt-LO6ikXt%whfNMO+pjYWX0eWV>IME9RRJqkaESimMo;y7Ka& zYj+|Lb6?@6I@q4J2Zti45z_rejCmncfXmgWvUmU6uCN!~*7bX5tzPoQvSF><)JDndaw;MD8ZEi>i z>G5c(0_%%pDts2L^OVKyWjvfl7}Qu#kBLI(+5HpwNU~^kkwpRe_?~p^OK6KDLXG}( z86F?Xayo(L)~-}=dPY_Om%<_H{u>VT!gvq)b&=Sim3tntfc|KeJW;#(jr$QHa* zwtUvP3JG=x$&)63h9AAbJAIqK3Tx8()F6MFe&sap`OCOQ`KGl`e9MRKvwfJUV}NXh z$TGhs53wPp9c~ZX0l!xqjJ?UYtw^TGkka9&v{r_r_uIG@vMa)ej|;x(Fx3o1SztpJDsZf3g4mLs1)XOJ>lh__v^IrXqF>H#<~%2V)?!Civir|TqoL; zXW&;r}AtnaDikJ%DxYt?41Ak<&CklSDk-6`=vIxqIZ|&e*ERkD2VeVS<<4J{E0(_M7LHE|Nd1X-TY(f&4*M2QYH7D<+( zaf}l+XpIq_O4Wj>LbYy%ow>zk|DD3RE~np6_$d_=?sKy zqkNUZvdQ#+$};0!+lmCxYh42zkHuEX-wXIrZXY_Ibj z1k*7U;gsI0bA?mN_o*UGwOiwo7u#`>;M;tLIgJ6!M{~EJ@|uaX zSkaPEk;Ti?zImf4>vO`P%-iDTJ*dTL|LnC~#r{|MQqCS!wUcQ=q1TX+T>sOJsT~K} z*hWDLDmsi#@euoja7ZJ`6c>@F1m#*8Zbb-H6lbQuwK@J&h_E@C97%XBvD|El5^IXX zuc*w0(RU|l9KBd7O4luH4fvKl1mvyT+g=!VBmT_g+J0`dcSX>?hA9c7lu;8!Ef}+F z;?l`8*?lMIB{J}HX|_0baVWAdL(jPNQN`@%$G8=Ka5C$s@UezgUfEcNllRp}!(ko; zzQh!^(QDl^)M>Rmd|Ad(k(Udhi{^hz3ejw43fioCq&bk()7J93e^fm@i0D(kz4mpF zfDTYy0!+nrbT$$Jm<*=Rd~-VPhdcbfoUcG!76Kkm z@efgr?Z}&pxlC@ur~nc+M%(qQVi37a`;eys>X_y$k+x8qHDt%_L;BYz z#83<@aZ)fVbk#&mYP>Iunw~u0K}S8ax}(CzRPQnR)cwbr0iHz7d5wKjZyL!$d_3(8 z34Ga7h1bF>zMA&S5mbcUC-mtOvGN;7jBkD9JqEq5o)%L1bXR^k$Lry)a!*=~ddQ3L z5C~YjQ$pi3s{sJZV=K+?CPn|td3fLtA{7vD*eXJMvC(|}0$9tt+Psu*av8X)FU9ckxl!|3% z&UW8w^~D4#XPwLdFvkZ68+$-&v9!Q3E%SHpRMZc4Khb6DI_~e_XNAj6zCBW5Wp!z0 zs>pW>i&p37r&@!}aQ;b$>Eqq+@cvdSAk`$wiTxP9r!(>acHm=j#38%de(CW#t~@ zKDawB`Bmo7`B#-rFj?)e^+d(wbo}dM!Zp6-r(qQcHBUN$?7>F_WcrxF{B|cgv^E&#qGm4yexH&NwYwtSuMqQcgD3gn=svfwN`VUv zp-In{V&{7@IVAB@_zc6eBdOPp>iz~I9@0F=XmGxvgYKM%u{P%)*Wrb=gp#vCETg-eSJGi4f@!zU}mHfc#P;M zeSgQXA*}WlJFsgtDDL7Y-K30l+3iINH9n32;PwURT}vxrEv`NY44|bW#zSfGGY-pU zvM^J;Y4D|Gm_RIXtP(Td76hO^p;Vf5iC^lq8v%v>el0ObA)q)nZ&84iHE|!Y)(tq2h!)o3V`Jil(lD3G<{pIZC(c> zFuqgLbs5>j`jOVCO^UIKz{@edf)Ej;6!G3eVSW529I`O%3pg$5_{Ui;1qq8JTOnv2 zFmp{!Nzh@8*zH}@3QZ*R$e#9r2baW_+th|XS}ICXzb zN$vCzOW^3kK>tmr(^^xW?`WsSK8)OpE9nZK6VN>;igoOoHZ8Dubb}BFM&XQ~BE7+@ zbD~rbQpMMegC15TuPBnZ>uV>u`1b@q3H#{h!a6%Uu^V|mWRH<3t~sR+b}TR~&J#`i z`>R^V@a^GPaT4AFn&lXR?-W9W zHJkF$ITk^K;~bg;hJWS}SpM{#{4?ojr{gmKA*%(20qZPXiI-8w1O1aHL8;PZEA>p3 zpV^&-BrO6aReK&q!Gju4&B9M&+XV<_KaK7SgchDJHz6lDFZ5gA(_jbwbm||_!3Z)L z6v9R^mY$joh&K;>ihBKI{orJDZt6ma)`P*+*1|bcKa>k2^G6je5SR`Ov11rFOe#Ad zXOi17V@#1d?o_S}zaY&T#`^6Jl7BgaK2T@_2P1wpT+|9fkuu8(n`QhDg&b5-?Bqh;)4+CNZobz-_iMF-_gaO<#gq)Mm0wrKVirJY zat2*byT5%v#Sf&tm(pjlt0e10H$-{el_fBiZPxSZI4wm#2mt*V@~RYO3xUIObs8xp zK``0Ti25k{*|-m~f=hq7N2FU=Zm@8X@%@aeCiIL-)#8H~pq{?nLz7bIXGNcse;GrD{e;aVvKh%>JQ3MT zFGix9>OEU>zhg*+8%+kqE-k%tE5@9%Aju z+JNwzH!%($I3|f==Yjsn#8n*a(H@p1Mz=}jq5J1ErXSmX$z?dyEFhbY7#%Vq1L+(V zbw#M=l~mZ&z#{N}C!(4LV)wMP7* z;hXYLUS;D}dSv)(!(*Mcc8Z*SDqqhoj7rIifqnnh*4+AI7>6vLA#pb-!>Bi8*&y5} zx4}XYleg+_1`EaUl8~0;Mn||S$Upec7GxE<1(_=Nw1J|2i-}e<&}ZXG_j(6t>K@f! z;QZU=z4oRoF{9=eXg}uK{4Mb~N88r<+$m7a%XUS3Uwpdz2x7v}lHhq?thMGemLyH|G2FDikKpW_n zPG%8U4RwogQ&^S^-=LjJh)bR(6Btu`ef*VmQxl z8!d=?ELeBOicLBTu_W4TRKR)d$4|QEV&d;D>tW7~L2{Z2NL{3?V`s-e7bra!+TnD; ztc!0U08CVULHUx$ESg*K8IBv1$Ye!5;sq9#qlWJ&4aaOO>DD#apxK|JkU7gx5tB}? z7w~TL0ycpFz`|(oEw(JXy6rz$tOp;qO0`gvqG6yMMxSM-1V{Bv*0V^-@lKzRogtpf zi_Z-6Db`)b?0u3$L{AG_bkFmXKRC`7M?}XJL-n>UC7rfwvW*e4&ln`cZdr&IF?YXt z`%3~DKK^ayQ>htIlCt+YS7n6qiebweGLBBlWfD+kk&tA&Y5BVthaw@;qx=KNb0evP4C+LGtx79H3@9FKuT z&Q`uFUwW52MF7wwYDQlv8>6 zZ8wBQy8pUOu6OsD5QdFg3a4zvvg551I)k7t*)qG^4fccm9PVr<;m5yL18Y5+!n=t* z2u=r+>09t|KEC#iQeM+lejsXUs-1&rVN~^#QzYFGq@40lqYxOK?+G_RKuNItmX&xf zHYptv*buYe_=R@52nsgVgf0%{MKYtdtm=mfnnRyf{snAjan!+)7h7dXs1TVo}Yfg|nQM0)?8}Lc87}tKwl?jlTzMTiAO%rt-+{ z)3e8A+@V68O=Aanc7W6a2XEX>>cKLnfYZ1{hz7`eSSA1nWzxZ~QmB=;dRw&nRBRk4 zxSj^=Ft_@UxuDSzEs)3}>4`#nXe%X81*^&ehA$vbXZdD6XsMIq8#;QZ^A(=$i8gD& zY&DnkpuUUFc~AI4-`$1#)@b$v`-yR|Ljxmmn9$I=ur#Q2AgfxTI60z)TMvi`M|ISz z+nQTr6Ib_-9^U1~Cy|4rW`V>)1PyMW0tXI6q{8a z5C53?&ZH_%dV1O+V8SKl@3h>wSFOC(3VE>s#r|OG% z{+yjiMpx1Q=EzZ-{C`94F>u?G7k1;A=;K-#(5*Vq_M>$C&+`NfDY zs=xH*>vP>H)PVa5gHP$6;-c~dy&~}&GYZPt9T2C7Qi#)-e-9?Zy1Xn}aTe0{p&s$? z28baU6Ty?61!Ch4>eF{dpDu`4_b?jv+!t z#v{e_+UXags8S*YcK#221QdQ^<q`!l-uCC(EW0QT-$4Kux2w?P;ufc=*KMATgJ%Y)pc{m{bSj_Y*G=N z_7VF}0!P;9y%KE4EZIY>MJVWr0F{4?#qm8awGX2%5r~jUTjI&rmJEH1eq$UcAyccg z2_r$ts~gWekrEFA$p-%4=qtTe!!Y4ZIs8bM=HWR&elWOuykI>6M} zJ6Dohf=j%`!~DC%+vLYn$~{osfn5AZ+n-C!g>tQr9=^Gi zB(SgkMWR0y;BYP?qcUho>I)J5QK0IXP8jHwy+RJU5+b8o-^osyFpu8I^3D59qJcb| zSPE=*7|F=}pm%$U7S$@?441%$?_gWI)zuIafLx5i(E$KB86V+pnC<`8B^r-U3l|fO z-n{$H2Nd>9Jk3d?UQ=sRZRhQuOGPalch^T--|XV88E$5NeFTd*LC`#Y+IWbs?r?4= zLRBd|MMp{-DUH`9rygfxIE^=rUJm|}7CXo2 zF#r^e(r2u4b$83XGpwbUFDeH}SCM1?$l=>LsNM^Y&l7aBU;+qkY5!L14d>$R>LP-w zwAVwPh~H!Pv~B?ko!OtCqN2LzG@c4#z7m4NX<7Lig+0SW#G(PTSv1umnYL@^(MHMV zQhK5dVivxXiLu^@T%_}r!&JmAz=`&UQ3j3aKc){Xwl?C9aiseBmeh3}CiY45%@(M=KYxvh>=vBMl{13oU zJ)TNgx=I?3W+1fwZhjivZqgSVBezrOFqKAwhV^GxG==zrTqt2P5eV71hs)i_yco<+ zuMmBn9J@2gH+3u_D*H*XxKqJ%4rZ&7*0injJ=A;rEZPlKk%)HIVe>hgPai)L{C?*l zIdAEPl|jlp*}_~h={_pDQF0t@HHAAUm7dYq+&U-j0A!V{Cc|P%SGA<2uO#Y`6?Z~!l%?7I~)qLMaFBOR$3Kjgh zik*blJ0f?k!zd}W`WjEN`qyFMds{4J5pPo(kv^#bn(CXN`4^uM!rQO-c1|$|OqP^8 zlnOoQURtQcm!l*o26uxw&#j@m#r!g{v-nx!qq#Zl;0OyP#_tidvQjis>{@9vJb?r- z63&RHxUg!{G>u_#%YeNA^VFtv^el%cC;JyFt+1`wLvyBCIhKXjO9w z>G3_O^0K^$$#i^WS{jQ1|Gxq4zO#@@%>sS4ZDbfN*Y`h01$!cJidZT`LdeF$^CA(2 zs1FWraAZ)HqtMjhG$JW@z8nxKszKh?X(~a1kW&DZuRh3{o2(5F4aAl`!6_yslg_0b z=C&I*u%Q{Xkx_@&P#DbcLx2uF(Pl<_Zs_Q}qu7=z=lY3rHF-9KOR`KdHv&f9Z8C_c z*|I)OpgsZ}VYrxMItmAO90REK*E6zi5iUQpXuIn#`uy9itCibm#JVD1H@H{h!0tVC zE@Dr+FFF=dos|(jm-lv0C%ahIIN|QpYHkC31=kewM9FG&i$kx!abM7Zv!^>~Zq6`( zGcvvPf5~;hbMABw2dd(^7{C6{a+-fOPrLVE7mY?~=NqkVd-ur~-bBBL0->QU+!#45 zmK)-ugAj{Ou|si+9C2LQXDd3TJMJ@m&Kxtbz%%Q%sLPEsx$fKuRUfqV;vK#bF(}*G zuil#A0Kg+6-k%rgkNhmIy99ec4)dAM?3}Aa={OUo{m_LXS6z()l_QS~)92rV>LK~B zM5y`}O|Oi{6`mP$$N^+Ny(-q_813r!yAlRQ>R_je9z8$m%>TCs6yW9Ui<*P*03;B! zgZR(kYxI9zWZRCm>`K$(K?jiT!Dk@JIGpxF9iES-28tod-OR?nNh##Qiz&>{Hv!n7 z*f@khX?H2bzp>nQ5H`=TFBcxySf2G$$w)+BR`vRWC#h!;s_wBqe52hW#_EFnr;1pf z$kyoodjJT-&Y8#SbN1j?+*@Ma0%d4ABG5;*ftn~xMT!@?*F%x>ANeJkwU@*fha+u! z0A*%M*1;q5M%}>;^cvFlYFs$Zrp7U1CMdmpZII0zpMr>}RUdjb;|kIl0A@V~F`|G8 z>zI=%qyba>-S*A#NB_^yX$ny=*={aDE@Yjv$ikQJuA*51S%-y3LTW5|6&A?!Do_bd zHKiTlXXHzh1S(8LQpklUk@G^+i{J58GA1P#b1FKF4a@0Im1CD#oC4~NzvyuqlF*Db zr8S>baiQ-+0RU8JL-}SfM&uOaWzS5>HE$647z$y?d{gdGEW*?)Hq0WJc1@-Mh!5+< zvo%$T1htU+`cxW2pPZDo7VqV|U%wSd>&vT|B4bnQA2ABKxRiV4@F5g;&|TAGJp%rU zFlUH~J#n&;y)SoIfpDvWOio8qHWzAwTPK|)7O9wS53=u;8uSgc^QUil zR%a>io?+!z$?LegVF3UK))s-udlE*Wd4{$4sHmtq2dmI47M(}_WJMZh0+ve-Iu|aJ zW#O9)58_Qqe#lY|D#xKcY0-ag&>Wj;wR=Qd=Q)4ZSU56W@G!F8FnJ+$#=i+4UN440 z7<<&qkmVW<4!8YhX!UbkyOw)_!_U;_g?K^``#shb z>26Jdl2v8V67KG!!1_pPp{*KGt`gG3*9Jzw=?b1tV@IcqrJ?+H3%V!ahR1XGhg5)* zna12d>a7hC0uC5ngz9hb?s6dF0V&A-&>mpX)x)JOH-5GU^AMM@U^}s;ZLfdkg=iaI zDA)cM-g=K0?1GmIZH&HCxt(S~xFAGLXn8|aBx_pPQe(EJv*nv-*f5%IJY8LNbQxya zWbnFDoDrK{6>4?$ezd`zBgc?;FwN5Y=2pLY+Rk_? z<%loVmNQ))rrZYiH52qF&)o#w@`_bXs0lyF52IpCb|4-DWp^KfGgBgqnEt z^VCPwBHkO+_DGlB@EqyW(=6*iEtjXZ9`)mI1kFLw_W|rt%Mch9y4Ng+#V=uw2-;GT zKx@%iO3s7Kp$y915Q_rn(%ptPJ?1GCfR_%O9uAEKwQHB@oR&!Kjw8pNdtRYRa>6yQ zIRuK~S{}c&4jBiJIA#IugO$^nGAJh#cjvUOgkx0I5GYv)QkE$R(_yFVzr_O~s-RVS z8nQj5lTygw@i6mmMT!mn8lNqz#{X(VvDu+guM6JrosUZ@Ke-}h&-)*3FhyXXcjdX_ z@;&skyQxrNR|-TV{!phdUYAXNODzxtoe}8=clThZE@}cud=)lJE$;QSCKrZL<1Yyo z`W33`tc7+fwlRh>xA+WfXZyqbXJipj6SggHc7?-^#(B4PN#R*n$NOdn3H_s?Tf&ZR zxPytW<=GNmVYnPyTz9ydZ!Lu`yZ#{RlSYyDOylVEaP=MwMGWsh<47a+~I{Bd~xyOg77cUi36jE6S^4RuV$E9f$qa=Smi{=>z3TW-Xcf^B$i&qI$xPzgGpaa2*Ux8E#GVTbUBJ zWQb7Xvy{Cz>pK@?xZ_Csl^g$Gd5-;6DKHKVldBS zYwkp-6qvry){fgr#o>l}s)f}B=sD5`yBr|uP@j$9)Hs{mrp{cg2SkBY&Y}^V>|LB- z!B#1U<|5s=h3lbh?xqk?H+JO!qb|=w0c39jAie=$j&8C8dIzp@Z%} zRD%To7qcnUC1z;Yuy5zfA8Zcq;V~Y-G?Y&IyprcX*X`S}lH?FL!?6|7?L*QUgCak&p**R`mk5}Q^4=fPb~5UOsw8BDzJs{ zKjdazWs8o+XTZhe9;_Y^yU5l`*pT6LNp%uD_b?FFJ{p&jBH$9;Djpq`qHMUWgz8Wm zf-xuQ|0|@I>VWM*7pB|#2)X>j2Z?4p9$R@s`Hr;rzobvlu6k6xCn5=cj1c&8I|IG| z%3WFOSQaaL9}SXxhV=83FDgz&INKmd>&{9AF+-O4zs7B?U?1SrkJF=dSOFC^6a}*W zxzcP>gf#=A1Jjj?CDK-L%%f}(iZ04sR6Yz8J{bUnojj`;WNIk0ng4n-cv#ij*4Eusb6spOiC3pIF(xVp zFi(+iyt8ds30I|WesyZZV3Jhi6kTMheU!hr*Q?ufkui<~kqDSQkj6un?v9l>FaNecXN!R3PrT`~&_N#OjBf%<9wkeXGN@L)y~aL3DtQgnBJ6H1S%h z@jn5oz$00gsI@>YvasT>JQXWLK&cxfDzHWJq_5GffZgR(=F-r6|7;v}$E`$p zS>5i`75lGW)mu!nUFSrf0_&__80eoSyI}&S8G5wp9`UBg_{vL0)w?#!+Cyw6q5JID zi>h{$J;C;N;Ul+~J|NS0|BkEh+Jk~(`o!UvLh20mOh3D6g>*C9r6r#k87|Y|VQP9f z7kmnS${iNucVy#u{pFaTBxL^dwX5rn4431~SUU9!c({Y!yNvC3gvn=n^F$JPWUyZ= zulv_qo-}U-x0?H3Nj<=*YI0k{=;Xn@jWcq!)2v_r2<^K3IW{XjF|A?RJ%2!~?ldP+ zvD4q#Rb46LW|4n-6y?+7%J74qBs)&1KS>lqFc)C~j+s_uzFQQ(PA77cLfP5~bM+z0 z$Ipd-M8KTB;h1vQJIAKxzZ{OpO&i{|4!6b$ynWVV)XnE5$Td9z2tfuRMktym2Y65! zuXf@QHj%~hTXAn@Kc)r^ukIrcE&>O$?lhloM^K76?95(nRt!kTzhvj(A+AR)-MYmj znDZ@AB9wDcyjTA5mw?WU#FUb9{2Tq363Yy-`olkvexS+$Tl5Z>2RH0P zUJ_OZ{}erYT&88%HydY7^(@_>j>m;@PT~=@PcW?bERnk6$3MO( zUTkcPIey%y%x#6ivAT5;849I6T|8Io2??p(#WCxUyTi+3)y-i+P`PutTPXMqap%mi z(cD3JFkzt{oPqsm>zy0ckNbDq_1Q{uH2F-I)xSRv^)Qq*^(6N48he$kv|~9k+fA`4 zJ2#yYl1Fa-{p0a$GSO3+30fk%>3L>%)6CV37ZX>VyU%~D5UCL~CJpR+-aZ+5Y>p+m zZ4$T+@HUgZsg>Y)t#b#ux-IN=r+P&yTi}9LC1Rl-1M{;^V0;?)K9ca)_vB zUWMYN4H!{E*hR*-x%U7T+_y$AgniOR zjHbYbnEgUWj>$kv`bj%y?XgZd;4QN85poxN#XfW@MzcYjpXrFtRBJi?4}VE!Atk{( z!z^aG<}Y$o90RM2*wjA=9tl6Yp9%l{!9*oI5`ixdG6v4Otslm9nOgK+B<663^s_Q6 zbpRPm_d1HmOE*ztE7uqTmVAvK9JdRY=USQ2oL6)35-vDzDnDX+wD%yI;ybd^RliG` z_F?r>SQJ^^jDTDlxGILJrD)>;qLp zks(0A!#y?ku|Cr{Gsj3OiTe=rGWmVbH3D46YL&(j1FO{|xSabF^%gOS+g=_R@8>C! zmKACC!b!g}f3=^Rb6uXP@H%3oS%cAC>F|_he(noF8xvoHtz_3bdZ?rd*9Q8SzNU*; z$|$4G6rWZsXZocFfcwjhOO-;@1P7~jVTt@TClCrMW*!Y6%bLZ^?Lo4fO=i+S3P(406N4h0!BDh_s5>ZtsH(s3a>I{R@X zAwiThSZ3q=Q(uPKQK4%XHUI$;2HwuQEugRi38|8qo<>I6-?;c4?mm>V9X4)c`2V4^ zHA0hLeL%B@k~I?TQF+Dr({n)c_}Jkzqkc4T$RUVFJyTrc%3PA`XE`$BW}=L!hl>lu zazo^)Ea_F-+*;V<1U|{41!ZM?=xLLdQSpMuNW^=D{1*--(oh$a=bn1+DX@Ofe|#-P zj^w{wi{@ZZ?w7rw5+BH5`qS>eCgl)CLvC+nqY4r$=}R=<3t&FDf#1j?GE>%X4Clbn zdP%%bl0mvp7+&RAMMRdTgaBD(0dAJ94Y`H;cjNj@@)*QSP3H_+%vOZ)3XAL>T8K`!1_pNC=>1#dUOgBZ!x;&)AD@4`|>=yyZa;BA|KGD3*Hd%ILsIS83Tk#X9 zkHnXDzBYhe%T?ni-iBb%N05>Pa%hBcQf3xE86F`KQ($|hx$JOTH{yTM>1VpKf?k?m z;#IDmrd6_t~?ipa0+R`A~sM+XU|r(nKsckMU{MZVAon_5Q;S>Wyb_yIpxltt@O4#t;yuduB! z;2aAfAGOGzAAVkTQe<0L#7Rs{#H^zjd`QCm?)lvx3!TC1N6)utBtTEDIo2#W8T9t? z_p;Fzn*wB0Ep3 z(i&6+a6#aS)6Vwxq}_wow@SkL10rJnn!>aSs1+(kfrxfnQq1L&SY)9*uJ)U_Mp!XL z?%k8v7gerKl+OCvA}tq{Sv6JS7Lw{<;vqEspYY!+-^T>ZChR#6g7<(z+a>>opo1o+ z;%2{=dLLg4mRsdT#_gV^@;#w$lVG-r zKn@Vd2d)Nw1En*!$6GP9_yXXx++0z(Dr@je+kdSf4?@djv5TO=%}g{xGYt?0W$W#o zL_N1Pe(bx7tSOks_uDQP^?F4YFzbJ7Ceu84EaS4|7hv98`QKr)0me?E;_vF(j$M|)Hy8%uNjOBr*NK`c^d;Hq}pA-StD8}?aaiLlnS?_ ze4(IPyS^?FKx6$s;443tl{WWKwk4=6ll_XQ)<`I+b2?VWw=J!c!;(qWH9-m(>=J5s z+VGD+bqvBxecaTcDZ1cp7h@;q&k+d-9HLcL0+VjzW@aCe2$aQo*yR}mcy?@&^%MeM zjFycZ%ZAmFP7csQ8t4GF$PHu{(wH2jG@M&dwWFa|gSDW!u{@weevsF4EkLf7#`JsF zPN6lmP97xZcGhA&VT<@o=ndY1KKK3@RXM* z0-mq#c`pPhR^htNCgLHU0kSUtv!+lMfyDOBe}x@fnofA;8N(fzVOJhx!m9G z)ER^8|2@a)x+j zTpiLkFfphGbx5~VeeBSo7t`WK*Em9&!a8x;^1uB+ZI--D02fc4Tl^8Boc<^%fl9qR3uk#}Rq6&X(6t~ue&iX&+f;0K>U z<9TLv7LLYqaTyt^ccv>wm2*rniVHUjQqp{MoA7V%-f%I*FxOvT2snoG_6 znMQc-$sh^3F$*?6_1+3R5^%M^{t76V`JZ)m(_-n*;Owjr%H#X#%Lzk#eArgC0x|$f z{5!=rldMIAm*M}0IicIik@=NK($#ZhUvH$@uv=HL*rz-*QeTvzKXqpDoWvGAu)3-o z#mbaPvpO~0oMbLXd*~-|0?)k&KPIgDR&f~3(Gw@1d^I)eYuVy113+5Y7|53}`g`_7 zacKXUf^3I)F5E_YMuESSS8mb$6T*qXUbT;9T5O>_(%xCYk?#GA+$XB*xoPFrlOsy+ zPlErY)*}bpOOmy9sC;4za6}v<;C!nr%}rUtMN9YqAMUHlcnVs0_$X=zaNdYxAo7i~0${D3lTHj5CcJTOLFZqhY-xNAPg*jv zEumZkILC{QNP)r=+~q|FERX3zQ2dAbdN6K~!^!TvedapnHlT4_^Lmz8dt!?Oh2Q?EvRw6Vqy+0X*Cl@6G-9QLRG79Jz6#wVS3G)9)cOWCF0xbVGiAOnC5mt? zKu+~ocM62XJ};-;l4bQcNa}>?NqTUeoz_irwYyOEd=tG>4;9rY)=>1dJ91eeJ zrNylTc;xu_zDw%?k&ViF?(qV%^iS=8m3*BKLeTC zWwxvR>FE?_X79(8!VeBUKdwd3_vvr5ATcaK4?V0*;IB62?hslzV7^CB#M@f$AXo8% z8iSSPa%ZRZR(hN6ICJwer|T|*8kv>>;CNDH^(ookuKMOAtFBz(fAz>s`RP(Fg&O{D zz*B5`HISH`YgF9Hie;9r3lp%Iw>(vWOUPO_tZ#l!g=3tJ_!*x6L%sS)c1hGkg9wR ziP-zGY)62yBg&Fn*m7P*-%*aoD9B@1OV*O%Cy}y@M#7RA$hAfsXw?e=BK$5wYPy1S zVo1w#{GGaWy2dM68*j`il(jfd3Nig7y0X5%CdVPfCv(D<8`Q4=YNCJ68fMM&ngnMu zhfBN8ngk6D=?wt|vuFgm)3s>5>^dAz#kot`W9Q?U z&;INQ?$(B^R?pWkp~t1);tL2Z^NRqVtf?8GJ`eJt$IVyHtb)~s09Pg(mgsI4Z56!= za>YHm%G~I*m@~apIk#t5S^t}KE)%K`@_vZEB|)XxU4tnz*Q1T~j=JS(4d2^=$3J-2 zz*-3q5$se#JyE5g4FHWVWAL^}n~!;1Eg|owyB(h3z#B*q(##xZZ0*5b-t;%IK2s&^ zQM?S+v+53-}BTr>Ec4kWqO_a62b;+Lio70Xy;y2Yl3pvZ*&>NANish}NvsU~H zDpXp`C*CaS?*SGmnup~MgHK2Gsiz0)jT^tMzqrr;U1TNz&Y_@hJ^jRY`1c#``maGT7qFTw6 zW<}M^BIX0gb{_jGvQ`w(Au9xPph9pwgJa(7yUL5Uu9}`+&Iym8y?@x;Edj`8aiPV3 zB9ix;+aTFP5Yj=MmP}L7dwf9G!5NM`E+&0o73W@ZF7o7uy1KebrO)n_Z`f}8c^bRX zq9l1S`ezy&t8;~M4fAp z7UmeQbHLxSvxJYdz8eN-p{5{j*fdF%I2Eb7W5&X9r6=`WLG2w0tP;ULTUcZN86-q< zbNh7!N>RE<8!1|gj4xj#$Fa)nspKNb6R)>V>4~};vCn*P@diqIiU^gDe(@>s)W}P! zZ?eqCVMtx*`L{MV#st&c?=!jXKQypVyw8KaW4qfb7Mh`sK6jD3H}BhZA3~a${8Hx# zv%h4Pba?+u6O3Iv@-|W!RQ)tJA6J=-$A&TeZbr0y5{s z@i=QFYq_z^qw9}|>y#$fTP6AR`~Ct0jRPY;;;UILjJTVmm>syACX^{rgr2?@f9fOo z!spTb@z+l^s5JE1^n^YpdQC&*1Tz#LQ9 z>vrYba$aaVrfRh1b~Ndla^4-cnlaGLeZJXrWU*D{?z&Z#QT=}Ti8;>mq4{qHD1{Mc zT~A^{jB6ROJBU4JjqjV9WLA@^TiB%U{};f)A!VMsj3!#!FgW-SdXD zKe~qQgc#~eVeB$L`cxWb98iqk8Xi_sy& zK(*+`j;1W2wLnHo+j9L?`K6`DmdS$FpKw%s z%{$!9Ci*9SsHO95O79jzIg8JxZ&x!O*>5aCCGGmBW_RBsYWafYl%H3+`LXJ94Vh1? z-BU|vtIFS8THjJjN4572SPctxdP1{0!+VZ8!Sjkl>GRfX>#Ng>l6xsrS_>=#Z!G6D zhOC%YxK0nx^_BTJ6)I`kp=`Hp(C2Un@tVqwMngKIn*&grm2Tr_=Xz45{CL~qTsDm8 z8t@i?NOCOTzU+BHdCfs4J+b#QfJ5Nj)F_!(5X_ooa?|Iu@r!ck)R#oMSSr@%j&Uwi z&rVOBNjI=}zXrzU?v^^rlGgVHVn+88dW2e^oZY6oYrBA13@HwaGHI^aI;wV4?sSFT z@x!2VSxfW35cK+eo$P+LesS@Bt7eo0YF?5sk3lHUCLXQF;%Ph4+``e1Q&R*TA{JO+ z7o~)k>mBmeOi}4sl^ru}+sEJxsbg?C|LCirf0TnT4y2b0G6_5?<=ACllv@T^$Fck8 z-1hKvYVNqNiyiH%A^UC5tp7>2#qP6zJXTm##bqSN0msgOZVg^dmqGRyQSffpOrfa% zvs@ROyI1N64V|=LwxQv&IkdxjN<%5>*TG9;b(ywMjC!q;0;3?xur82T}+twG|b6UgF_cZ8!0*Lf`)|FX9D zq=rno-a~w?qX$vpYCz0|wjS*n=s#5$+*g4O!NX#>KkkQ>W21`cUUk;$d}n{Zvcx<( zlrC1dMh$*qs_t(HH04z*b_`7*MLUsi@J>JgssyJ zvKjV1ACymGprs|?utXd^Q#su^JN)(i`}fOp;+dyaWb%$bm*Q_@K2*M-N@$i!2)Jx2 z)HQTt?JDQ-E}#m(&js6UR(+?9@2%qT^^ z`2SRwv+t^rzzW+7I~KDt-#fks@p7XTLT&tgT=&|&|GN61m}~Lqx_M!X)w`3HctMjU zij34cTmTz_&{A`EIcT_Me=wr|aIX&geXJ@Y?Pg1*Np=D@(M+k%ejyZ!wOJov%}8pQPzaWz`(nyJpiLb=*QY)ELpxCW~Y;!7j$ z9s&nwYZ`93CqwP!bfX0hmVIErFTC)k#Vw-wS2RZpiZ65e+4UL{IT+FDVsHk|f3#a& z+g;u*^zFl>qD+@l#N}@Em7JVxIy?O4dN3r$tWo{~(6~;0)ErBjhON^Q=ezo_xNK+NgmUEz+88a~(Zg!ASA}3fgxF&5x@W8M z!pje?F0QZUf_mPhpL;WF4VtjO%%w{&n-66%3JVZ>@j~#ajxKwqubtImNW*r#;kKX- z3Q0%`gB%)V{e0p)&#A4O46XSz_p!mXd~|PsFRB=o(rwzErJV!5sx;~|A>x(j&lukY zq|K9K0>lpt2C=uK3rM~DmXB2NJmzo|>NA_no=K$dpv49(n`%!!7(a$W*<{h3d5-n9 z&_y=WOz^|yzoHiZJgRBHR*ee~gDsRf@-B6V8fsJi9Gv$b=B7zLUv%Px&A$KjMsd|V zS&4;$2(U1{mb8ChV35LJ2M(_O|@xQsG2X)(nK<0_*YFLj)* zzO$un2GOUDE!CQ^p^L<+Q6V93y%E8JIQ0?x3&~k{dKnpAyL&X|dYW|b%$S}p@J$eX z3&Y(Bo{49la;B1tO(LSc6F-2qUnOS?*12igp?s2OuQzn?W!6gdFwnQOSgyx>uqEdF zLb$VFVdOdj}zVuqo)g3-_|)GZQ{#gp*eOOMizR1e_)^G zPsskqR66$qAF*e>J@pxHI(z2R&w3~?9GLMUInAq=Cq(3_G09_GyRQs`YABDuw8|z` z1f~%HoQ|7&Zk8yTNKUNKj6#Pa-zWB018wBN*JkTOC*d4qHO_Klb&ihy#GD+6vPIFS zQ8M)&zfj-{N3C+DJB-y`Bj?N?aSFYpQ-mcUwt61Kt&whXteYe?Ziid0qu)55*LpFA z^uq*z2V|qe z9v$Oxu){Xx*PmVC4?-ETH<6(9j3u|ha%9?3upv7`nkRhX|ipZ2Pz6zE265y zxNxpm}=2PuuqHt;ArdV(ZgF^rtkl)q&DhWkwp!tQxOjS5wQZ_krJ?=+G#0EUl`7 zx*lbaE{I!C#bE<=Ttup4nKM!yYbpqgzI43FQcJh?KhH7zYztG&MVT0VCbuvAO+%86 zfq~3&Zj}`QH1o@hz&R?*9GK1t9@4WXS#a2>HR`5Qy>Vam?Nz~0!Mm4yP&NrsOhFuy zmhZ!qYL`EG&xe>8fhn_Q7#7CTl3&jPH-dnfERIpDs@9kV9+kTq0Iehl9(6~+mO8d@ zD2@_h2Y_=g)v`5XsDge{9&tQZ5TW&LOgd*__T^ors$Olz)M%A^?nCUs(rO>*v_wVf z`b8LK{%(m~h~D}-TSPn$foS<161(ODlyvsoP_NVC%#Iims#>9c^fd}+Zf;LfLg7bo z$Qn@K%IE-Vt@)3g*Hs6`yp<*_{YysbD)Hq0v#_t5RH@Ao;kPBtW@HG$_TBba@Rk@*3n9O5! zg(8V%p|QqD<2b`Aou~wzP+sV(vgE6E_w+yR)Kh0?Ovzdnd<}acV{t~Sn@oE2aLlZ) z{#5PgXXj#+`&G&VzLfKLHT20})%Jlwy4yB)&bv?7H)*L;`s=wPem)<|cBFs-EnwaS(`T0R zxMlwfnyKt!%N6fRU3+_ok<7~S;kRGw9ls%$RnY;c7`>#d4yCbcD6#BL;$)00>0WL8 zj_gwPu6b3b!CfZc-QC+{E%+ZwC%uwSjKRq=@J7X3G7f}b5+~;{YO-gnJOmTyJj-M6 zD5J>gU^SANlajdCPe!vXP}??D7hdrBW4a&^(z-nQPf0vghb=`{E-L*=J#>cL433Mn@Z~+Mt9!l~GK_!kz1so#`}GcJ8aWy*W48qm-R! zZ0gRun(c`?N8`E1i|V)txJXYa?)r`kZU0{atIURITf!QvU|(=+?^A zu8q*UKTx1hD6a6EVB-MMmsxj3*#dHTc${4tmS33YeSXClVXSO1>v0_p>7Teb(b;04 zpr8mUS`uON>)+bkyF5SHI+v0*mJkdvek6B%VE*ZrqaQA2xpNtVy-|hf{wv-#Yg7nC zZkn1Q-KH@Ekckn8IP7_T(@bh{Q?%ex$k!#qq}b?Bo}PKfCB8+H)mi3t$qxaay2#9c zu7Tp`>TKWVbY_1$&@`B2zPfp}soJWCmC#RWN)CGm4vY~2;Dh~)3le(nejev)7>>dA zDcsRclPk3{g^ryiT@X5>upd+>v!hx}-PT5}@Q}n^T#^cmA>HSV8dTVM*as4-czl?$ z^z-^=1a^+XhZRKymC*ZfFfc99z*c@DTyP@OCC`ZfB@uL#Pr87q=6(IU#j$!2Y*j(Q zohT#-DAPT!D@SXE+CMECXHp_x)0IeDb&t%7A3XI)jF?oT<@JA_Di8JE;eNyLe#0lA zzQWqd1oK!~<>oFS??l+>ubmennRa*fY$oB^qa8UgAd7EXiRZ`#Ch&KKKJiXrQZ6+% zm>{_}D(3WgS901c2=aMTXCMS&ybDX7<*&+@`p>h}pm&-tW>WqU$ozKi=C3wt;i;+C zsj*I1ZLE}%*xZ$`kdvJkNjQ{x&=!CSu~*;GoaQliN{c<2i#x`oBg*{G!)Ve4O(dpb zpwJngByIKmhk0HZ{(Ep4~O=Iq8W!s%RL+y_tp=lz>fQmiOkW%uw}TuchPv z$eP{v=Hd`HHt;V+?QwJbKy|Ua!nS3u`}R+wzu!KugM?Ox6&HsoBUOX8>bb_t<e4i~2M#N*T;o0PS*2 z4AynuDL(sh_lz`yvMnw>^73~tDTv&@MJdzh1G5T{PdU{rS~;$}k%|`~1oI*%>lp@6 z7HITYc|}Eu2mGxxm%HgyNCNtQhHx|fuf-m4PKE;ii+$h)p26s2JZ|o=fK*y2?xgGE zAQdo@wFs1xc>Xt z)**4tSm1y{L67@Tv#`4e^0GI&P`2jtnH|$S@I$7H^`+NV_^W^cR#W=0fAiHyn#4B#X{5IN(y;lH&VqQa_=0+U>B2Rp$q#7RaHFdM9crj%e?xNi&@z3Dzb-5 z0oefQ;QtvtvFgjE3tyv-RimR4WAkL{|MO8^ZJyU|&M7As)2;0Gha>+PB3Rcd9qdl8 z?JG^Rfy!p3hFd*>ko`53Y#gK(%TqC=4~@;vKIgA-u(L z;DzOJbwWL)3ZxJa5J@`;!CZ`wVwF~-0MFfsXgB(Liyiq5Z6L707pV7^OH;wM&ysm+ zSGN5&$VI%DBxU}7k3aOY{TcXD3+QoUne*7!Nb=R$nIg9vnFPjV28fQt!;bo&QlwXw z+nA9^711MC@gqDiLI|~1Bn45|9hx42hgm?o=&U+7oWbrsUz2k^OXZa@a$+EI3)HUf zWP$A1z=j>U2zFdomE1ggmtg2A1qJ+_sC4J9!W8L`N~iM-%pZTG=5(V%TrX|p*O`Af zn$Kum4`z4%ukSLA2Z1&R-IJ;OKki4xT(YxVVB!BzK(WC(^6!g+JR+D&nA`isuYc6p zWF0xV(SM&~e`-1vV|H(cmT_$OW|8^(ZW~R(u0ZYIi4Q$xOhUdib~w_=C~|<>E-n&_ zm6y91|GiOnkTF}0qeGxa(pF!#6}XA~&=8LL)y1wPQYc`qM9L|MEQ*S*ut+qMwxnNz z+tJ$dP1PeG@pr)wLTbT}q3`qImcV|pDw7yPZ$fY&cc2Fm2LYmqkikKmn|lK_rjfB4 z$G&-6y2!^v##_HJGg^^uF)OrdMRlO1R{76*ohk0iPlWUfe?HT1t~iNAjY7j-@!fbi z@LSqODiJodDZn*KP-0^MT<4z;ocawUG@CW4S&r>@NkxUfS`uYTnBr;p_fZrzkwjqhYvuwYt^Yo=F1iEE7IQ55 zRmmSs29JD4V*&|Pri}E&`uAxOX5E3tY*mg9)g0&itpC1RF*P-?+@Y+?U*=ZB*~qmW z`9WvMqx2>M(a+!4(*W!ALazNXH{*>90i$~sNjj7&b+q7}Sb5`hz&v~cE7ro=LA#7G z-QRJufVb=%I*oNxLq`r63|R_HijAGkj^KZ8^tB6+#_A7ZgBVfJ=Ae5X=RbcMG1BjprQC`F%g1=gs3woO@=+TGv|ZTG!rpcA{0y za$G7*6j7RsA*{c0lZllg{huF2oxMKpn?37yy1X00cJuY?*ZTd~BJ;mKsw{d5)m+p0 zE6oZBxPN^$>tXXliI@3BZ58Me<>oRlG3A36E|h)uuE)yq^87*F$;?IdfZO%t>~$EB zeM)g9ObC9vcO#&CWX;G)_M+0H>(kmF8-Z`=&Gz^85j+e*#iP62n!Vm)uACZLy70&L zIN7C{R2{CNTkc#G@yiniC;E3$s5iJ|kKUGtEXiRwO53Wgl*h~yw zn{~~akod;jT;%4=KkGHOb9243+@sXmu)n|Guy@7u`0+md z+4Z#3tlQ1N&A|;!R7DG#$$$D?P9||puN!A$b#%)D_Vb_Ro;ygr@dua5dVFu@ee3rt z`5~p~p2y&nzJbBbXB9X33+EvjWNr!4)jrMlXMKmI(MZ*aA~JKrMJE8)i( z6db&~NY9bW4&Ld=>b9n^l1k5;5qX675{miuN2j8F2e|h5OzqEn>yOJl05fO}VGmvd z_ichTD0B1fNhJZ=cLRvGt(Q4L(8KKo&lz;7-5Z_JUcI$QC$*fbM$1vV8l z=X++LuKq*x=0Fs*d1k-6-v?+~=6KqHv`j_v@kxXA4bwo~mwzlv&fu(DTl8XlpgVo$mv%U;zHU zSN_d*dA%C_ubA-XkB+to|Myq&t5^E3PDKAo+kulyF@6MSecaD7+t7b(y2aE@g!#ji zT)*zc?0{X)^oBWj%6!BEE8Aw!Z{W~gc$Fl#$Y%tc5eIwX=*W1C&Q>TB-8E7ZvH|4S<6A$pPgxa?fJ@ZmE_$ldg7hw z9PAh@;_QFSK#JxW1QW*DKE#HM49tXh8_Y)|Hf-e2s3XC;J3c7-GFxFI5&Mt9;$s4= z+6Hd(CZ0#(&(a{%kl;H_?&#LMo}c~)M%1{72Ggo0%XYVAcC3c}d@IOO-FLkyVV|Mw z!)%sX8{LloJ`fVn?o@w3&K%3&N2r|ZVsZuQ+`oba14#%>bxJcfO!#US@81V*e}Red zNzLw$|M?^VCPP*2PQ;&4hb}>XL!QL7V_8CWx}x2GSC9)-L`5&^%7&rl<~y4f)<1C> zTl78VVajjA{`rEXXG5t1uQv=)LapW&X1t{k(Ec$x>VYWoTM$GE-JaX*H+w8I^#{V8 zh6C=K{Pn0r(6>`V*g;W;L)?yXpnIX_qUJMQoI2Eclg_|+9?gQ@`x>BoO4`tt}-YCV4ZxJ)A> z{#(__+^)FyKh{od4faG+Gd4~h-#&-ZJtNQI%byV`?NgH|nF)M@-v|tFy*5yz6R0q9 zwOq#kGdWUFEM4t*7$}4`tQ_})qI1z66aZ$f_P;7)JpadZ_uB(tj~2HIEXhHZv|!I9 zQsL{aKnydJJUBo5W0{e>08f1m2XQDFN-dvH-TB7=fB#)f&!0%zJ3Pq&8vq7~gE@a@ z7yT)~kNrvR&F5&k%u3``fiAcLoswv+Rq(%4u>(`tN|qnRFj2(p{@>uRq!e|23kx7^ z+D9s!7IWSUIAFf`v*p%NJYjx&#ep}Jf-nd4|J|bKRM6} zfWtRRN9tyOP@3ZQ=Spv`QFiiEGXJbgBe0(SpKX|F|MxEw&cS-y-wgf%m3=B_Na)Wn zmc60_#pq)KlidFa*Fv&Se>)J^*yz3La)i_b$@(k|Zl|eFc!`vMP)rE$@w~I}(l`<) zkO`ApUJn4%8CS}5&3#PndOlD8XEm{-@CIS#I~aj52gkCqdrC;5J{ z3@FJ+Y3f@tzzCT5Jvtgx%^;F?@P>qLKLjB*-%|88WYq+g)a}oZXu7#94gXAE48UDm z3h3I2=_i}bZ+NQ+p3M3Ns)b8WjM>JtEi-}BVYy1%zraY%DZ*9n*dw+-DT#CLr(S6Q zuC;OhdvvGaB@>f3GISu()dd6zjV!skH^=lyMe6c$@eUKjQPAEV{e(~x7OI#5olxU* zk!zsd>I7Vx{2RG&SQ&AVz+T; z@s}U%CG5)sBVkwsVOXx?ww5rV063HWugi6VdQo-gH__pjIE~iskXfVa&it{6mo6Ogf!0Bh5~(n!53m zlbp5@v-9QnA$2`{9(10zO?2;l#WnU7!K4*OiM3N1mw4RRBal=C1aPQ;)Guq>T=Fc~|u4oy_zvb9VS`b#?yH}Au7z_0-3^bNJG{>8+ zTHP5)j1N!Z7-JMG{E$>CD(X4Hh0CsDQ0O%)LDeRD@O^78(O$fbGGZWVU9_v5jRPly zuTxV?^g_hYJ2a)ng!)LF?bhu~x*IC^IvQXkkle~Ka zbznArg{M44d-hlFQJ)0-yB7b3Xtj1uKu6C&Fj$su;D{4Ro>acDfb-MI+cQ(lzJu1{pIK!xH450v)`J6o7nQD-CvJuhCB9}>_!|WzWGI7t? z@m};9$)%@-e@}rmqxqtK-wQ*HfVtiggV!G21MSo?4Bx%`Ig7l;yU!CZT5djsOJAo{= z93uC3D$)EvPpL)!ZcdSIQ?;)T?TC6GuPp9JQ0pK*c*1E>^0hnWRO@5T(91Svn$_&` zDzyya?eAcvxTRS*QcR#Nu(nmNSwXDQ7Z)$$nd7%u&^-0-Hgw5rTLkCr&A8dsk*U& zjL}nk`!#VA0I$B#kVu!lHBXCWnXLN?(L17PWk7IT|yE}_4g7V-MSDV`& z(yYJO0Uw)x1ie1oJ|Y@P203=i-k^urAh4H#^YBWD@1uYjd&$rQ_GIUY3M*wj&VhES z*`5-rG|wxmf-tJQ0$S`Gz)7MI0-9m0*lX z8Lr)DE6~0aNjtaLS>#H%VYSF#HX^sLPG8UzAZ_nz27)DjGDqLPb=OCwP}nB|;jjn+ zue}7>B$bcjx6DvRZ?pg;lxOiJRbAJ8Yp&pd7^4}tbFsAuqg%W(RTvGB4%<(O8IGca zbJ0arNpZ#06J%pS82?3rjAZxIz`UW7zdoNI;I~gDDPJ+vmPz>&+f4^Fm^}Z0Mg}<` zAm)7@-^Py8tSxo=82-P;&|=HQF!-P7VexPDpm(Gufse{Lm0T5O={?}REyO;Cf`}sU zyFqa9Nfp{Ms+8Gt!aDZMn_~dva^W-6w_Otx(5_-w`+JH@pumy*H)}Jgu=$Pq@R&w% zrjn}uNT=b`o0y{Y`&c)O$lzdhZ>-`PhVxqB@#LIgM)x{H(Y?rqKE@00IEldD6#DOI zH)zh3LpE9b9HcSb77rnqW$WHXzKHAmmj#0dub`61>LKyIvKaOGn)RgICpkzoZHG-= zUbE+>8w#)2SZ9PX;J$6KK7Pz07^e+NHVppn|6Qg3K&z>OZ$P`7ulfMK1|nhd#g7GZ z=0h8Ud5kl8jbPpsH+BGS6eO3Ug9T`Zwm5MKx!jiymR#Re%m#BGQn+ zMuIz7xSU*LM)_r+a|_z^rH!Vxha z9-?DLce9##Z=l$x@N>Lm+6Vt%MG*LeFYbTFOR%zRFynOF*Xy>JKZoT)FmK}VrPXIe zNqjNxcEY^Q@w(!BDFtzQBfZ4Z9zIfr5M4H>8j}v*N2Y=|?29HD!;j6{DI1E>o)Q^! zX&$J|^^}gZ;`9E2y{NhN$kB3qV5=*SG9Ur!K5y-JmDYlt5ML6q$fT)C5Hv|KA-td( z3{dq6g%J(<&xxhTwRbNI^NEGow<@yAYPrE!~a2G@U-)0N) z+gm*To7o_?keUAl1Kh!=pCK!1^5!WH&h=}oYS`l42r){`Gq(HnN32rEbDcNU)%3p3 zUz3cOuW9`b=h&23yUy|h@eTenVZe-NhgC`5E~!Sj8~Tk|Z*8czG}1&IY+#_2gqX_$ zDyfKbUk3_7S2cyfdHPgY+ER&U(o^2J9sQQRzcD>TT^A! zws{txmR*aBhfT@Fw^2bc;T6#PZw!#L0JZeG(2q}_R9D33HJ|e+gHg*94M%V1r+AzH zXhzk{<%xX|F6PGcO{Rk9nPM8|nfOQcJFA29cue-^Z$f*wvpcqg{V*RVv71f>jUQC7 zRGTd)opCQO%HU&|I?&uD8k99*@K8mI#Ul2@MP0^~r;kyCjiwh5Wj~S+YOaNoeFV55 z|bC+sgAKB*J!*ZS=<#lv@bc}&a|L!vvL#TxEWA$@ zw89lBO8JHp2x{*p#GDF|ut3%wL5K1!Gvlo;6-ED)MM8xjAl@?j(MI!8ah{()N zezfzW(r$_TNIjpIr8fWdO494h9+VTxfWzk6yP%RIG3%8+7uMvY3nvk#s!Tm^(OI)~ z4WF8ED{I|O(;nD#=dWI{_mkp+cA3(gA3U%Z`y7^mK`Yda7IVySkol2$Uti#rj^%Pp z`2k_(vY#obJZTI+gR|=O9A`ImjI0i!JbfeL>2Y)mJqRRsNFrbp1@XcLKKyoH?aMyO zv|J;*V!R=Vk+#v8GX$KG6Z>wIQOM#ueaoqLnR7uG@3Ld5;+EOj62u5& ztBHRhvy~B=n9Kl@ConC{M9BLp9y zw_}ipxv^V1RP#E8C7w1WqnDr^&?{0r=fbf68AnS+p6}-fx0#_<49AX^32nEN!K4Th zS~}^IbT58ZX7H@}RXl}gD_QZO-)m0x0ZT{B&XyG^r=oaaY|@Hs_~j{twgs8M+$c<> z&gG@J6aunQx{ga*apc50pMMq&c4uIVg$(v&F`M-r9y`socwf96uD+yF_a`K>-1yP<#_WgB34Ozw@-vYo}9Pfr$?5 zw2P|>7;QyJ!lmg--s*6_!p=AJm=>?Fo#r*DXq7JY2_`4>#NaH89Jl#2zaKEI7zVn)vClQFSRGThp|djSa?%Zb19 z@q;TrSuYNHTS{9O%-LtM#o32BFe_Lc`(u-uCq6#@Sbv7E-^XBj&qyQ3!4H+?4qC$i zA}>oU`j4B3fIsly$6&0zX2+5KX<3;W8X9-w=j#ab&*W#OegHGg3>7y0wY&bcTNQTW0+}vKCznntk7j%He4u9kJm(Czu2xH zzJy|Fx1{7F)ZA1FYhg`w%)!tLVIZ1nP%&UPvlsxrMm@%!W84hDS8L$;`?WpEOG?g; z^+o%|kZ~P`xEFf-a(d*errH`mRSKm0BQ2NE1P}Xd@ucE2`5GEa2c=q6S&XiYFANDH zG?$3^QOHQg4EU67%I4ymB55kktp;8+FeaCLddG!jSUzLjLKjA*tU`8{K};o20lC0w zLcb&wZAF5JHr?zIGp_eOZz53br(BND9}B7tS*T=)W2b~X#FTmQttFO-;jHAY8cEu& zc!^)&a`_!vWcPrl5_Ji4ocrOuG^=)WC0=j1eq!bO858FFEs*CM+D|vNK~y!xo&_-p zx_hB{=PHafx){ao;o*Ca#lnu98I(B*c(9JY=(<8_h{5Ti>RIOeS1|JoaHuH|0rvvE z0r!LJC83A$&YWs1R&(3~|GMJ?9dQH-nJ3CBM*##!lsy*oC%Rmt+;6n83d2 zu!N@SV#xZ^Wz$VVyZB0N90w)bgxWoLD##ntzUADwZRA2TUX<{Wxx5ZbT;b0cp(R8V zWD&#bF+TIyF^b1Nu&33+?yBJ4C~8sDu}+>XMo?m)+E6TD4C3O+C2{U=wylL82u&s9 zVYkwv(Ko=JXOf9`1!JG$Ee8m{Le4_n&*a|PB?zLpK*y+WMh#yM@(s#P)6EMi=2{6E z$c;%82*#C33>1#poah$7FS!?#?A5zy{NAER5W%ig2Um)pC-O;miFDQF+&)>K+oPVO zfNrKZFD5NTbGwOS_8-~dlom{ugIH2u5cR$qB<1@B;T#bAc|S{!@~62=A7heyCnu-o z*C2xbCb5WkD6ElE8l?CZ3krCqJ0GiU4t&;EqJqwlTJp}9SSdJgJt{_Ku6n;n<@eC_ zle6Im9-AIARdIU2dPkNp2MJ@$%P`)UV(&(IT-un<7&5c_tzbU3BI0q;97o(-e*R-s znA_gdELZu4Kqts)zdi_&wON&mq)hb zfn9CXe#MI!y}0gS$zjh!G^O)Vzwt3%Xp{L+%hO^@Xt)pGBc3%T*=k2%(aW8f*V7;< z-cdzuRk;(3av2yzS>Ie#_89ReNnq|oU^Z)Bz$t1T+1Sz8^vXnLt*{^d_zJX6L7(rt zJTw-=9}T=w%2X9yiU*2=DGEj2C01yn{+>aoNe=ElS=G@}H=!$`iI8(PUNHCN55VIj z>*Z++*C91_TXZ;`w+p91oHR(99y=X-GiID2T`;2#@g&%kDX}kUDj6@=z0323&#pLf zkNLPNfbTs?&VB9YP0CI1SBXds&0mK}irz-(;d0Xs@QWiCa~G4_{Ib%0SLu9jNqjh| zBoNw1jQ8?lu5_6|T#wO0j940S#@=H30FP>b@7mTYpQ#^IDR=v6la7JrwF+zA0`lOY ztr_Yn=ZZHTDT)9ZeiF~=drp}+M!p4hb~LxGq>_fmtq4K5kQFia&2$C`cx9qgqU4zV zf+_xWIB}4ID_5NqE`}b4NotKrZ_^psUuX!$7LI;chP0aRG@EgwrDkazYn!9laAoJ#!HuV?J->v+Bd@4czf|Q`5;tc zi)eu`@$|R;j7V@T>!r>>sS7-AF*R){CQhjojnbuj*`=CiE6HcPU@hVVGg+uNnrQ2* z1?8&A37YKILmgH~?Jka>m?erM#V}kIg>VlavZAW3K1m0Y4myv@vT|&dMo4@x5}cv+VvH^}Cfy+dDgXY9IX!&~tc&yZMLX(qxuD<(46lV%4n!*B z$qeEr8Q~mDk)3l$kjPI++`Gh#6I|1!#(<>1L%^fa*evdfOu%W&D(?^=mWV>YSyr=U zL^4R%QM9Yqd-tGeicO`ma+zJ&eK~!NMN3IRksHQE9lcjyF8Qf>&rf|H@X-`5Cv%nH z1)s6Ss`%({R+*)3f!>DpZXruXG!lz;Mnm+wpBs7Bn+PCqz;EkA(9)vh{o=#zPA#wg zOtkuH?t6FtzVoT5$eUTvQh-F7-IlMAwoyybYB%`KH8=6cefMa|F6Ia z`?hBP{qKLYQ;BTYXLs%tE6PE|HU8+RQkSGbd!wdCKo`M-CwXlX_eNkcaf$2iZ-CYS z)=yWk2K>K(fY+@SfU{shkEU#J{^qw#5`64c)KZSJZft;GMxX4@TOHZ&f0s`=ewTls zP4!P>4~icFzG3C<;zzuHx@G|k3~fN{cb|leFy`+Esb#YQkSTfo(MOp*WylzuXqqAZ zdq7LF>rk$cdCp-EGWmZrQ_XU}m7~AE;O}Mog88JELO6Y3jIkO@oCbTflTzmbL*c(| z7Xg74M{5@^WkaQN92nY?lGTfW)N6R_A}hARaFS?Fy{HL9jJ3 zfW$~s{4Pkp3S>}4le#%sco65(x`HYzlk0*?Q;12_<-@ucZbc4a;uUWjZ#9{>;SNu+ z=yR3JVyF6r_N}0AhU{WzC`H(MRM#7f$@XPaGA2S9LJE+0DFGttqv1g&<|=3?+nhcG zvcOL7%ZK9w4bL*l5dt|{q6iQk%%&ERAAnVO4b)iOi1f2?ICww?$n}N-1B8GejDzSm zSF_-L+Cu5Jp~vfSkT`pNePTUW&jF@9^kOF|30uVdwZqx2{eu&8Aft2!Ek_eJU}X$V zE~fUI6n0A;qV-!F1~=`qSJSgsK-_ZW)Bv=zZac22HL?nfIyvsEzB`qYkw z1hj`if7nx0Z|}qD=padwAA{E#Hvt$~t-*`glOpordTQ!@sz(`WQI#k1X9FH7Or$;{ zb(POS150ynUv{=t_(KXK<^|J}Uqi(xboqfg-Q?d$Mq-Fazq`rknMRjnc1QMSx_@?d03+4|nQE%o+3O1`ZAmfb>%; zuvA)*bT!kKNtAsQ1e@&7BCQ- zhQg^yj@g5WWVjZF@=l5&3k0b0%1{LR?I$;9aA5hm(?ZMEH3J;9Ldhk zE+H{-=imxY4P#Fw8=rvSYEkrhG28>5cs!{Q^0&GXG|=O~u}=5hJ%xq6+8@@!T`ZPR zd|`Fy%dt2FmqnW_jHh!d9yd3G(!&TI$f@^sLHh*~nxZfe&>67Pl73kS&ZDIe+Q${B z!>g!qnRQp1=&`&M*tZ)mIBhHfCbkKjHr)&Y&pH{eD)&aDi~heFck}8GA_mkt3OhmL zE)CJi>r9OzxKX#~><|;q6Q@_O#1n6Cd4b}w-IHg{+?u4MN8>%QJ0&@QH4ucfZ9ufqpJOyP~Gl~Z=Xr@#p>S4JDIF@b80 zU=U`t!zDdv$mgAu_*_t}eqpKev*nLBk8kzgGx0Pe*os)l4<5gu2t&@Z;6*;0OuFp~ zHX-Y#|LzLL)xwNOFb#iq1u^I5B#?S#DlS8hoeft!p|chUc=wy)8WKtxla?#H*AeL? zSFSAW5~t4Ns7WXHy+z?vl{$ti>qQcswZuJW)5T4pXTXn5Em2vk|BN>O9P7wh&)~F0B{A?-N&`=2BVto+*T^Al zH_k2Y#IP~_{3%lLO%C4Qy}q{}$o%d2$p>Iew*pagG&E?h@l36A>eZ&1l&Yi;ClK8(`y7>!z{pjH8Ts-uFx|a zv@ z44F*JuP=k+GoTgoEW#VsSdpxtU1UH7jtuO#b7VXevEZNESuH|jyyu1{kpoYgnd-#g z`s7WyYdOd1?r3sYqF|1Vlx4D=Iz%>jKe>H)TT}OXVrtlW{CZ2<^TaB;jP+vK{?$edUG)d)9c@AsGBUJDiP=ssTpwR4BlQpm5-%#|iu z_2c1cqjXQApwyqU&}q=K$5Asr?Cp2InGm&c_vn$1l&GIJzD zHE12yx0jMxKK$M(lRq+>e=k(}Odmlv(SHEz!%H$mx;SQ|ayhcoO#>X$UmjT0pG+v? z! z?bG^FUUTmC6~YGeq;VTw)_s$rhxDG9##h6E`frZxBTA@DroB~?ea7{>4`tPmH~Ab2 zcNw$3$-HNGlVxkB#ujloj&a1u+Wd0or5O^v=`E(ebWv)HRG%z^GEnj^Br~B%f509c z`aF5w{GguCq#NI(m748sJJ7H)o}C8X1h1@|9jxAfFbk@8{Pj%F0Z$L|g7j#}v%KdV zQp^k+BzaDig;5?)b@^;g(~l3Bb*a_td;?(tZ$CGH)@rD<`m-qlkD}8E4wGVT(xkE3 zC~c9s$;Q<=uaLOXB9n~^9M}f(N}8|{Bz{H~BMc)*{|o_5`VHZq?&>qy9}~PKLp~J& zu({HbujzKj86Q5nN3CtJvKoe9h7i1KHYQ5>iD(|-hWZtq45f&me($Uu zKvUcr!unaSuV@^KY3^D`2bp0QB<}WIeRkESVr;(*zq~dib;&SceOLC&OHiT9nTizo zHqT(En4B&%wk(Kan5woJ64b`R=pFbm^x5@%VzmB+hQ=df!u2uY^>~tn$)F&#%g%n~lx8@@M*beJj0B2B^$%X8pqmQ+x6Sn*#hTBGM zMk}A|{Ku#vV`eo8^6NuAm3_BDM1Vw<_2(l+LGf+1&Ik3UZLHlToUN&xroA{GGj=`9 z1{V{f<*7if{~9B7KByb_%-Q%*uBW9W_At9j^Wl!b$nVQ<(N1%9?5v|d@;0N4g;dkWQc^+l`^bST&{#K=Z zE%&*|?&;d+(r?Q3XM7^y7!0kHiQ}wW!xR1={3}P;-Fd64M;o(}Z!oi|${`dZ_L#QR zDQ>bKkKxT{DPK@UsAJ%_&UHrv*cGzkiHOpaSCP$UM0DYi$d@gL4T`Cd;g&qmy@N<)HSu6ir( z2v|_6t>mt>E{wCP$jlnlPtCE~@E5(@d(d#2bt@bPKU8@EB65*IL!x#4+0OO$&h;K; z!|v72Y=+VkkZrHYlR_o=z%kXmT?yvMr&}~l$mGMq8dDl}ZxE!ibg?7MvjZX_o4CWDT z4ZW~X_}s3fa>{sS{6=!L{ZTta`wDsa+iT>N)#p_c+3r#?cNkb~zSr+8Aag51LA5t`Gg@$fg#Efm& z)Jz<`0`2ez=B8>6zNdV=Js26p+mkXJ=VEH+aoA;aX`n!F7Y5V@3c${p^@LRvd~%M9 zs(x2lsBGmmWT7pR9X#f1JS5t^vEGITHP>Fz{>*{KCU%@z{43L(anNiSXqdhIuI9cFYMXr8E*T$<+ z*TId0O*HVk>6We+!cB@i*s@{o3=GiO!09GpZ>(e{xI9bEBkLX4^d=xCN{sXH)|gNW9ZH?+=Vu5DYFZl1?F~e>+MILxcqy z=#zN}LXpLJm2!UHg>y$$)DZR2Gwe)O@1fxi|Ja4sSf3D6`gc#9-iyf>NBas=Q=}uR z7en_B{r8t-*^rH}z9GIOOV6jG-~If~`O~j3$mW;3I&nL%W9IA`C`P@WLcs8UY)%A% z>S3n7c0dT3Sj{5+>FRpH<=^R`!XrDDE|ui6bx`;p_lF%HD@${AN>_<<-6=4}&(t-h zPS0|GFjegLp1m+6|nt*4p+`0<4c3Jsh#zuYP+Q7 z)E4@tYN*4}7>9;N9KfW*Gi{zUjG9r`H$EWsM<+-yVpI1Fjz=Fxor^3Z#{R7I{`O<45@d3 zHL8l3lLY?fKWX6FK6K{V^Ub?2oX2Ow7dkjOU4u44#jF+$cGb7k2_%G#qxTN+2k*l- zC`>b;k{G)0nkfhGKMUF<$ass*&Mw3CM3MlDJ`-P!@159U&^Xg*-;StQ$R+MwV1cT) z*PIzcpWmbW{$8VjHYh!Gazib25SPYfwfpYyd^wa9ps>vJX}@pucWO3KNdY!d>=88$ z?sA82jn6>f%qen?3#wsK8hO98;UBoP*lIIG5_`HEq!`9G!Ef698PZogvmg9?P;jL| z(TDCFtpxQSB!kF&@K~S+=`a1w=E}rCWiGi6gP&@TI0RC{YjGX1xjOsgS)IGMl~ve> z0O`{gxX36f$%r~_kYboe4mLc$VdK-n^1RUp(xm#6Zo(T}e+$a<8bUbxS2M`sclyj2 zHGb#e!-SHT9pP0uud}1gRDf~%nT{&QcM5+Xl|;l&K0Y0?Zc>cElQ8(p+KY!dDJMzt9NQwTxXhmw_v1j96iZRe2g{x zElx{YBQDqAnK3kz6xSOTFu*5E#6@qdIxBhAN~cJ*&PK6553s^fmLV$;L6;A$+o#BHI4Kc;}AM*peq=BHdt`bz8V?Vp-| zmotj`b?$dr9_!x7D@4uvp$r*mGIeej}Y!Qd&y^wJA24`!4{lOLSQ}kgLLE zD6$mvrAsIoSqy_?fj)18wsq!9<(s>1wpqU>i^9(fz(JDf2qLKDbs)Nxlu6)abZ5G{ z8Blo}|2PpJHY$VCgCxuLx|SJDz@Hb3i9R+%f_C=HhjE((r%CO0aAe>$GSZKLsE4{4 zXsh-M3WZWfKgu9-gEn7xupVHs;OfZW%jtSIn7us)vGmg%&a!cm)EWJ;a%-X}ZC2aL zYkfz)UPEeAr&>3eO3bp3ftmtGESW+ANNChhM&n!>l<{$q$M)9|`{mTwXqgdi#Sb2! z1CseI(i)3ItCZnu^Im}Zmpa1>|BO854Hoec83Vd+z$)I7-5*`4Y}x4D4e?T z*wP>4z1A&fHWk*Dz#c_5NM(n#4AH&N%~%28f@*baW^x45bKISX6m}w%|A_dqzEMHd!`}UH&r|={qt8!v3<#r>hpKzH)z(5_t0{{G=1|e z=aC71f}7|jf;^kV1D|TF#V_z5(07WKezh{FfonZGWBX{_9w6=HJ<-`iUy;jb{GENP z9W{$?Q>09T1`C!<)ERh+!;<@OolQ4G65`(;F~ySgwkrmJwKSOoQ-M+ei|ESbt=eS3RGpF{r$}(9eZXn4HI|sFG6Q9=Zgcf&vDL zb`zpd_51uyghax8Mo1>Vpe{*YOBC}#os_=9rqyHm*xPgr-uOZ}a$TXl@$SlcbphT7 z>62d{%S~G(X6MpeK+-8SJjL(6c?vO?cNh1-r{d|bY?<)#?KxG|NI0CE`vl@hWDW3P`BiT)$ZV2NRw7hU#AY~7nML_J z2Df3NvkSZZN`4@p9tw=^w}7DtSRcq>KS*>cBx8F($?#L9{;Vnvwg|F}WT+T)u0<}M z*yIF-vLWU@QPbWr`T9Fb9QFkJ!^5}sH*&qLWJK#$KP?OJJTWvNPt(t%*ugpWw1s8! z!=pHD|AEgt2BU0l@45^N#ARay;#g8+4Za&FB)#B#dkt;@%82+ddoboZ)YRhg8b!#Y z7;uTNw=V+UuoxtyoP%|h8F>)ft3lK|l7z{e>nQ+8BI&aNJ(Vqk!7AfIZ~@Wl;n5pG z|IomfBI@7h0>1^0aZDd1mxDf%06)m_TT$k5;r65jPCaos@8FH~Exz5C+u=4mq7yhJ z3<;2ygJ^S#ywqT$hHMh)oN$bic)6T;W_tN2TM%9HCY<@ zR!oykc{%*VC*VN(i@F+aV4@D-eh2U0{EBXws0`$-%U%EuqMJc7EJjY3uv-72AmwEE znm{+><7&Eqp^QRiB}{g`CEaV{UFFsekYs1!(X*aHf0#IJJZ5HBR#g*2#oZo3g^Bam z(ueeDw(f~P(jT+gD@OI0tMNjG7WTKD^|8j$@TaHvoU2y}`-VJ|W?`#?i?GR*iFcHCw-3f?AZU2cPx3mw|uSY5!8CwiK#>Um+~GQXtAZdt(!s zP-QbNcHIBVO7+lpBOySF9y1Ni;KUjI`W|0)_;=i;1=Inj7n!Ye8}iGDt?YbRdx$nRt;>3ZE)k_ zKxQlHX;Qy@k2>k$PK{xO?UuXWN4@&&9=Zf?GC$YS4;ZZuDq{ufV%U5Wcx)K*PVdp` zRx247-?tipBY#=<^-aVSV%}~&ODR4T$$HWw&V^X!Ws_d=ML~6FgyrLqd%e_lax1p0 zwdnzzD=(QZE(89SuhQD8)s>$QHjC|M8?INCZ8ifV;nRhV=uTm8_|bEN3Xcc)umJJL z4A5&BD0raVdS8x5n963$R;OxFA`4RrG6-B`McGN04?(qEicEo<1SD1*;d`jLuimuy z%7b`Seu?_28A&kkm`p!&TOBOF7Vy>bT=#^yUu2I}h=t;G1SAT0)hT`6qJJPte0q-* zP20yxFE^!bw>N8pHBIT=uQBPebzmmE-`+0#+MlPuqKLV3bkYaEj>V*)hQf3KaUvAh z6D%%V;!s`=vsoD)~5l`nJc$-Q>)$()q@)Ls`pGYQrwZwT-Pd>x* z%sKa02e)dX^mpS*>(tDWAoL7>9(YZQEj6-5b2%=lQQL$rSNr!U@#i<*;Remz4_3Jg z=W?~jT1j>ZNKoT(ODF7Yl(wQ6b7ozJEPZ4h+EjkFkdNJq193}tR!knU0{PL({w4bn z1=a8? z;tsCCr~Qy&cWPvLTj%>H_ zw2b`%88gp7>cT`Qs?Cecv)kqnUlJR8w;oqkkpBbY7OSZj;g-QgHj&A?&sk{hoyJC6 zvdljY{McKV{A<2mO3`re*i9;uX(?2NFFOW8D_N{wMq=9f{NtT|fByrE=X0Uf^R;{1 z+YB3JMeny}6_1ibc*uEb< zQ4^R?k^m+1F4%eXyq)(kBXb3+*&Xv6Tl4UAh}D4zRu2p-Pbqiibs(;JwAx!bMT0S! z2?ALW0=bmHi)b~TM>Z~RCtEm1(z2P3k%Iadtbdr?(Z@;F&>Ot(wBKmzCmv`%8~D^0 z4WVMFee1|S%(7LJK#2~HHEJ%A*?&e$I*x;#m&P1K{ru`NdohGMY}Gfjb3Wc6h6n%- zr#89Fr^bspV8^68t2rP|E?eXBQ6H%vh{VfHFdZBFm>Zh^#%D#$uOJQY_L3cvL2!=c zFM)EjCkEQU85Q~-i~XS3IpFz{5S3K9CQrhotI3ouk+>%S`N}ho5wEZ5M-m@Lgcr)R zG9jd4LEP7bT=JT1f#W3}b(clQq!Y~Fsae{m%Mca~ZNOBJ54LQ!iD84`WPD~6@J-iI zXw3htp40;4E9BsNFWf*vr9{qm8BwW+1mX9HP?~bYDUTFq9F@U$MPZ*Ig zQ1yE{^(&Fa2)m>9NCt#MHHi`4negIyxOlRbLX4_^$hA;&TeZD-$B0*(ZrlHB;wm8D6(bOeuk+>(2}h!SMR; z=-8yXH#J6#7;(>0p&1DhR_Sth(RUvd(-aE= zhU5`fr&?TI-##c5Ee#G$g!J(&{j#+z-OHMs{e1&epSG>ZwG%bB2O8k4f+CY|jXlrm zt^OC=JAz+YT7#+r;wRfpf!lJ-sNhB5<>u9qUmsoC3g^+t>j)B~SXN!Y`O=dP!^3i~ z;0j(U?NuD%)?NggR%)9XL9o*r%hPMe3SOj~hqxlZ^;+h*NQP{;X3oa8=~ks4=S}mF zO9Q~C*ei+oHIC6vj2RQZyeJI|j56UuArQYvicclq!m_E-6``CI2JV?IRRSg(_v`Mg zV6=X&T;}5<%ma-QC;rZTrI=!J%YB9Vp(9_My_AJPe67rv1v zj1FBt7&U(oQ|7mk`SbhkrI72FP1tM2T|(uo0KZp0JOaAq(DfO>BMKDNwO!Cc7zC4M z(uI4so z&}vdj5+N&p7^oV~%Zt>8Ffv`S6LN(IHw9I3xMmvV^3cU7R<_-sPi@-;`#!LM&5o3@ zaW)I9-s11-a z2-kS8@KE^$GdsnI`>N_sH$V!~w+OYV%1d*(4^7Q zNjs7ICKro0*G`dQ-|60mu6R-Vus3?Gk7?H7=3FRkR;@~vIePUD>svh+PXzZJ1_~gO z$I}5xdP_&XQ2aU+9%d0c^Tg$=x0^8x2Ct&)E2`mljjF;7tzu98V#S~H->pLzmYi7% zZd`y4BR2cqX?6>KK6ly9$m1BpE0lzh@o>w-)>7XZNe#*;w5h^`?=-(2jf#_>!$;F> z3maE60X6m)>R8TIt(u_wIbX-MUVa9umRdLexOg@|r1H7Ad^^z6yS-{>tw~cZXo$_- zw|=t!WA3<5FrCHJ3(9DgJ>@hklF8B10-IfP2j&ECg@8VspAyuSazSF{-1;iYWy>~3 z-*LODb*2ZJL5-cL%V3oqXtg#ndwB_T|p^o))L4JYYZ*VuSY*S_h5LfRg@Iz)aXNBMLJ z4{bRQbWR6GU)0oeP}kZozc&f3y@CgyU1i&5IDQDAsIY0>M$nzb*=!9M4Dy*qlqJs} zWxekt$X+O8*UnTy&M{p8R40MYzv5xUDsPHkyx@TywS6L0c7e>JRt~TR82ZHh3evFx zEK!nvmHX@2Y%FazJfRj7a=jL~ZHEbYN5S$8WYIgLuqZ3haXGeJt%Y?aCO9lfrj{g~WMbM1Z(awJSJ%8skYEY1aBr|yR@S>E%G;X`7fp}s z64H{LYt(UZ=7sNLH`G#~8$+-5!U50*CN#ubp2Hz~CMHK>_6+Qnv7p`E>rcrO*>{D& zg-$c`t39PTOFbkn&24!Ks{`aQaru&go#nLEx7BRbHB0oXVd!PpHW!~ zjtJerUO!CGw^yW`tLk1b29P<4m5M7;QWGaLYtAU35rWb+0TihV7W0zaCfJi&F3V_E z^0Z>hFAQx2q~j7l3tE6GkaW!43HSP&I9R|^^gis&;OcGgme)oWD7lgENu@VA-3%&6 zV^9!|2Fgs~7S~+jV|uu_>EtC%Y85;R-|$JGhnz2n*(u!0M}?^)S69|!v_eph z^)SH2J;onm(4D@S{@N8$jJrDu`eqYCjZd%qtZ|Je+vt!5jZ~bJaw&;Hx-!j%L+{3C zW?#L)H5CbDVtvRTP+}~D5oW(wB-w#zhE3i+7{0AIBAE(k9bg)%X5(!oOm2cU`lF~d z*mIXsY$>0VMxyG{Xgvyd>M^xki$HymMD}=G-_b-y5`NCdrwqv;^rXwyDPb2D&VwEG z?-$8AeY#fd8Q=edRXYnAi<-y%7~b_fzJX-xQLky^)0hN42wUZPjXn8(W(0LWGGJ^m znrPG!k8|aeesci>_3%1#{jp{r=W?Z%C^lb}9>#D%(C)6+J}f{ z`Y@V>9~t(Qul0xV59+|{ zF6=jLpuQ=g8bCHd(4NdXQVE}495@PzWoSL(c%{Z;fI&6V z#ie(tpZR?4ptA{o$$-jE&&5|lJU$!q>?rVM@3YPh>~(`_&2tHQY!+zJZnp3U3E&WGEPLgF*#ruSk2LfN3*n7m7bhDBO~jk(F>x8 zq_~C68|Yzvn;KG#N;eU=n}r1}nC<@8za_@0NR=BT6=0dNf%g(Cf`jv10ps` zbRY?dS4eKfT|ak(KRz{|Gke2o{iL?ALz8Bd?UqeTjQ>uNEwhKae5;Hk6xtK|P@1xcoW?`8J%!2+Z*u*L6c#gg81Mbk$~g zOml>qMl4_I_m@E@>-{TalR`<%1SNa1y~}5M{x`grnXpBkyGXn}lGZk5H#>MBV|F8F z6Nii|JS*J=$JLlFHUeBC40`$&SiMo-MRIF?T(lJvl_0ZxnTz0LbN;#tA>?Ia$EC{f zT>(p4W(Syt6{-S!_P2<;gJqYU>ca!_X=}~xY&xv>`b8kb7$Fk!FLO5^*#paPPKtuK zd?3i!AaqX%i^rjH5*i_>!G_9VhZ{_v{R>u^`?0rogxX5@$i|Q83qfTKTR)Ab;4Fj! zW2C#&IZT*7+(5v2T%}0>l!f&V|Cc0uoCWJCBU9)sZs(mVwE0n#29R7}ZJuuqV&Bt#}WcY!7N zb@p-=H5n>fz2inX;x1PKiyL(TG%@_mL0Huhm_fu#41wM`re{sf~iyMN_D_6 zaph47gLm6ma85xaJwqwfINjNkSzbj+NM{8`F+u34Qpq91yL&@PT^$|!db?1|goEqX zCbUL`!r8>zY|5fZT$9FS=@>2iLsNWigrdMESSpmf+(P-3h9;a|x_QBfdu`P#Q1z@z zgPT{$;MsU_31FdCUN8`;>dKiaTXITQ@NO49Idmg4zSrt{PQXh;`B_N z_eXsL!SB*pEe)IWcaGjz6W+A4GW!y?+L17iUnq5@k1nNAsC6(TzG*ZiT*_(|#VH&< z=ElN{TkoY(GCHuxyq-t7SmB@MC}Gz5EFL1O3z?j_aB)3G4h?Hs2t^e|_F@BkX|~v* z{+JWk)*?2yN`q9Jfd^jv#J?EVMlPRlYB{$rM=H&_T1M2jG4>9|ys^bH`SPZ+;lsE_ zxWBzmke$?swvUXEtSFHBKzbHHw?c}WFn>hPZ!O-i38T!8;?GxcVGGn<|l`(xJ_ z`6CU>h8Ub$nKBZlrr8Nk^cf6GU#=i2>AGG|9i_f6#R{mHW|IPArYW0T7jC>g4~sOx&*S|KK1g{K2RUKJ?6LX2Wi?F+F{yJ zj_FKpXU$whd{w3R!|}=M`f)P&^4&90DiovbJmYZj>Gpyz47tU17LMFT-yw&VzxNu2 z*ysxUobX9#8d^~Q2o)9<`KflQ$yF&P2o`qo;c^7o7{kUy#CgBAr=CW1HO!&qim&5b69 z*yrZ>ka!9jGfj!1c=7=b9=K6HdN_6aZ_;r8Mw}?|y)ty<6!POVmRT%a7&ouL2E2Dx zCWejt%tQIclvn3{!57q)&>Cs} z1I;m6y1u#)xt<^O_70_9IEMv^YDPqCFEtEj2(ySjNol^fUeJk-S07fAP)dLtiarp< z+8(A7w=Y}RrkBSa#e9PHsl7NmS+ADo=h7U9Uow(hmBnfgL@4kOf35|W|ds4)^tIfAe6-mgR1LXx-mCFR} zH@u5}*(54%>TpCQe`ss4zt{Qsg||XhN<}u=?cQ@6h+|e}lTAr=p5vz=pm zPv&K0hFLBm?JB#6kz;vGL^CC)c5!|ass0h~tm33wS_#4Wpc)v^;N|XG03N2!k){u_@Jt<0jRzII!Q*y_ zR88{6U0P~nvy4!S)EkElu^t4NsSscFq1U~|?y%%RXR0jWiWqdX9k6C}}d-ROx za+B>^iZOIuBurjoD7XTJ8N>c(e-cihpCFuC^?a4-WvA5WLD827GVq<&3JxobKiqCE zA73$SmNSclUsNUX@hdgH@AYdezI|5N>i{;y8i)1m=0VQfjH0jlH|!`hQZ>Z=w^mlh zGNORsT{N(37W;3!2j4-Pw`+43>Y zI%p#(`P*0YvaO1^)#B{>QxZG9s2^UGo^+l{JxH>H)72Kl#X#h6@f$UfrITRACELbC z%}=$2^a+#d_CGPod1sttW=_@njz2aWhL{Z7`hzT%mgWe@o)AkI<;N68@45dT?I&83 zB+xfDadT;f|7Pc)f*58l?Z?sV8jxr#P(jd6PN?EB6YPX#HiXs=ZWP%mH{G%7X`mLz-*mKSP@v zn<=ur*%~apuOiyQFXC8bqkTs*jo-R?sWGEiu?=m`dC~m2esq4XRJFjf#=B9Kwe_e{ z&t?BGhZN?p`#|AMlCuEzo{qOTDTf5XK`O*{Zr_nkwFWZH<1K|*okO*NnWY3zID=3d%%@@r&ix>xX$A9#pa&PBqTL z^X{AYhmVF)<xi%TeJZQAFEOV5X*u@<8m@mDcgQ03zLB2Q{NnFBI1HPL)hBs6PfjEfAW*!1U8Ya3BNy6 z*2@-zBh#2;GK+7CW($YDB}$ztmr$kUxNzJc3sU41Sp7YJLpQp@FRRNTE~0`N1y}!oIDQe`Z0qXKWwA6O2B9IVm)Wl!2USR?OXDm~OpiDDtORhZc_ z2N18?D4cYn(|44l3QsEg3C6v2@GU*a5QKsOH@<{f7vc-$%r@^4=Gkb{txdOnSh$60 zI<^QgxEH$4bgfD6Fi>0A_JC1kwt8*PJXni37#~2NuY30iM+wjIe9E7RJ9fXoR3}a* zpwj1a2q|kyWay&Gc5)>^Mzc zWHRz@e4*p*FD4j;Tgi<{s|!->i&Bm>0JO_|+KEQiKJP-of8Rm`M6V6gu1ylH-M zbCgPvh;>))H41KN9d2M|RY{Z#7^^hT=gtGcRYt?g!&($Cgrb`ymGnA8u<^zctK3xA zMYp4_(~abj+nJ|$$G*M4-NRR}T_Od#FZxq0=n#Ldg(1!7CSMTp{Cn~%c3e)9%FR$a zaW%i`TIy8-Oa=E`_+^FME~6+?k2O3k*{%d+} zycqKHP*PS4Dzw{e1FhWYUO7DYEO`2zqm;_};>O9B&iH5$d?AmTEL1Dc=UTof!^^NX z9Ly*db~`;1o4tBeKV=d0OvXtRvsVM<-{Y+^;&v(zwj&Lmg-iEDTsE<%t;i=TIQ_0${vw8yLGz*>{h; zb69*;h?12Y^=s5mCeS@!sHtTli$mt~3?9NUATJHy>Nj@8-ga(m6CN<`vB9GZca`Ne zi9AV!3excGui{Fd6;Yl=yvbpluFgDhZq(9ZHATlO-qf}!;ybv`7b z%C>q=R^7q*&`zgI!*Ytya?IR7b>hgqXh(w*IvNQ_EsI;!ubz4K_1XSZqg4TBY_ITl zftdQ7TU8wwI`x$9665|Y7AbH5cCW=-&E7y9@Oms6*L?}f`wb?aj0r4|;Ry^j*6+IH zH?>-R5G*?ry+?F!>=w4@rFRj~#*uTb{|jP7@6AdSLB%vqO5D$S9 zG7X2`mg6E0i;>55IM-Do0ko?6LeuRo9=vN5-O1y3@kGd}%nm%%l2`97Aw!eY`p@uM zN2`ZN3g*pPCwO9}0{nnHW%x7C=*McvW16ZU7ynJNg#gybhR03JxKFux8K%va1sz~D zvL^U;&!J1eTW@h7m2?Q9$#k~Mgt(MJ?5cvPo%oYN_PJRyt)G1!(SQT-cf?CHOa_y& zj}2_s1Ca2?qhQ$wv)%Yu^_8b!r=soY0E+>2Odp9`)>^H~Gbpa`0V95#x4lWYgraJR z7<8NUE?T=?()rZiiY2~4a-Do&0Mhn;2$m`GeSNbA)arJ5Y~75j`7)jG$=Av{8~H3P zZ!=pO=X`L6mUzQP3ClkRADckfk^4ci2Y}{-REECx*m^VB?tALU({Z|kD@8r+7Ricl zx6uTsyo5_A?MDvIzt!b`GFxPhXP-!&s>!UWDmEZ-b8le{I8Twu}`joDlVBY`M`xGTfMJIhFyTC(T-$|7P+ zbW$0LVo2LM4|TCK$PW0W7_M(<@^foCj*J5Cb#I`vDWj##PVgJg*17Pp{ zKj3hNH@uu;Hg~ad)_BwKmB*5?9NEx?b8=>;ALCkC-Y9AwOJ16hX-DRXdEf^1CBDAu z8#dRvVIrjnh=-v5Uia)Bb2=Mq~ofYb}KP?9Ma4u9ul zmdn*qq@(QqeA_)uDRSN#6rK|N-}VjU2O)``1X@;3k>}O zldr}|`UW5kj%@Rcdi*w-Tz^Tbr!2;;$11|jt zVP}}5VSB@*tW}@01Fcc_d2n;`$z)jrttNelvHy6Cx1iQ>Qs=P!aDgxKYip*695Yif z@9su@aZxge-|N<8W7GHmkoaM^!~HQY--hw25?e1eun!kEM_Y7Kw|8{npP`dicM?sZ zvYoERgGhMm_mD9Y;f@v2A5f5OD?J%;Z28qjys>Mx4z=K2Pb*Cc1WJ^9#I#aG zG@N=0=F%3M6sdI<>*Rw`xhz%)-CmLqyLny{V_@Rz#MH`CLGC2sKkZj0lA7o$P4>f?o9g zt&aRzfGw0;yIk+azHgO6L!_Z86Uq`c!}tzjn-$WWUv`PGfY5rz~#?a0(x7lHIM#!6=zEZ+>FgpOhx@hZz+# zVeE&T857wcZuADO${`%-xYstUZC^2Q$`&=sjA$$dAW0&sVi$@`KFe&u`{0ZN2HMB46p0-byWW-?D2$r zLWg9H(m3+zHilzX|2u88$&20C-)Rc5;7GrNG-^S`I;5AMp| zyV4carw8p*?tj7f)yR|kBxRJ!BoiiuIoBkzx~#{h+1s$tbj7iA`Wq-X8k;SADhC&2 zv;~npo^elaKQi(kv+phm%#CGM7a_LBZ8!ug#z6=dWujVkYnKa2cNjjUB(yt6_ca0Y zPR@EIx>~kK?f2*AbQ>nx_W70T;q!NVTG16BZpka}gD}Ij#g33z(QxNrx8F1>8n|9$ zxmSDQQi%;wk+b94euT#_ylf(CfA@S5XICXuDgLisWQgGF5yo#NGv1;E8d85|n`BBd zb$o&30gj&hUYg5LAgAZ0y<~m3P%M$#)?;g(#_~zvg36pThQ+(S3+>XKpE0dYlO%_i z!FOjfWd`5v_sku40YCcF7Rv#CVZM@QwNDdnI&qa0AmOd1Xke*vlfMyshZRNcQ_xLK=e7Au~c$ih?> z(cNL2W^pZ;hQ-7`sJ9DKo)}!h4!gnlE1z!vm9!$E>Mx!@8|MI=(s{vuDI7^My}7Ar z@|iM8M=+du%p!Bx2)!1X>pgw646$A49T7g50GkBaFLxLeYclAmW#pdiy-sz}^RYa1 zv0MEn==lA~OZ1_}Pz0p?EB;vqeq*8h!e0cMO#ql8fpXJCJ8UTz`~7}n1Em}P%6|UA z2jQl&kqvFfw>U9$*IM$#qo)CPqlA=9HKreYUEcYPcM2%_{E+P+h0P!a z@9xBA2YhV3S!ElnxDnZjf}f2wv;T~3Sj7GDSarcLrsC$Q^~hQd?~k2gAlT%Oo-dRl z!7P8~7Mc|#$vE4t`6)`l9{(Bz{Se62#k^d;?jn7#owqRX$}nmi4aS2u$sMejzpXkZ zQQl!21TrGQJm!OEwfaQu5f)gf%4gOnoU}(9j!8C^zEVq~t8I+wv{$8gpS5~k8$s97 z=}sa@sB>WJq?cT3ARq8D$;0tg%j(RR8q|`)BCrG*@lpHTe5QcB3MNZ^&RFl zC-TZ#0A;C$hLO3{qDzeZqPyO zYn^G+Q5OAV^RI7bXjxN#?wNau`W>N?^?NT%^+XU=C-wd5QVir*40~}RoD2d1Y*EzH zKo&?3^GBJ%pvil{;dlpa_QPM<+hz;p79~+&5`p&Y=O=F-eBETT>n0gJWjQ*|3q9#; zX-PCNCh^)r@VhQq#Bu9u`eoV^7-KbJ_f+{t&ZdV;4B820rgi8k8N8vT&cxNH;1*v{ zR9)_CXwt2*A9o#Y>w!GhK(AY{W^l^?@q z)W3Z+g=W0}e6}Hei|)KBFeJ;VK@qDm z2@h$C&p@|Pu8D*+x5FmN-bCa3a#AUCBy3+a5^p#iA2faJcHDV1-hglbOc1F(*#uoc zz&ao=7U{jKVJCXbwN+S-V&q<3mhxenW)TjG_(+Z{@P%v;H_ZPKb5NCowI91rLw=w% z+{c}iM7qV9nPAj>l5|+^sbTdghrXLVnqrYZt(x?ck+Iw-o2iLjeZf;F6Hya^`syrR znX}-jvUeG_=Jj@=gzZY9zqwgpI`+J8bQBMdk=~J;l|!w*R%^Qoa0;qIe&>uDS%kec zFuaI5!?TMh`+0`BdYhwA*E8?yefec}3&+T!uY=U7z3R1cZLOco_Mn@6t*rA!>vx89 zdV>9#l(~2~*tBjAasE?$`{q;cMMQMcc2jF^#QYR`h3}tO_A+yXnD`G&Qk~;<+-<7Y zZ`9x7J(duRO({vB$%R>iq$6;l30B|{jA_{G$;%elj%WXN&WA{S*b|grFVwZcv;7*b zmbOwB9QJ-V!+Ml(^z&5=KPdq&5`W)GAh-Bw6%81v1xf2Et25~%w^^6(${p+6rj}V6!ohkbb&S#RXHCwLzOb9oQ5*WXAr3QAwol_ac*zB*fgu3eOM*n^21pjSXNx}f__~aQ2YIZelB+ByOnXp~qzbtA zl4>okNT`vjadw%rd@qE5D#dVzf!2;FRJchz_D=t2V_93nYPvPB@YyN8jZaDQnRR*{ zz2BU|7Lx(7+sSk>vKXmYsH$>qmoTzG+nZ@2)8lT@uTP;>ld~SYVFn9!Jlf^&C!MU3 zg2yyvG$*)uT8DY+`MwJtd_gjeTKwJXN;J3PwAAEkXgEE8w%ylzeU43pKMu551Dk@S z=EGbEq@8VVr{LDe?RlXM&22 zrEXupD?>TVG^q1tXUV*b?6GFFh{G@uW)Kvn?s`0V#*9BV2fu_PrTVcZ_U>yMgll|} zJ9rk^N_rGK3L5F5qtbzkrl@y}xB`*PMiPFtz=Q(x$JEfQDz)4ohmo@=D{N#V_1iSG zbF=tTLxe>q=oONOeW)FGmX)TLV0oSQS^PUwaLQL6-o29R2PA6RyBABfUL~`XNqUtT zIdhWw$|GW`oV!2B&gTe=(nb3V1d5pZOb+u0firG`@WspRADRXN+=#wIao_clD89zT zsn0?-lizj^zXn47)pOmZd7*@+`CH8<_}TUyeeEvCMIq(ooxH!^SrCUwb!a8O2uhf^hiV3Dfyy}T5}@O zV$sGw`d7ebXhzA+TRE}WTU`J4GIB~uIq5_On8P3MJ$P;06}w4aUK?ULn8$5VI=khd zXY|(mVyQQRDd$>~LZ9*h#q+gE0*e*i6xDHz6{HTRXYP9ZQ|U0)X{vIP4I z9{D^E4A^>EA;ku7`DJ7w4@4LqKT3doY`W@8af$cG6mmE42w^k7)ycr~ZCvryF7F?y zte7S=r4adIb}Bw~vay~~fQIw4h~`W!*JIbuom(+xH(#Eh`g2-Cf5TMlUfCDs=Ae2J z9-*CZ#RngHfgY%#TbG6vl3)U|ERH;Z1G+b>Au-)EeE;G|88`$tf@lU_#A;a`07qh1 z=zk}iy5SiQ01KqBjdK!HsM#rNH5}$XEr}B^(D1yAMr97`9?Q`#AEs$bd7L_#cFrPK zz_TpC!oaFZ$y4IFj;P`R3 zU8D`5Ev0x#RxL*dzN8d*>WD7qhaUcZ3a3_f6fDAlrEkfxf!+lD#qYNgKJC1m<>-rO zYRy`fZy*uUf=*m%?;1QVLpGR$kDW5}m~9FvzHxG}#!V6yp$qaH%(SF}2YHKrZrbG3 zmXdZ98Hp}Xky*ejpR~gH4xF^$sNZ$&yBr+KJ;BmnTi>K7QvLlT@WMnwjK6Efo5v`D zASdC~$+t|!ka8IR?ass|Y?Xv2l*#i^O4^lUl$~PZFA3Ms6r&rvJA+E=Ksp^1?s7Jc zOs9biRS!<_|5B1bFeqRp(Cqr}JWl#X+efLR`n423&uTK`C<=WtZ^F0Q-qjhkz}~r^ z)!H%hcPn>(ix&eqv-L!!2br(Cb6dXPY_a`K-Jt6 zo7;$5{p0olCC1a^7kQCF&mEs20S^Cf#5DMJ5K?vsc*V{UhPK`Q%WeM3+&B0e{ixRG zikW7HC*6UFqefFt;)_e~!Gj^&Jsh?ii5@DZz~8a)il4Aj!OrWgNg+cU%0*TW?)gVq zu+y44X72B(u(2+kQk0(ETxVp(R(vnbLOJC^wL+EA1mM4>W zgTKfK%vI#r4Ke!gfKW=JH&H1+HO`j3(VSGRFAB*;Vm0+&GFr1d?g8yB<@g95NsNfbf86$6B4$Xk5WqA}&`fl7=_+jgx;;CGoa`}S8JcHvg8vc;xuzldud@pEa(p~#Q z703fwTeq{$u|C4)6?_tXz%{Nfo;Lz;SiL*bL^S+8wl01{U-{Gc(y6$zL$U4;g&X@6 zhZj(Fu&Pq!w%-CfHKX7YxRxs_l z!Ch>DCHhP^Q;e%vo(U7=7e<|9MJ6n6PhJ5FF7QZ|Gh;>^lxXQmIB4GLa3h)q6_f%>9d(Zn z1j)d!rmYNQ85%aMHNiH;RbROMJD+WHMGDst-iga%Si85N{uIddT3F(FjEhQ2J94M& zmcBd~KHVpt_2d^sKyz=rbn!nqdz;}3&asD&hgzd0nPy+JI0GNV8Pp;ooHFW*bP3G6 zvHA2s4@8bvScjuxv-A3lG4uYH{~bFE^1Qa*DEv|f3AFxnqT~F3S)UZHzX>>aMQ99l z0RMc#{EC_#D%)nQLduC7E8ZI`qyu`x+z4CGANm(u;gcQNj*@E@KEY8MY1E())h)zc zIs+HPK|ce6fwG?`#&>YeVDu=t)$?rg%a_;C1=<$=uKy2^GG$!8Gp_BJb1whp*JnO< zgOT!;K4QM?lK!*Pz_UAuV_3NYHz4QzrbWE${#ra@8*;5HTgT#+m^pE!Zn^-p3AU3a{OVZP>Kyg2PV0`XMFQI@dI0OHWxP8YoV7 z?C@)75(&Ae4v zS0~T{_>O;cUI{kC`@olS>={2q9FaXusA=1QQNpaGNZ~AM=<0tQafS~XXjchWjmVcI z(&Y^R2Ju5|`IrJ%-+|}UaM^4^8U&zM#f4ot^f2ADK1bPzsE;+Xjro$ppY@af4qFjh z%p>1@`{Wi&R*20pcW|T1Exueq#{n#&ge>sj82gXJSpK_1AF%Y7xahpA zAFLaTPSJNC3f!ND5pR=)sFCT-h;@pA~UDJbKCXmH)V%*wH*rAXDmC6pU)-v3Iq|`nZXVJ)NgHEhnX1( z&d#@o?hjF^$ZRf$a0{<&X`5;M+$02l=>9mHEYY^JH1x9H zziAy`Z>Cy`zQB27A3neb!cMu-P;x8*XDe%MYTtnQ%)dlE!uZ-QsD+vYHuLE}`|&@yAUViOjZYg`^otX85)EJ0SdA=q5el`<@F~8s62zRUl?HT@ja2 zm7b-Y_})<3YeVb6rm5&b)!!+_rp{K|9M^D+A5VaZj^4h+C}~kXLX05S&@zUdPkv+- z~o=+8~U`#;$#VS~1bl^PBUH^6L;LD`Op=JzZg36p3*DZ!vnc zixPMvVjuT19L-RqA`ICmutp36%DXqRc0KIgFLpH>WbQC z{|(f@o!}Sxfh5v9qXv3=VHMoohpvO9mh@WIrqUAEk5elh8eZnd(@~&G=U+wReOSlk zdrM;f{5R1nA(Tg(-~Q}iuKeyBqP;gg-9g`V@NeOQgny*r*m)L&8?dOt z-qTl|e}v1>i!*5kkfcRa!#j3x)ZR1Gw(=KRpKUI^JJ$=S98ntlE@_kJ(9n^;-FAZE zz|Y+MG$+^&>oxWcYu66u4Rr?R$qZfj5v_o1WzrvpOhiCNM#i_|qT)YzjN3})?D@_E z&jPitYMX1q4p`SJAk!i`Hx#O}sMN2|-`UuPzpEhM@7UO1DsgsC3@6eByZ^cz=LInN zV1Yz&{{_Znwe~+&N&Y&CuR^+i>{)_Mu2RRSDRuegC~8SnZ&ff_q4Y!2(G@EyDVUbV zrIj!Sm*HhU+EM)39q@z!5CKrAYo5hw8dV3Q6~%*fFjOzJ{9jZhGLYm$_uBk@a+YE@ zrO&&AFu}Cx?Fvn|#{@nu%~FZ~yN**)`>i}M|L|~^Ibhty3uYpW6y-f4quj@6q)HUg z_}SAu4rB@S`rMVcCEqr~AqvZVn1fB=KAq2O*CUAeLekF>cy}=nbGPv#i9XcT*+hk1 zLI<5{SB;VK^BrVAZBeFE@ga9lJHznpUwb$0cHJ|g_lCDOsokX0s=&)Cd0*u)dVo3H z*OWj``5j+)?)Pzq#DsHK`;(}Je>Jx!HR*ZXXq;y{!C3z;^ym1W%fu1Htc&3g2&M)~ zwYAYcKy>b#%I0|DPON3P#QE`fK7G?)(D=8nkWBibb`dddLVkJk4YfB%Q=T8t^%@h0 zg(7QUmf~s0Y_ACD+(&hQj6`D;0xGPUX69`E1>lYRzW15^z*jRA>+-}|3|>i5@}*CZ zJSh#17Qd#_AB-Iu#oS`OX6*#nb-Q2RJXLD`@`bh$zIiZzzqvT1ShUzs;^QrvjkpN_ z&iONJ#;#2ZtrY@ikPxuwK7p_CVXC=wOI?R=I_Xhjfet;@4q{FVkahY%Dc2Vcyloy0 zuXs3eOR`#GwsOP5eQC#H&nf#Q4#A|#W@>4e8bLnQGMAo`zI(@}VEhC$UcTp-WiQ?I zCFb7O|AM0)59G;Y$@53|y|7`UqnOAj{vSoNpW!*@y*4XfF1;k&xelH4M+4w!PJ~DV z)Z~JG%ljp^F?t3TI1Ho~^?+mw5V*~hImR7oFdOmJRm2qG7)(vuU z-fktxQy^gTF4Vs2Sd!t#1#ru~5&b#JQ}V{SCjWpG9#y{Xjp`d-9Ygzh~euqXq2BYyTpm zzqUIUW0yOB^NlHyDXCjucBdk4gw?5f8b%YQ@HFGS_eaM;{#Ch}7O9Ip{X$qNG@7!I z-l2NyP*g*+J68EJL)i&P>24nO7JH(>|LhwordY9Kh2X!qg7s?b>L}$EI zJZIp`&L`sQobeRaVQo3+tXOZ2u37pxzF!!%*JY5|6U1oKslGOVI#65E+`3`$=k?yq z>>7UDBO*kOFMoFCR(kc)jNlIYdN-JuizYBu*tbR`ZBQ~6auS=?zI{O^$?ID52t_tO zj`ny$vK%0m70~JyO*VI3zfp@CQ)9oPu&104%QmobR=KYqW=79`4OWdcOmjTsV^4Oz zpT&~ljl@ev^W|4BE>L|1N6fpCt$y^SAauNcpD?Ew@IAV>wW1}1QtrXGy*|fTag9}V z1l&FFe@wCY^Ae~Qs90Tfke#KEU?|Mbii4N2Ia2}KdVDebD=NXr5zyANz=E!kvNiB< z9k6pX4$k&Nh*UnJ#s^=f7j8`-Xr zXu!q^eUR;Vw`1)lFMZDHmijf|x;~z&?tn3e9LLrQ%Iy&QL*U^K09sVg`_(y{c9ve& zZ#7hpRc5hSVj_&|eOD{Rhfg~d(Q!1K_wys1e9~FT1!*d$N=v}%EF3(VEAnw4p@m)vOZ}omx zvGzKhX8X4uH^E9Z{o$)?olRhP<5GL|Pjx`nvOb08Wq#`aW?}mhd{ja%Iy2F(e{GWp za9$=->CZxEKGdQq?CeaW@T0E%>!rrSN1R)ZOfFDJ$ zW)H`h_%cb@%G;mT>y7-~P=PqMI~Q$Vo!5aJ@UpG|mIA;=wr>RCke2vy8t$0Wy`H_< z^K{HF(ve<@qlX#q0KD=?tgy7zTRV>?@9G@+C}`mzBdZH7;LM7ZTP7uqvq#@L2q*s7Ea zKnVN=#U_AZ6OJM=$R;sNoCAbIkv#w8PJH4O8;!O}3$*6O4d9>lSMFqohMI3b#9%r4 zGJt$|Yk|;Uz?s1?Bbqh<3_Z`U4u5UIpQR!8{R9jzM(|>Ac__~Tm-B*5Z*%35x_W*}=#Vo{M%DmspZtW96z# zVJ8ee4o={lhk>#uO&A(+A)kaTMKd<@zF0P?Mx#Cr{Y;OMvh;R9aT$kaNP)=oZlTe_ zGeGLZDKLl|Anr;KGIc#k2~+*v&gB3Ju*DKh5FhSB#8H5vzaB* zqKx%=J%Pr>su}3ihtX?WHsH!h#o&oDc>|jE^(mI+HA5c&U$L($KFG7&4Ao^*V8yv_ zKYaTGRE!VE*fLRwKM+c`0U*mB1#fGy^tGZESoEEOZwf&1C&dDQf9?oEB(RhqriIED z`xyn7aqvpaqU`ukv;WF0v*JM|pUV&p!P>8Q6Y#c9^KeJ#YZ{uc9+SO;qVs@~~&kRq?74Mv=k=~jIC@t_h0&cfOsa@w%p@d=H%r+Wph zP6anO_r{WLv_B`p?}>w*7&OOc((bPB$-ULXPYrK0+L{;}pZp0o5RGS3I89=AHlYj> z!yXv7HxgFxOD6vN_*T62EwhUqnX1~Xwr~RJG`TjfA6T>fHikROqU!De>aw=N=*MS| zzj*=BuH%;&px-yukyKTEs$_@}39a=6q4xU`(~b`kcNQ}f38x;QDw!rMc)D8YdbIia z?9~{E+ei}WDX;>BAM40yXf#;kUBpJ}-|~j`3_At5B|VWDFpDJU#s7-|vTFl{%AOH! zs8iH`gC)Y>ljq?O;0zirFj$aw(xKUwtJI&SRreGP+phS0CszK-&TXWzdnCuo+hEh( z)poo2n{s+D;lK}yhNbVQ0d?PgLp4aA0#5ak(@0i%fRu3&EL{t;3?SG5-SdhB zx>6DsumBNq8HE^Rkv_7h8vUffzWHs3 zFn4vg(VK%%TgXe2q9|F}hZvcgdy#Q|3iT}aTFReocz4Gi0T$%vHB^N$fczD2+r_w2 zk-XxM-QsoU8=2X`BCmR(DB?5zB(vm1rDrCNGCxaKL*n(mRKy&vXIYdmT{j4V5FJg9 zMz@W^L}v+}dvM2Z#V5|b{TkWN<7Y~1rM-4({@xq=5&MVFl0h`gKhEes*vfxT^Ro(} zwEpP-5N7?6JcRuM!TQ7aDL$qqp>;GP(>wto-Ra5?XEAZK@`!quN%S3R(EwRj^s=hF z)}MkuWi>3foBu)*X3oJlO=Ii9HMNPug8K$80gj{iPx^Y9MS@=4&FhC?-$0d4G7J1* z`~TpySM=daA0;u&Ne~mCb&4@Y@D)3AF_={W8yv{F09xF*p-zpH7x?XJ!PyrG1z9%D z5uj;!;ERTxqY)sU(+ZbX=mb6P9K*U=ryK9`mhT3U!34c0s-^OeeyA6kRduT$3vGNx zr?0sUev|gj@g;rY>?!X3c|ovn=lRp9`Y33$f7SVq9L|r4#mR07SNTLz(K_jv>Yix= zT;&udNne>+^cCMCz+$1c2mEhlfT0Nh28{qO6#mR`uCMCXr>xPZ4eT*YLV!#wLH-84 zMdy(P(Y|CzkL$jqepX_I8fPx`o~5kgs1^=^C0of=P42=|bJ zipaZdK?X#SA8*GaS`9o&*%?f5xybQJ*H{6K#(DF}nl9zYryW3>v&L+G|_vM8{ zU`Xz|;`irqQEBcMzxjvNf6p{=J3P!7d@cDvoWd25uO0xA@m~_nNaY217@}1=*3W#< zTd((?b3`cu3esdgSvt9n1)XwAcqAlf_%GZ*y8%x>Z7o6-9Qu_ZVEG0Ir8gYi6UWC) zp{bqm{WZJ~oN@KPYtj~Apv!cGe?U!882WTtjkM2pO}(n|`LT#5cx{7Su4Zrze!gK~ zIg^aE_@VUW|Jr)%u&BE44-`c~MLX> zl_}i;q65Ys$ocXj%`#4k8vrl5?=yfj9-#g^&CN*evXJyH_bXhz>-FlRSFhl@kHOgS zfmgo+!FCi(oz25~sL-$TO|`RVr2uqPZoQE4UFO*_i{n8pCh(Ow^sqZ{jjzn+0**;i?c%X+vy*2Kb10Xr@sNelWp&&MLx!49N8FJA+u&w#EX;y zwsx2_`MIclRRDO`E?|e}KttozfTVthhi2u2_lhb2q|{wv7Tip`4y`7Nh*5C}#a{@m zu-mTdbNEJDD9TML4rL#Wo9(hme8;(zhu%snkV>0@KTx6zH>s=PM9|U_E_?yfPxIFTNi#X@$6qjv#FQQB1Nrww@*kxg zqg`>)=O0e08(N&k|0D!5-S$eP1o*i&KZS=60X{Rg=N_H>J3TUVpalvE@^iij1R0oU z1>6cLzxiICnaKH)IhR~XhP2XV=ZBI zWr>hwA)o=CMHU_r3ZmCt>w@+cbAS_iN(WKu1fULp2O5NB%)N(L2{(R{Qyiv#DXu@3 z{qQZ(lK1P7epV}xzIGdM&idtR)y2*gkYtwm8c84QjBI#nqMHZ^s{~6}_!sA%L07IT zQa)w;S^+LYnE~mBJ>LW23E*Mm>S94z|AL~uRX*8tyFRk^oe1b8p6ZkJVm3LqY>N|6 zl2c!B(RvAmsH6E;@CkxHIteoHLr%k$3%!hjfMYmmljlvSy=mV1LTx`;_vp&&6D7I! zlZ&Xbv+ojh@=8c{uA6m%vH45P4}n1Pa0&1>f&5!P|6dJ%S9`?4(|4Z2I8$f4x!xFE z7uL*n4du!)4?LTdk#%3m6q!pUE`nM*H@S9!b#y)-HLu&aRjFM|I4v)5$7jUGC+=&c z2&T6XR8TkpiTf@9sGN(>K*AP|l(!vs5Cg!ICxT}2n@yp@{OtrTCR4-b%Dcqj4E)Ie zKmm}Y?K7z71;c`Zib^=LKiNai;U?^euv&B={Wdg8c-jj%5A+570yqXSs|v~s0aEne zv0cQHla1%0K zN73%8kfze{|2Uh=eTqylC{B5Mbfr@>tHReHC&|SN=yf2ntZWak`bq?xtqRtE-CYjY z;xOyCsr=*;_y7vTom9wM70hW=BRVR9fEYLw0R*#UyB1jTHR&iO?gG}et+lAWnmUP0Ja`W%(&6rhHDJ=fj}DA z78)B3Q~<7#-w_dn%LZh)<^d!J$h5hzP-g*b(gRCA{^j_oKuXwyyJ#6W3I`T$G9^eNayXkbnfB zpaqUcHVVgCb4~2tpH2M(;9BJBeZKAgkqrw~v=e^*KR{KF2+&05Ci6WKs5@pdbwmjT@n0afFW7>4Xn5Dr@e& zYy+*?Ex(1>0Vi(aVq-PJQuGr7zz*yEzluL@j7^SAj1c|!aT=A)mO@ebQn%{6r^vtV z;re9;h&Fq>$?~682&!b<)I0BKh=_Cm`O$B{ba!o-r3ut#9G3=}iI;|((O(bkq?pE@ zG6OJu_mBLn1MbKs4BRqj+q@U9{0OdH?`+*4&vIdXu-G^tgzlLXHAdqo@K0Rt1or)I z=E#98_$o?JW$BuxjSvcjE`24+p1A_K&&H5!_W{AA|sxV7WDB9iz z55my^3p;J+q8UHUcJHFO>EuH)r1ZA#;Gn1|xUjkh`lJue_D6fFW5X8h5qWc;-jTffotQm{7_JVeDTI?S%;#))RAhXrAQv?99MZ1g(+=&>G2T*o^ zWKSZGIR1bSY2f;a$;rvXm$^V{dVw9R&{0aV#f#e&c-r%Ml2I|r;fYqVpJq2hgL+_e zwExk@m|hGkRHxB?zZu~TE@(YJzyx3TJ~s^j--!((>HtO=zPmY*@3QGh0%Aw8;hwt8 zNn<)fv`92W-h2n;Fn)UA-Wn*Yag&YHb)73%*ceXL#{vse19}K-VWS z^p(6Q#KAeQ*O(d5#a29@9GQpZ=;s$t|2IkWS}YYVWyz$xg0pYX@FMhg9ds$`8A3+Mzu9MMVQ5xsQ9 z7ayNEBfM{Sbk7f9y4ST_nPFOo=TpoSM9-z}bs2!(nKlOOt~<}|d0n3^R9Vjfb4nF_ z(t2VG$da3zTlR)@@@$>cT-Omy7v9_qhas+~h{+J}^X72C@oeguIA=O3#r-!udzl$2 zh+5Ny9#e{jxUPh9-IV&aG*`pCJpkcU!Az=Q+wOjeAgPC60W>_!DG&b-wv$#%jQw}j zoXx>hu`aC1ODvo*zo3AG%|uE^hZNp$>+Ev;AAsgjrzA+Y?o@@c&TgkL9V`+}f9rr6 z%9Oz4)L-ye@j#sg+_u1$c<@t4#jT6onw5g0*OlLPfN;*Vv%kSF5iS`Ru&aDtpF?k| zFiv0Fw%7V+_w+;_d&#iN7RhMG#rKRiCpZPY43Y-py70`=6b6#;Y zu`*NM9|0IvE4}dLN#4P!4cpxA6!}F{BCN>9!&(kHzlz;gPF3gDZW?YML9}%HSfLx2 zOqmGtdR}#tkfig)UzUO%7lQkF>WjSf#b*rT%3OPz=WKWAp{&!f%W>H!nxA(HMdK7G zDE#r(i_IBN8m%G&Mup}ni4Gdibwos{jNj~PS-a5mQHBayCtrVw&3(sE^nSr!NAe8? zMTH;|DW7X%uU z))e-DGeFqX#5D~HEG*+Uz{Ke$27dflLlwLj!EgH0F$9Jm1Ncqn&(P3tnG;biCWocu}27a4VH&o;G&Z3mdV#G06iwK0|VYteh0DJXx3UQ zZHz$n$~uM52PFEz+e6Sm%CBw@--tXKNPx0GiauUzfhgpppq zTu%}$jlFQ5pb^OTEo~EkNV?!SCN1obVa<6_t4gh2;r!{5+pZx)w1>UjlBtWzW>Ptl~{i>)oNcB>f0{xOa_m$x~cyWC5An<{X?Oo ze$?Q}*0&j5oe|j&bvwtUSRq2u&k^tg7~&+yHj&q*NYGFJs@nB%dC2>${0=m$;tqyu zRXYg8PO5oUa2qW1&6^t;40Be#lj9JhAhQO9QYjJshq?7znrAwuptc3uOm!_>66+hJ z92~JHbTz9MHfK2gRz{dzvfU31D>-gZ5kiE<5eXw_#aB5UMiz@VXdDl}`_z2+O@kM8 zDRA9G;x}jKhCIlx`scW1v@I1QBkGdi($gU`dC|E%pW77R#4qogl{xql89bw+qN29e z4FGu5&_V_WMgRQy^A3Zndj1G!ZzC|!jPL497g+fb;M=!+eoaYK?6oPo->REYXe{9c z$ffITpaZl6NH_+C@t?~#C;QxsI;kRPrB(R$v}#ge=4)#jWTUnwC0Njx%jb5l^n-&W zXRaq13O^-J59)zcFy3o{5bQua28I4!*a&|OZa>2?p^jyYI-~fY3M0$=#xGAjgXKI< z`zG4$J+5ucuHo(Od7+;!XKE&xvhjxmE>tAoASqgSG~Kc#9_idy5lxO)zHBF8%g9f# z(X^wSYicy@AX`g4oXg|a)ta9JSrJG6zZhPdduU~&PK`8AwHB<Vs9a=EuDZZ&gC4Wm0Wt&yY!PpJLC9}fr4pu z8YfBnMmOsM97Z|7o&bL6t0m;gyiC9RwIYya~j-IF8k{!2+8Y8+)DR>yCM+{uUrA zvqZTzGy19oxO;>9J4R}98P;uGD-MbN}YrW!w12n(m!@S|dl#&9!B_buY~PYjxP1vu<|vxCIWk{-J~}f z4nuj{tjzV@t^AQ@d4?cMalj$@{4nP95Ap$VBdIF!P$%59(3z`^7xN(!vEzG&o+`rR ztY7t{NbLH)Rd|2@js5-4&Rc3U6U~&Q!~B*+0LXKhS@FA3zX6e9Dg_3`X6SJX>G^Ho zcRvvO!z8NsA`*foWku(-GIZgM6-^MZxb(|?alhpF0I_#{?%PCIW4{ z!pXt~E7NG+K@MkMf^|a}v6}TjlsLel3qy&Se&Hlpi@+r-8`svJV_HDXOkOSMlz_+Q zile>8SE{Ts1F_BGFEtfs(?p3o%@Tj^3D0=rlwwNZ#H(>ejAxttE@#=0L=_gLcwSL? z12*VAj}h#s-Y%#>VNhcbALJ}y^a=F!EL0rXdzNp7J0n3^$GM!z?}J!ak6JsyGB`H_^146Zg^g! zUr1X$xKvQMETgDc*avz6f4)HZtGJ@_$w|ojst$`Ni?Qns9AF_mKRZOmqMyxm`GR_m zP|KxOnt4dxey_dr=~?R&8N7MFU+4jDDEK*6Mp>3!caGW9vkoS2JNI-&6nIa%AKqX~ zGl0De1620x5DqZk_kuig-@N!A?M_=6(y9E|^6iC^QBYs;=}otfZnflS1O)uZr_b3w zT%sA~e2*C^45NG|OE{Mp@iL=@e6F5;%i=ZWw_R+*2Xt=WTprZsf6P z`*7&!5rJk8I~R;nJR_hHH*3~>&JZ+Py5=$;&1ycp&CkvKL-QC;E`RL?Bt| z$1|)@Kqh&>5pQ;?Qky;YDgAwI-j6Vu{tmh%9=theUNXf*bO8>*dZX_YW5eg$$}aC) z@fBI(4FP87cF-OT5J3yFChJ$|_re`ze^FEBjyU*^Vu&er!6=@w1Lq-+xE4aGbaV@wBS%Lz>GH$rj+uAQkhkAYhOc#IyHia;;mn^ zT&RB#9Vn0!^c z>hwEplw960XQv@wCjAjLM(RI;tQuunoZpATQ+h3*F4z73pEtqxJ6SjW6jB*C67243Ll)irl$f!L`9Wn!&9 z+BPC`dgvqsBsE#Xq^ga1WBpLbhQyk+)-i%Ef28b<;1{*J_}XORrk6OcH?~W0Ba;g+ zRViqW*vj6}pjhv>D#==wP*~*oG!1{myMDZq&_c z{NOBGtsuI3OC3T6ISDY_SN*Tw7c=v!62D_9{h zf1}m3p^ub7Us}7&ulD%$>G;Vq{gnuPqn5a8yJ^e9CMX}P=XTi$nI2jIw;`_;@k$!< z`eg(YmP1QwqQc}+h2Sl?WBWQA)5Js~;bITbq;xqhyi(l2?A}d}oYIdOlzzv6aLW?sltVm>8RO1vV&k=;$QmHaZFTH63V3CqW%b#-Z-L zL%Ff5>jKL@JD}9pm?_pJ_02@{5Zb>&boeQoLP>`FXpP0ZJRXFsC|b3Nbp}NvW&{_T z>+PPC97;RSbAjLd6r0k4&6k{{U7D^LTA{v>9h#^pfJ?0}v+)UEc-9jr%DiIP_#Si)I(!Jpja>Vg z6?=A}7%M}eEk*gP&TGeevTBJ#-l{ja$$hEKv`{bFIQ=FB(?XsW(T>VO=j3M*^U0IS z^zAWypd$-c1RItSkANAii2+@Y0uPB)wob|#6|!#6nuLKv#@h3tLhwrj{@e>Pxv^NB zFLjR}B~Tm}Xv;l1jCn&H%l4pRqB8AEyxP8v6GJ;{OuX8zt~#`|;Hj@v^wzd%40rza z$+~XfR-|(ED>}LAu1>_|AgrH&OZNI1Ggm)e*X4Koq7}q3^}$Voo8j%;>ffvzuI;o8BM5N= z;!)Bf-}YKwoGu0*ylOaGiX?u;1b>_+0(s38`s2x?_`I=hZe)`u-9Mz{a~@@NL(PsK z;dX7$e^@`m^cVcKq3Tj$$YIR#Gp2S~_EWYYnpp>bKteYiPdDa;N@w82)xhL37KgvHAadPox49YQnEQssQ>VB!fEXxh8 zL#N_Kjp4x|whv!vi4er1rI1h3xqh|-DP+a)kUxlYn=E5+rownyDy+QSZVw9t9jdR& z?OH~nui_~NnXlS%9BB??X!LCjtg8H==PKYt59k>unI$3rs^!ICYwu@oWB%QHA=0**Y`-PQtj;PnHr;$;&WN+l;~rIHWz=kqa%veSs@Q3{R)3btDEq_YzI
y5xY_`j-5ilWA-L7@9li0BMr(4!^Ond0XJEL@EC8st-0NIdSlMT z+xKNYtPiQ^Cm*NT9R+_rn8w0E#U$wT;SLBONsQ+`$f1NWi?N%WHJi!}8C0seJ!3n) zacSL@A$z_SPbMt>mHzUhBH36b&eK@@t1QuOLt0SA#rRWWz6w?y@NzPc(45^f*U8msYV%bku&l2QVrji4e*gJ5uq^iY z5(ijryC2R%lUNmyf#mbErAH3L@dUc8r`6Ytwtxm;NC^l~@F5z1ffZWu#FT*YNlB@6 zG!bwdD`cu%>>vyufqmHHg*Euc8B?w0D|M`lE{{jdCNV{&wd>ySdQ|hGhkO{fYafGP z?N)Y@A3E`RxK2D=SxL$BYAg*7Kevr!i^Ikm`Q7{+p0l_Ai1&C55oY44oeXVWaB%~c zO*P!#3!{d%p8%>43T#ryZ$}7)W*UPf@)rp~(bzyQ_J0FoJ+oEqt}D#h)X9K$4fAvK z>CRrEU2dE=gZluW^NwP#y`AIrfn$Fb&wI>vTf~`d+V%Vf;uhA-M5EHd4-vwpxwS`W za`^*5%1y@W$J{jzt4kaBsg>>pC5%=*$czDY^qK?4F^C`iV(;B(M6mRry*_x?}rV@k=^kC z7x-$7%L{&-hM1jdg0GOlvSqRj0Eo$ng5Jk~F;NB(8a77n2D2~%zrxu7NITW^GCO+U z23R(QmaCfIt*<7&yBcp$bCKo8?FR<$=p^6DRA3t*2sc1K&PpvvRr5U_+KM--ir%(Qqin{xn z0@A+YrMZ|fdS2=G3`-t#H%?~z?)cBeAtZo=xD0uHds=bgs@C{f@&vQ$4&7%PsG_IT z$UwZoL0oz(W#POPZR&Cmivq%q%?XJ--DL}Oe;Gh>aD34n*Oedm>-p*g?iK7kaWeJA z@{i%TRDvyw-iUR5yr`Zy_X{xs^d^VZq44u#Sz!?89k0_(!xza&YxTX!cP@V90j9`A zuwC@|0AMFA-P~FLs7EL;3v^wV+}o=uJYFy3zwa^bZTRH!YSvQ${t4JHW@3ltPC#&gF0J2GJ{=(j;`4*KB8xy9 zV2jrLsj0>d?&54ZH!cTEutSdRg+F0?!B=uUjaH#_C4xzOjJdH^{<8v=$)m26A5Zaa)^XuPrz zo=ZqkP+ zQ(z^+qIWCy_|P>Mmg>wjgA8Q&Ww_nmI$w5a$}>b@kTUNAlJTY)*nO>dQ5Eh-H1Y?N zQy=t5CV+<3DCyogV^66`;_Zv5y3elpMr2~S`)B6obnHC(#Hmw?EV zTR$%iAXT8pcpVbxN3NW3u^iJR3vGJc!5k(6W(vl^L6W2#`4BbTq~3+Ot3VhVvj~B%<+Fkg#AYVhFnbyv_aV`a*e1>DAP>*_RW_mDflR6 z`^rYc;cN?SNbqbM5G?qgo0m|0B)vUFY;+_wDr|IiOzu&)8~CR!=0(vGxPaSEKD;$R zL95Yyflz6Pxi|bMkO0~bxruLP+mx!razW`RBV9NLy|S5b`#cwExnbLIx;$ZsnyTRb z0BKSHsMEy{ggmfv*`?#P)-#p0(jKV`YeRH3_Mz!)$C%xG2xe4z@Q(53$evr`=2M3T zPTG*C10drEJw2*OU+T}(=GLQ;Un12MS~WPB+#ue~;pk}t`J+k`*nqkg;RIhvU<(7& zQznoMIOj7thm`@QgY|-}i6r;+Qy1@JeCQJ-Gu$|?+cd2PF>aLyUt-X6s^G=)w*;7K z=YH;-y`?dZ^PbmpS0wrjdCot9hkDtKQ1QpX-SwiFL>ps?;s7) zK^EiAzemLTIw}KKH5|~St0}OXHJ_C5cOpngu~9YywlW8>MD8a@bi|T-pQ@_p=3eM| z@wyz1P91m&&Q`1EO)1KH|2c?5quLzx90_=K`bYS?a#G#2X(wU8>tvSF zZ#$GJfXn=@jxe10pE!5#OhysgdUKDL%hMKN2ci&lUh3W)0%Lg#w2p-IVWp1e^w3L_ zOerWI1o81Z?9tR+uyaJcD^v4j6yS2W8GZ__k+7s2iDx{jFI1at@7@n*^v=e8aQ6!O z9+YMoTJ@SK(^XhGen zh@z%8Y+}edwiKYaI{mnPm9;xj!NDE8&&^BV&rhvxRtt-xDegW?AL&_I4CQJDx~c>y zhNCMjj`D!*jPIn%-OZhjhBjy8t;-=gNd*`W2KHvebopG4ekeS;`;fg(&2o9?yh-)` z!%SSIenE*Xzf`MnM&>+G($3|tC}uWy^F9nbct7xx*oDIbjY+x@HOHq<15s4+Xap}V z`?*RdzbV|87a*(V2sD)=+KQ%>X@VKa6Bq|!w8C|kswoj>AMB1I@qrmo_P6N*O#HN@ zy9o%bAv&#N%O%xQB0XLbDb-*H5x*gl^K@MrYh3Y`0X^Q|WGs&)A z(B<#)m&YycM;$Q-qdgc7P{ozBO#4F(}wPK~n_ z!)EsM@5+$SL1AzilFLek1_o^O0{I!ojSV&!E{}T*&t0ir3b*%Wdu>!)^s;rNnO>;- z*$DoDo)5}h8GG{K(krr?eOrmcDslD_Q9D_=yMLQu2UeZnt2PB!Qb%9)0tI-l=ABnD zj=1j%Klon#Y0VKl0atzk3L1}AE$4A??+OyT$Woh+E^ebF?2Lhd2Lsk~5FiEZy#Tkk zJE5K{04iDI3zN?_fMt)xjihYEynB^aUG*u;gu6}o*Vfy!7 z)J5B|YS=4R30g)#Ia&4rqADYB^!1-k2*eTd=0EMs<5S7viaM za`SR=c}UP2cu7`35r_NDf4PyKrv$ca&@?|T1l_)3EUUQ73LzvIr| zz&}NkIT5oHZN4$uzcM-*FYrG6l;?9YNr$GxO4~>mZXka(1qqc{A>=2|!*FS`U7N*o z`>Zc1yqu$XubAzvT%EQJp)~-)=}7JyqRKD@PJJ_VHgFhlQ2w|rQZ?oXtMToELwOWh z;?^%QC=*dnvA6d+;DG&8wRuKkDIJ0cx{+9w?I4dhGbPz}wS5cRHf5Telfh40xgBI^ z_7M_&+qA?nVhjr(R%-tA^~v&|6#OG@5+;*poy$#$g3^2+C^K28fMR4=GnOsb!Z-os zd(28SUwO=BQ{R2B*CreDOm)C_ash#074eJ=;BFKR;q{qXM5hjlk&kLOZfDKQyFDcu z`lo#Eb!GYtiJ;^1vO_hu<&q8+(Q#z^>hAogYQW}Gku8$2QN>%&uuDbe6Ot^o#$F>h zefa1nvNeBlbRk1PmYQphQvUTbP-xTeZ>`WjFs|0bTa z889Vu!C*z&ca!3f3`BhXQt9S0)~zSH;Wr^jDaI?HBcWpl|LiGFuW=nPJqi_+*ju=X zppu`WLwrGouXwIczRxY5KfV*3;WuzVC{*DOru=HRAMGrz#lZyYHfsKLDF?9DGr9!w zL85?I(%nf2ASnO1!rh3No4KrO|0_`b(SS|UInOREi7 zTiwgTz{-4&Bn_FH(BJ>RuiLojPq6$acNMAN-HCEpUAg=AaDXYQ;r8jio9r>Zb76qU zs?icn(2V@;l@M=yR?(#K(haGV!9T96pmbrJoS%;{FwevS7As`R3b*P+~EyTuImOD z*v<8v<*(BEp#GolwUY?UO1kQy02!UM6%ur%1dkLJcK-?pQpi6iyi_3#gse9C*Ikplb9DhLYw))W@a?@% zkJeJOPnuX0kta5Gb0a}Kx}JsD8_xiAkED7fae|> zbM=OZtwXcJyfVPVBP~Qny-~%qf{n;`-?aQNC=4tHj?}4o z-iO%j!JJH;PL-_B;epTh=nPy7oZn}$nc zuzuEAMbVwuBp>32m^bpkrl!j#QFexib6~ZXXVt}gm$O?diV{qJ+qvuJ9`PB_&Zz+4 zki95-0tZ50u)y&^d$$b`gxx)TwSadGkgqc5w2^JI?9M@Cj~p^>x*VH9T-`ag_ns6I z-QCO;J0~gTFSLco^GIiUqRO2PrUz>nXupHKI053()b~f0|LUZxxtQ+_< za;1$|pzb2!uUP-C%1(8=1%zTe^@mw{5$U3r6)?)b+-k7~9ChQHz^B;gH{Y7P53W1z zdCYd-QJbAS|5OfA?d?F(x3~&K_f$bD0Nkzn()7a!v-@AZbPE5a7!px9r^J81q60Db z-DAcV3Yf0J!GVEPR%a=E+ZbMNtv>WBmAJ6w6KpSh{J(-OD>hfli5)66^yh=Dzd}LY zsWwD?qLPnh3}GLoR*OYG3Ojt4GQGb9<&(&N~nREaV6 zv9$(v-m@nX+@D9rBJ8iX5+pod3+JL+f1;xz5;S-&^mj-t;a2ECJXG$`F|*^~2LeKx z=u)8={aI@Cy|^bBHuzNk*f1RLEe;{?Ld1ww#<5`KI>qt)w6+vGf{xLh0Q$3FNtt8K zsx?Axb3;psRDwh=o^$09ed_vSFU#1(AKR-cu-TBMOWKuFrryWzkLoU`p{#Y^izhsk zanM&z27yY+!+rrxkRglF zFN;gS<{wnU&Fim@R@pwKL|KcXx5&`|*1gsi2wTIB@^qPDOgg(macR%S38RH}q9Z!^& zRV5~-E;h-dO&GC+KG;T<#|gcZr;mSnY!Y-eRNO!0-}~pZlu3#`Hc=Z`KBEYYO#Hy=RkV*mhsI@&0oS6LEG6VI9Yo z=FhVy@p?k#R5@dMfwXyzStorZXw)CVY4DnQL;^cK`7)ByQfG_%CtD+-CUJ);u{5sm zOYD_NH;8``W&ULTHG3 zqIpvety4A+c4VtJAen~Rl*DM6NzcA7s+rpM4XZit>@Qk-T=85(v~NqLark{R_x8S< zA@rR4K;VLb6e%}Fb6e`2oo@e!`sIRVGc~nf*snc*ve`;YL^gbBemd6Y7PXqJ4m<@% zURm%8+=rhmURRO2>-je{48Pjh4?V}E#v~yUJZWifAI!)=zbq|mtUn92nVnsjAcK`a zOLm&j>oG#C7ZraWq=A|W+_D*he05aZ zbsQ{wq-68+lZno*ZIgPzb7XecZH&6pOK5YqSemcjF;!e<;^|JWz9f&L$@(OgP50v< zysKLqB0+&$6|z7mJGV@j-=FN-OCp)5fwLaV z+1Dax-!-SXUM`^8Ie{+Y^(w!Y*n=-Zk9t;DZXvQ_DP-B&ie^w zLr`tf`Wb_=Y4&{Wa&C@%VN;ic`s=c?H@4H`QGH^@UNfZ*Mmy~vGV-kr=7!f9kSU4l zjPi(ywq|Qh9hxFSL~k!WOh(*3Az>(8JcNZHRwV9{pb0Lp^{oTJG%M5>begnr+VcGoSA(3bm(PLg zvU)x1ygTQ5vVn>zP?4W6NNi>|+nA`C&1Z1_-5NO)NbA;hPPSNeFns2Vxlc;4^@Bxp zdEcycE!-l|SrsP!vFh8(9BTD00qM;60)GT4!Cv=yl?jjUf^TVQ;Kzf{tWlViSz5J= zW=&kNTUL?Q0aAV?@7dKqlGv2@=}vd?w=oWT{P32Vg>97W@zoi>rmqYB;@O#GFJ z#vK*i&Z4?>42*HYD$_?ueM}X+M&Bo<X zY$rdYeN0hKlPRBhQ?A_!Deuj(b&i=fR?#$WU>!Z;8{a4#c$XF_72dI5@;6o-buj7)BcXUV;+y?}RU6eZSzVmf z9m~!$qp^6ZgpymYdR$NC%{cvO3952ClZQX;{1wj&!EC4m2E}My(?@TQKY(ZoT>0d zACP2Hp=~{+A)#8jAZ?s#zY) zrN&~qML84OlNwQ}a{XJO(|qLlOxw?CZc43~30y>RQYXK0O>a9s?pFynIkmtGw`$x= zs>a~E_+7-HS$B1 z)#L6>&qS#tDSaN|=mUlkl^Ftyr2qzOCzOX}c4MH|M$bf6^NXp7s@t)v9P7D~&>Wpb zu25Exg-fOU*`gfQ>$Mgdn~Zu%%~`%{(*FwJehWKm(-0GC>X|k^APnh#t5w_3%#R;X zJ!5PZsZu_!xm*=n!+~91QK4@5Ni(~Rq2BiL~XIFg# zG>Zw=kAq9{1gA37sjvE)6fZZst1C8IQx+J$r^YV&xVnHPi|D3jaDu1`14Ae$_P5@C ztGhC=k0ysHpl}&IE0f#{%yMW_Q^+15?|OKoEI9kKvR%5AQ&Ma&PO2Wnv(i(wvyf1b zlTY)bw`TT7Rct&r$%LxU2XTSN3~$E>M~p1i(uFbjzp@5r3C&}hMK-I+^>=%#ILBQvDxBHKc%ji>#~tD2)e(-=8_V*;v}ey^&&`frDZ|#4diL|A zU|~I)*}1->Gl?dE`6?8LeKTqqE*H zHZxw!*n)kNtVbSLD|?pHw`;GtD-+d5#nwe%-jOjxn9@%&gHqM0byzdE$9d_QUB#J3 z!u!bgh*qq=Ze;{dli5fjd)4=>uUbrf+_;SqExtiwvdJ|`Y?3++MiN|){V7f0?d7s+ zfb**F;Wz16|8Mksh3jFSuVb7(K{;$9JB0nB#JR<|Ori+G>EA@+<&%87^3DFG&rOPX zcG97!9!}48Z% z62^>;xPOyek9P)poDnMSbIr^`#+lYlSo Date: Tue, 20 Apr 2021 13:52:19 -0700 Subject: [PATCH 18/37] fix install link --- docs/log_viewer.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/log_viewer.md b/docs/log_viewer.md index ef29de0c9c..90726273af 100644 --- a/docs/log_viewer.md +++ b/docs/log_viewer.md @@ -19,7 +19,7 @@ estimation catches up with reality, this is more visible after a bad crash. ### Installation -If you can't build the LogViewer.sln, there is also a [click once installer](http://www.lovettsoftware.com/Downloads/Px4LogViewer/Px4LogViewer.application). +If you can't build the LogViewer.sln, there is also a [click once installer](https://lovettsoftwarestorage.blob.core.windows.net/downloads/Px4LogViewer/Px4LogViewer.application). ### Configuration From d48f5c0368729332489362b0c98db8ad28493b86 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Tue, 20 Apr 2021 13:53:51 -0700 Subject: [PATCH 19/37] add link to logging. --- docs/log_viewer.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/docs/log_viewer.md b/docs/log_viewer.md index 90726273af..fae713f39d 100644 --- a/docs/log_viewer.md +++ b/docs/log_viewer.md @@ -25,3 +25,6 @@ If you can't build the LogViewer.sln, there is also a [click once installer](htt The magic port number 14388 can be configured in the simulator by editing the [settings.json file](settings.md). +### Debugging + +See [PX4 Logging](px4_logging.md) for more information on how to use the LogViewer to debug situations you are setting. From f7d2fea248524208d25e2ac9c3874b73a3d225c1 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Sat, 24 Apr 2021 12:28:12 -0700 Subject: [PATCH 20/37] fix drone server wsl2 connection. --- DroneServer/main.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/DroneServer/main.cpp b/DroneServer/main.cpp index 1806ec60c4..79da40fd8d 100644 --- a/DroneServer/main.cpp +++ b/DroneServer/main.cpp @@ -38,7 +38,14 @@ int main(int argc, const char* argv[]) Settings& settings = Settings::singleton().loadJSonFile(settings_full_filepath); Settings child; if (settings.isLoadSuccess()) { - settings.getChild("PX4", child); + Settings vehicles; + if (settings.hasKey("Vehicles")) { + settings.getChild("Vehicles", vehicles); + vehicles.getChild("PX4", child); + } + else { + settings.getChild("PX4", child); + } // allow json overrides on a per-vehicle basis. connection_info.sim_sysid = static_cast(child.getInt("SimSysID", connection_info.sim_sysid)); @@ -71,6 +78,8 @@ int main(int argc, const char* argv[]) connection_info.tcp_port = child.getInt("TcpPort", connection_info.tcp_port); connection_info.serial_port = child.getString("SerialPort", connection_info.serial_port); connection_info.baud_rate = child.getInt("SerialBaudRate", connection_info.baud_rate); + connection_info.model = child.getString("Model", connection_info.model); + connection_info.logs = child.getString("Logs", connection_info.logs); } else { From ad5534a5f4bf444c2c7d20abb761ded4e8838b66 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Mon, 26 Apr 2021 17:58:17 -0700 Subject: [PATCH 21/37] CR feedback. --- AirLib/include/common/AirSimSettings.hpp | 43 ------------------- .../include/sensors/imu/ImuSimpleParams.hpp | 4 +- .../sensors/lidar/LidarSimpleParams.hpp | 41 ++++++++++-------- 3 files changed, 25 insertions(+), 63 deletions(-) diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index b0b3245d18..37ee6374c5 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -213,24 +213,6 @@ struct AirSimSettings { }; struct LidarSetting : SensorSetting { - // TODO: move this to use the "Settings settings" instead. - - // shared defaults - uint number_of_channels = 16; - real_T range = 10000.0f / 100; // meters - uint points_per_second = 100000; - uint horizontal_rotation_frequency = 10; // rotations/sec - float horizontal_FOV_start = 0; // degrees - float horizontal_FOV_end = 359; // degrees - - // defaults specific to a mode - float vertical_FOV_upper = Utils::nan(); // drones -15, car +10 - float vertical_FOV_lower = Utils::nan(); // drones -45, car -10 - Vector3r position = VectorMath::nanVector(); - Rotation rotation = Rotation::nanRotation(); - - bool draw_debug_points = false; - std::string data_frame = AirSimSettings::kVehicleInertialFrame; }; struct VehicleSetting { @@ -1202,24 +1184,6 @@ struct AirSimSettings { clock_speed = settings_json.getFloat("ClockSpeed", 1.0f); } - static void initializeLidarSetting(LidarSetting& lidar_setting, const Settings& settings_json) - { - lidar_setting.number_of_channels = settings_json.getInt("NumberOfChannels", lidar_setting.number_of_channels); - lidar_setting.range = settings_json.getFloat("Range", lidar_setting.range); - lidar_setting.points_per_second = settings_json.getInt("PointsPerSecond", lidar_setting.points_per_second); - lidar_setting.horizontal_rotation_frequency = settings_json.getInt("RotationsPerSecond", lidar_setting.horizontal_rotation_frequency); - lidar_setting.draw_debug_points = settings_json.getBool("DrawDebugPoints", lidar_setting.draw_debug_points); - lidar_setting.data_frame = settings_json.getString("DataFrame", lidar_setting.data_frame); - - lidar_setting.vertical_FOV_upper = settings_json.getFloat("VerticalFOVUpper", lidar_setting.vertical_FOV_upper); - lidar_setting.vertical_FOV_lower = settings_json.getFloat("VerticalFOVLower", lidar_setting.vertical_FOV_lower); - lidar_setting.horizontal_FOV_start = settings_json.getFloat("HorizontalFOVStart", lidar_setting.horizontal_FOV_start); - lidar_setting.horizontal_FOV_end = settings_json.getFloat("HorizontalFOVEnd", lidar_setting.horizontal_FOV_end); - - lidar_setting.position = createVectorSetting(settings_json, lidar_setting.position); - lidar_setting.rotation = createRotationSetting(settings_json, lidar_setting.rotation); - } - static std::shared_ptr createSensorSetting( SensorBase::SensorType sensor_type, const std::string& sensor_name, bool enabled) @@ -1264,13 +1228,6 @@ struct AirSimSettings { // extracted there. This way default values can be kept in one place. For example, see the // BarometerSimpleParams::initializeFromSettings method. sensor_setting->settings = settings_json; - - // TODO: delete this when we move initializeLidarSetting to LidarSimpleParams.hpp - switch (sensor_setting->sensor_type) { - case SensorBase::SensorType::Lidar: - initializeLidarSetting(*static_cast(sensor_setting), settings_json); - break; - } } // creates and intializes sensor settings from json diff --git a/AirLib/include/sensors/imu/ImuSimpleParams.hpp b/AirLib/include/sensors/imu/ImuSimpleParams.hpp index 8dfb7529a8..78f8de4dc0 100644 --- a/AirLib/include/sensors/imu/ImuSimpleParams.hpp +++ b/AirLib/include/sensors/imu/ImuSimpleParams.hpp @@ -38,7 +38,7 @@ struct ImuSimpleParams { real_T vrw = 0.24f * EarthUtils::Gravity / 1.0E3f; //mg converted to m/s^2 //Bias Stability (tau = 800s) real_T tau = 800; - real_T bias_stability = 36.0f * 1E-6f * 9.80665f; //ug converted to m/s^2 + real_T bias_stability = 36.0f * 1E-6f * EarthUtils::Gravity; //ug converted to m/s^2 Vector3r turn_on_bias = Vector3r::Zero(); //assume calibration is done } accel; @@ -63,7 +63,7 @@ struct ImuSimpleParams { accel.tau = json.getFloat("AccelBiasStabilityTau", accel.tau); bias_stability = json.getFloat("AccelBiasStability", Utils::nan()); if (!std::isnan(bias_stability)) { - accel.bias_stability = bias_stability * 1E-6f * 9.80665f; //ug converted to m/s^2 + accel.bias_stability = bias_stability * 1E-6f * EarthUtils::Gravity; //ug converted to m/s^2 } } }; diff --git a/AirLib/include/sensors/lidar/LidarSimpleParams.hpp b/AirLib/include/sensors/lidar/LidarSimpleParams.hpp index c42bb59c7b..282f56a0ad 100644 --- a/AirLib/include/sensors/lidar/LidarSimpleParams.hpp +++ b/AirLib/include/sensors/lidar/LidarSimpleParams.hpp @@ -41,17 +41,18 @@ struct LidarSimpleParams { { std::string simmode_name = AirSimSettings::singleton().simmode_name; - number_of_channels = settings.number_of_channels; - range = settings.range; - points_per_second = settings.points_per_second; - horizontal_rotation_frequency = settings.horizontal_rotation_frequency; + const auto& settings_json = settings.settings; + number_of_channels = settings_json.getInt("NumberOfChannels", number_of_channels); + range = settings_json.getFloat("Range", range); + points_per_second = settings_json.getInt("PointsPerSecond", points_per_second); + horizontal_rotation_frequency = settings_json.getInt("RotationsPerSecond", horizontal_rotation_frequency); + draw_debug_points = settings_json.getBool("DrawDebugPoints", draw_debug_points); + data_frame = settings_json.getString("DataFrame", data_frame); - horizontal_FOV_start = settings.horizontal_FOV_start; - horizontal_FOV_end = settings.horizontal_FOV_end; + vertical_FOV_upper = settings_json.getFloat("VerticalFOVUpper", Utils::nan()); // By default, for multirotors the lidars FOV point downwards; // for cars, the lidars FOV is more forward facing. - vertical_FOV_upper = settings.vertical_FOV_upper; if (std::isnan(vertical_FOV_upper)) { if (simmode_name == AirSimSettings::kSimModeTypeMultirotor) vertical_FOV_upper = -15; @@ -59,7 +60,8 @@ struct LidarSimpleParams { vertical_FOV_upper = +10; } - vertical_FOV_lower = settings.vertical_FOV_lower; + + vertical_FOV_lower = settings_json.getFloat("VerticalFOVLower", Utils::nan()); if (std::isnan(vertical_FOV_lower)) { if (simmode_name == AirSimSettings::kSimModeTypeMultirotor) vertical_FOV_lower = -45; @@ -67,7 +69,13 @@ struct LidarSimpleParams { vertical_FOV_lower = -10; } - relative_pose.position = settings.position; + + horizontal_FOV_start = settings_json.getFloat("HorizontalFOVStart", horizontal_FOV_start); + horizontal_FOV_end = settings_json.getFloat("HorizontalFOVEnd", horizontal_FOV_end); + + relative_pose.position = AirSimSettings::createVectorSetting(settings_json, VectorMath::nanVector()); + auto rotation = AirSimSettings::createRotationSetting(settings_json, AirSimSettings::Rotation::nanRotation()); + if (std::isnan(relative_pose.position.x())) relative_pose.position.x() = 0; if (std::isnan(relative_pose.position.y())) @@ -80,16 +88,13 @@ struct LidarSimpleParams { } float pitch, roll, yaw; - pitch = !std::isnan(settings.rotation.pitch) ? settings.rotation.pitch : 0; - roll = !std::isnan(settings.rotation.roll) ? settings.rotation.roll : 0; - yaw = !std::isnan(settings.rotation.yaw) ? settings.rotation.yaw : 0; + pitch = !std::isnan(rotation.pitch) ? rotation.pitch : 0; + roll = !std::isnan(rotation.roll) ? rotation.roll : 0; + yaw = !std::isnan(rotation.yaw) ? rotation.yaw : 0; relative_pose.orientation = VectorMath::toQuaternion( - Utils::degreesToRadians(pitch), //pitch - rotation around Y axis - Utils::degreesToRadians(roll), //roll - rotation around X axis - Utils::degreesToRadians(yaw)); //yaw - rotation around Z axis - - draw_debug_points = settings.draw_debug_points; - data_frame = settings.data_frame; + Utils::degreesToRadians(pitch), // pitch - rotation around Y axis + Utils::degreesToRadians(roll), // roll - rotation around X axis + Utils::degreesToRadians(yaw)); // yaw - rotation around Z axis } }; From 3d8f8b2644f9a96e4445d01ea2240f0e819caeda Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Mon, 26 Apr 2021 20:23:00 -0700 Subject: [PATCH 22/37] fix ros wrapper compile. --- .../include/airsim_ros_wrapper.h | 43 ++-- .../src/airsim_ros_wrapper.cpp | 230 ++++++++---------- 2 files changed, 126 insertions(+), 147 deletions(-) diff --git a/ros/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h b/ros/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h index 9d51cae4b1..58aa4c2573 100644 --- a/ros/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h +++ b/ros/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h @@ -9,6 +9,7 @@ STRICT_MODE_ON #include "airsim_settings_parser.h" #include "common/AirSimSettings.hpp" #include "common/common_utils/FileSystem.hpp" +#include "sensors/lidar/LidarSimpleParams.hpp" #include "ros/ros.h" #include "sensors/imu/ImuBase.hpp" #include "vehicles/multirotor/api/MultirotorRpcLibClient.hpp" @@ -93,18 +94,18 @@ struct VelCmd msr::airlib::YawMode yaw_mode; std::string vehicle_name; - // VelCmd() : - // x(0), y(0), z(0), + // VelCmd() : + // x(0), y(0), z(0), // vehicle_name("") {drivetrain = msr::airlib::DrivetrainType::MaxDegreeOfFreedom; // yaw_mode = msr::airlib::YawMode();}; - // VelCmd(const double& x, const double& y, const double& z, - // msr::airlib::DrivetrainType drivetrain, + // VelCmd(const double& x, const double& y, const double& z, + // msr::airlib::DrivetrainType drivetrain, // const msr::airlib::YawMode& yaw_mode, - // const std::string& vehicle_name) : - // x(x), y(y), z(z), - // drivetrain(drivetrain), - // yaw_mode(yaw_mode), + // const std::string& vehicle_name) : + // x(x), y(y), z(z), + // drivetrain(drivetrain), + // yaw_mode(yaw_mode), // vehicle_name(vehicle_name) {}; }; @@ -116,9 +117,9 @@ struct GimbalCmd // GimbalCmd() : vehicle_name(vehicle_name), camera_name(camera_name), target_quat(msr::airlib::Quaternionr(1,0,0,0)) {} - // GimbalCmd(const std::string& vehicle_name, - // const std::string& camera_name, - // const msr::airlib::Quaternionr& target_quat) : + // GimbalCmd(const std::string& vehicle_name, + // const std::string& camera_name, + // const msr::airlib::Quaternionr& target_quat) : // vehicle_name(vehicle_name), camera_name(camera_name), target_quat(target_quat) {}; }; @@ -132,7 +133,7 @@ class AirsimROSWrapper }; AirsimROSWrapper(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private, const std::string & host_ip); - ~AirsimROSWrapper() {}; + ~AirsimROSWrapper() {}; void initialize_airsim(); void initialize_ros(); @@ -163,17 +164,17 @@ class AirsimROSWrapper ros::Publisher global_gps_pub; ros::Publisher env_pub; airsim_ros_pkgs::Environment env_msg; - std::vector sensor_pubs; + std::vector sensor_pubs; // handle lidar seperately for max performance as data is collected on its own thread/callback std::vector lidar_pubs; - + nav_msgs::Odometry curr_odom; sensor_msgs::NavSatFix gps_sensor_msg; std::vector static_tf_msg_vec; ros::Time stamp; - + std::string odom_frame_id; /// Status @@ -261,13 +262,13 @@ class AirsimROSWrapper sensor_msgs::ImagePtr get_img_msg_from_response(const ImageResponse& img_response, const ros::Time curr_ros_time, const std::string frame_id); sensor_msgs::ImagePtr get_depth_img_msg_from_response(const ImageResponse& img_response, const ros::Time curr_ros_time, const std::string frame_id); - + void process_and_publish_img_response(const std::vector& img_response_vec, const int img_response_idx, const std::string& vehicle_name); // methods which parse setting json ang generate ros pubsubsrv void create_ros_pubs_from_settings_json(); void append_static_camera_tf(VehicleROS* vehicle_ros, const std::string& camera_name, const CameraSetting& camera_setting); - void append_static_lidar_tf(VehicleROS* vehicle_ros, const std::string& lidar_name, const LidarSetting& lidar_setting); + void append_static_lidar_tf(VehicleROS* vehicle_ros, const std::string& lidar_name, const msr::airlib::LidarSimpleParams& lidar_setting); void append_static_vehicle_tf(VehicleROS* vehicle_ros, const VehicleSetting& vehicle_setting); void set_nans_to_zeros_in_pose(VehicleSetting& vehicle_setting) const; void set_nans_to_zeros_in_pose(const VehicleSetting& vehicle_setting, CameraSetting& camera_setting) const; @@ -316,7 +317,7 @@ class AirsimROSWrapper ros::ServiceServer reset_srvr_; ros::Publisher origin_geo_point_pub_; // home geo coord of drones - msr::airlib::GeoPoint origin_geo_point_;// gps coord of unreal origin + msr::airlib::GeoPoint origin_geo_point_;// gps coord of unreal origin airsim_ros_pkgs::GPSYaw origin_geo_point_msg_; // todo duplicate AirSimSettingsParser airsim_settings_parser_; @@ -343,7 +344,7 @@ class AirsimROSWrapper // gimbal control bool has_gimbal_cmd_; - GimbalCmd gimbal_cmd_; + GimbalCmd gimbal_cmd_; /// ROS tf const std::string AIRSIM_FRAME_ID = "world_ned"; @@ -353,7 +354,7 @@ class AirsimROSWrapper std::string odom_frame_id_ = AIRSIM_ODOM_FRAME_ID; tf2_ros::TransformBroadcaster tf_broadcaster_; tf2_ros::StaticTransformBroadcaster static_tf_pub_; - + bool isENU_ = false; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; @@ -368,7 +369,7 @@ class AirsimROSWrapper typedef std::pair, std::string> airsim_img_request_vehicle_name_pair; std::vector airsim_img_request_vehicle_name_pair_vec_; - std::vector image_pub_vec_; + std::vector image_pub_vec_; std::vector cam_info_pub_vec_; std::vector camera_info_msg_vec_; diff --git a/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp b/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp index 855dae597e..94aca385cc 100644 --- a/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp +++ b/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp @@ -26,10 +26,10 @@ const std::unordered_map AirsimROSWrapper::image_type_int_to_s { 7, "Infrared" } }; -AirsimROSWrapper::AirsimROSWrapper(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private, const std::string& host_ip) : - nh_(nh), +AirsimROSWrapper::AirsimROSWrapper(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private, const std::string& host_ip) : + nh_(nh), nh_private_(nh_private), - img_async_spinner_(1, &img_timer_cb_queue_), // a thread for image callbacks to be 'spun' by img_async_spinner_ + img_async_spinner_(1, &img_timer_cb_queue_), // a thread for image callbacks to be 'spun' by img_async_spinner_ lidar_async_spinner_(1, &lidar_timer_cb_queue_), // same as above, but for lidar host_ip_(host_ip), airsim_client_images_(host_ip), @@ -51,7 +51,7 @@ AirsimROSWrapper::AirsimROSWrapper(const ros::NodeHandle& nh, const ros::NodeHan airsim_mode_ = AIRSIM_MODE::CAR; ROS_INFO("Setting ROS wrapper to CAR mode"); } - + initialize_ros(); std::cout << "AirsimROSWrapper Initialized!\n"; @@ -62,7 +62,7 @@ void AirsimROSWrapper::initialize_airsim() // todo do not reset if already in air? try { - + if (airsim_mode_ == AIRSIM_MODE::DRONE) { airsim_client_ = std::unique_ptr(new msr::airlib::MultirotorRpcLibClient(host_ip_)); @@ -82,7 +82,7 @@ void AirsimROSWrapper::initialize_airsim() } origin_geo_point_ = airsim_client_->getHomeGeoPoint(""); - // todo there's only one global origin geopoint for environment. but airsim API accept a parameter vehicle_name? inside carsimpawnapi.cpp, there's a geopoint being assigned in the constructor. by? + // todo there's only one global origin geopoint for environment. but airsim API accept a parameter vehicle_name? inside carsimpawnapi.cpp, there's a geopoint being assigned in the constructor. by? origin_geo_point_msg_ = get_gps_msg_from_airsim_geo_point(origin_geo_point_); } catch (rpc::rpc_error& e) @@ -120,7 +120,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() // subscribe to control commands on global nodehandle gimbal_angle_quat_cmd_sub_ = nh_private_.subscribe("gimbal_angle_quat_cmd", 50, &AirsimROSWrapper::gimbal_angle_quat_cmd_cb, this); gimbal_angle_euler_cmd_sub_ = nh_private_.subscribe("gimbal_angle_euler_cmd", 50, &AirsimROSWrapper::gimbal_angle_euler_cmd_cb, this); - origin_geo_point_pub_ = nh_private_.advertise("origin_geo_point", 10); + origin_geo_point_pub_ = nh_private_.advertise("origin_geo_point", 10); airsim_img_request_vehicle_name_pair_vec_.clear(); image_pub_vec_.clear(); @@ -137,9 +137,9 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() auto& vehicle_setting = curr_vehicle_elem.second; auto curr_vehicle_name = curr_vehicle_elem.first; set_nans_to_zeros_in_pose(*vehicle_setting); - + std::unique_ptr vehicle_ros = nullptr; - + if (airsim_mode_ == AIRSIM_MODE::DRONE) { vehicle_ros = std::unique_ptr(new MultiRotorROS()); @@ -153,7 +153,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() vehicle_ros->vehicle_name = curr_vehicle_name; append_static_vehicle_tf(vehicle_ros.get(), *vehicle_setting); - + vehicle_ros->odom_local_pub = nh_private_.advertise(curr_vehicle_name + "/" + odom_frame_id_, 10); vehicle_ros->env_pub = nh_private_.advertise(curr_vehicle_name + "/environment", 10); @@ -163,17 +163,17 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() if (airsim_mode_ == AIRSIM_MODE::DRONE) { auto drone = static_cast(vehicle_ros.get()); - + // bind to a single callback. todo optimal subs queue length - // bind multiple topics to a single callback, but keep track of which vehicle name it was by passing curr_vehicle_name as the 2nd argument - drone->vel_cmd_body_frame_sub = nh_private_.subscribe(curr_vehicle_name + "/vel_cmd_body_frame", 1, + // bind multiple topics to a single callback, but keep track of which vehicle name it was by passing curr_vehicle_name as the 2nd argument + drone->vel_cmd_body_frame_sub = nh_private_.subscribe(curr_vehicle_name + "/vel_cmd_body_frame", 1, boost::bind(&AirsimROSWrapper::vel_cmd_body_frame_cb, this, _1, vehicle_ros->vehicle_name)); // todo ros::TransportHints().tcpNoDelay(); - drone->vel_cmd_world_frame_sub = nh_private_.subscribe(curr_vehicle_name + "/vel_cmd_world_frame", 1, + drone->vel_cmd_world_frame_sub = nh_private_.subscribe(curr_vehicle_name + "/vel_cmd_world_frame", 1, boost::bind(&AirsimROSWrapper::vel_cmd_world_frame_cb, this, _1, vehicle_ros->vehicle_name)); - drone->takeoff_srvr = nh_private_.advertiseService(curr_vehicle_name + "/takeoff", + drone->takeoff_srvr = nh_private_.advertiseService(curr_vehicle_name + "/takeoff", boost::bind(&AirsimROSWrapper::takeoff_srv_cb, this, _1, _2, vehicle_ros->vehicle_name) ); - drone->land_srvr = nh_private_.advertiseService(curr_vehicle_name + "/land", + drone->land_srvr = nh_private_.advertiseService(curr_vehicle_name + "/land", boost::bind(&AirsimROSWrapper::land_srv_cb, this, _1, _2, vehicle_ros->vehicle_name) ); // vehicle_ros.reset_srvr = nh_private_.advertiseService(curr_vehicle_name + "/reset",&AirsimROSWrapper::reset_srv_cb, this); } @@ -223,7 +223,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() camera_info_msg_vec_.push_back(generate_cam_info(curr_camera_name, camera_setting, capture_setting)); } } - // push back pair (vector of image captures, current vehicle name) + // push back pair (vector of image captures, current vehicle name) airsim_img_request_vehicle_name_pair_vec_.push_back(std::make_pair(current_image_request_vec, curr_vehicle_name)); } @@ -236,7 +236,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() auto& sensor_setting = curr_sensor_map.second; if (sensor_setting->enabled) - { + { SensorPublisher sensor_publisher; sensor_publisher.sensor_name = sensor_setting->sensor_name; sensor_publisher.sensor_type = sensor_setting->sensor_type; @@ -244,7 +244,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() { case SensorBase::SensorType::Barometer: { - std::cout << "Barometer" << std::endl; + std::cout << "Barometer" << std::endl; sensor_publisher.publisher = nh_private_.advertise(curr_vehicle_name + "/altimeter/" + sensor_name, 10); break; } @@ -256,19 +256,19 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() } case SensorBase::SensorType::Gps: { - std::cout << "Gps" << std::endl; + std::cout << "Gps" << std::endl; sensor_publisher.publisher = nh_private_.advertise(curr_vehicle_name + "/gps/" + sensor_name, 10); break; } case SensorBase::SensorType::Magnetometer: { - std::cout << "Magnetometer" << std::endl; + std::cout << "Magnetometer" << std::endl; sensor_publisher.publisher = nh_private_.advertise(curr_vehicle_name + "/magnetometer/" + sensor_name, 10); break; } case SensorBase::SensorType::Distance: { - std::cout << "Distance" << std::endl; + std::cout << "Distance" << std::endl; sensor_publisher.publisher = nh_private_.advertise(curr_vehicle_name + "/distance/" + sensor_name, 10); break; } @@ -276,8 +276,9 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() { std::cout << "Lidar" << std::endl; auto lidar_setting = *static_cast(sensor_setting.get()); - set_nans_to_zeros_in_pose(*vehicle_setting, lidar_setting); - append_static_lidar_tf(vehicle_ros.get(), sensor_name, lidar_setting); + msr::airlib::LidarSimpleParams params; + params.initializeFromSettings(lidar_setting); + append_static_lidar_tf(vehicle_ros.get(), sensor_name, params); sensor_publisher.publisher = nh_private_.advertise(curr_vehicle_name + "/lidar/" + sensor_name, 10); break; } @@ -338,34 +339,34 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() ros::TimerOptions timer_options(ros::Duration(update_airsim_img_response_every_n_sec), boost::bind(&AirsimROSWrapper::img_response_timer_cb, this, _1), &img_timer_cb_queue_); airsim_img_response_timer_ = nh_private_.createTimer(timer_options); - is_used_img_timer_cb_queue_ = true; + is_used_img_timer_cb_queue_ = true; } // lidars update on their own callback/thread at a given rate if (lidar_cnt > 0) - { + { double update_lidar_every_n_sec; nh_private_.getParam("update_lidar_every_n_sec", update_lidar_every_n_sec); // nh_private_.setCallbackQueue(&lidar_timer_cb_queue_); ros::TimerOptions timer_options(ros::Duration(update_lidar_every_n_sec), boost::bind(&AirsimROSWrapper::lidar_timer_cb, this, _1), &lidar_timer_cb_queue_); - airsim_lidar_update_timer_ = nh_private_.createTimer(timer_options); + airsim_lidar_update_timer_ = nh_private_.createTimer(timer_options); is_used_lidar_timer_cb_queue_ = true; } initialize_airsim(); } -// todo: error check. if state is not landed, return error. +// todo: error check. if state is not landed, return error. bool AirsimROSWrapper::takeoff_srv_cb(airsim_ros_pkgs::Takeoff::Request& request, airsim_ros_pkgs::Takeoff::Response& response, const std::string& vehicle_name) { std::lock_guard guard(drone_control_mutex_); if (request.waitOnLastTask) - static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name)->waitOnLastTask(); // todo value for timeout_sec? - // response.success = + static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name)->waitOnLastTask(); // todo value for timeout_sec? + // response.success = else static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name); - // response.success = + // response.success = return true; } @@ -376,13 +377,13 @@ bool AirsimROSWrapper::takeoff_group_srv_cb(airsim_ros_pkgs::TakeoffGroup::Reque if (request.waitOnLastTask) for(const auto& vehicle_name : request.vehicle_names) - static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name)->waitOnLastTask(); // todo value for timeout_sec? - // response.success = + static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name)->waitOnLastTask(); // todo value for timeout_sec? + // response.success = else for(const auto& vehicle_name : request.vehicle_names) static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name); - // response.success = - + // response.success = + return true; } @@ -392,12 +393,12 @@ bool AirsimROSWrapper::takeoff_all_srv_cb(airsim_ros_pkgs::Takeoff::Request& req if (request.waitOnLastTask) for(const auto& vehicle_name_ptr_pair : vehicle_name_ptr_map_) - static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name_ptr_pair.first)->waitOnLastTask(); // todo value for timeout_sec? - // response.success = + static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name_ptr_pair.first)->waitOnLastTask(); // todo value for timeout_sec? + // response.success = else for(const auto& vehicle_name_ptr_pair : vehicle_name_ptr_map_) static_cast(airsim_client_.get())->takeoffAsync(20, vehicle_name_ptr_pair.first); - // response.success = + // response.success = return true; } @@ -459,12 +460,12 @@ tf2::Quaternion AirsimROSWrapper::get_tf2_quat(const msr::airlib::Quaternionr& a msr::airlib::Quaternionr AirsimROSWrapper::get_airlib_quat(const geometry_msgs::Quaternion& geometry_msgs_quat) const { - return msr::airlib::Quaternionr(geometry_msgs_quat.w, geometry_msgs_quat.x, geometry_msgs_quat.y, geometry_msgs_quat.z); + return msr::airlib::Quaternionr(geometry_msgs_quat.w, geometry_msgs_quat.x, geometry_msgs_quat.y, geometry_msgs_quat.z); } msr::airlib::Quaternionr AirsimROSWrapper::get_airlib_quat(const tf2::Quaternion& tf2_quat) const { - return msr::airlib::Quaternionr(tf2_quat.w(), tf2_quat.x(), tf2_quat.y(), tf2_quat.z()); + return msr::airlib::Quaternionr(tf2_quat.w(), tf2_quat.x(), tf2_quat.y(), tf2_quat.z()); } void AirsimROSWrapper::car_cmd_cb(const airsim_ros_pkgs::CarControls::ConstPtr& msg, const std::string& vehicle_name) @@ -494,7 +495,7 @@ void AirsimROSWrapper::vel_cmd_body_frame_cb(const airsim_ros_pkgs::VelCmd::Cons std::lock_guard guard(drone_control_mutex_); auto drone = static_cast(vehicle_name_ptr_map_[vehicle_name].get()); - + double roll, pitch, yaw; tf2::Matrix3x3(get_tf2_quat(drone->curr_drone_state.kinematics_estimated.pose.orientation)).getRPY(roll, pitch, yaw); // ros uses xyzw @@ -519,7 +520,7 @@ void AirsimROSWrapper::vel_cmd_group_body_frame_cb(const airsim_ros_pkgs::VelCmd double roll, pitch, yaw; tf2::Matrix3x3(get_tf2_quat(drone->curr_drone_state.kinematics_estimated.pose.orientation)).getRPY(roll, pitch, yaw); // ros uses xyzw - + // todo do actual body frame? drone->vel_cmd.x = (msg.twist.linear.x * cos(yaw)) - (msg.twist.linear.y * sin(yaw)); //body frame assuming zero pitch roll drone->vel_cmd.y = (msg.twist.linear.x * sin(yaw)) + (msg.twist.linear.y * cos(yaw)); //body frame @@ -572,7 +573,7 @@ void AirsimROSWrapper::vel_cmd_world_frame_cb(const airsim_ros_pkgs::VelCmd::Con drone->has_vel_cmd = true; } -// this is kinda unnecessary but maybe it makes life easier for the end user. +// this is kinda unnecessary but maybe it makes life easier for the end user. void AirsimROSWrapper::vel_cmd_group_world_frame_cb(const airsim_ros_pkgs::VelCmdGroup& msg) { std::lock_guard guard(drone_control_mutex_); @@ -621,7 +622,7 @@ void AirsimROSWrapper::gimbal_angle_quat_cmd_cb(const airsim_ros_pkgs::GimbalAng gimbal_cmd_.target_quat = get_airlib_quat(quat_control_cmd); // airsim uses wxyz gimbal_cmd_.camera_name = gimbal_angle_quat_cmd_msg.camera_name; gimbal_cmd_.vehicle_name = gimbal_angle_quat_cmd_msg.vehicle_name; - has_gimbal_cmd_ = true; + has_gimbal_cmd_ = true; } catch (tf2::TransformException& ex) { @@ -632,7 +633,7 @@ void AirsimROSWrapper::gimbal_angle_quat_cmd_cb(const airsim_ros_pkgs::GimbalAng // todo support multiple gimbal commands // 1. find quaternion of default gimbal pose // 2. forward multiply with quaternion equivalent to desired euler commands (in degrees) -// 3. call airsim client's setCameraPose which sets camera pose wrt world (or takeoff?) ned frame. todo +// 3. call airsim client's setCameraPose which sets camera pose wrt world (or takeoff?) ned frame. todo void AirsimROSWrapper::gimbal_angle_euler_cmd_cb(const airsim_ros_pkgs::GimbalAngleEulerCmd& gimbal_angle_euler_cmd_msg) { try @@ -643,7 +644,7 @@ void AirsimROSWrapper::gimbal_angle_euler_cmd_cb(const airsim_ros_pkgs::GimbalAn gimbal_cmd_.target_quat = get_airlib_quat(quat_control_cmd); gimbal_cmd_.camera_name = gimbal_angle_euler_cmd_msg.camera_name; gimbal_cmd_.vehicle_name = gimbal_angle_euler_cmd_msg.vehicle_name; - has_gimbal_cmd_ = true; + has_gimbal_cmd_ = true; } catch (tf2::TransformException& ex) { @@ -691,7 +692,7 @@ nav_msgs::Odometry AirsimROSWrapper::get_odom_msg_from_car_state(const msr::airl { std::swap(odom_msg.pose.pose.position.x, odom_msg.pose.pose.position.y); odom_msg.pose.pose.position.z = -odom_msg.pose.pose.position.z; - std::swap(odom_msg.pose.pose.orientation.x, odom_msg.pose.pose.orientation.y); + std::swap(odom_msg.pose.pose.orientation.x, odom_msg.pose.pose.orientation.y); odom_msg.pose.pose.orientation.z = -odom_msg.pose.pose.orientation.z; std::swap(odom_msg.twist.twist.linear.x, odom_msg.twist.twist.linear.y); odom_msg.twist.twist.linear.z = -odom_msg.twist.twist.linear.z; @@ -725,7 +726,7 @@ nav_msgs::Odometry AirsimROSWrapper::get_odom_msg_from_multirotor_state(const ms { std::swap(odom_msg.pose.pose.position.x, odom_msg.pose.pose.position.y); odom_msg.pose.pose.position.z = -odom_msg.pose.pose.position.z; - std::swap(odom_msg.pose.pose.orientation.x, odom_msg.pose.pose.orientation.y); + std::swap(odom_msg.pose.pose.orientation.x, odom_msg.pose.pose.orientation.y); odom_msg.pose.pose.orientation.z = -odom_msg.pose.pose.orientation.z; std::swap(odom_msg.twist.twist.linear.x, odom_msg.twist.twist.linear.y); odom_msg.twist.twist.linear.z = -odom_msg.twist.twist.linear.z; @@ -751,8 +752,8 @@ sensor_msgs::PointCloud2 AirsimROSWrapper::get_lidar_msg_from_airsim(const msr:: lidar_msg.width = lidar_data.point_cloud.size() / 3; lidar_msg.fields.resize(3); - lidar_msg.fields[0].name = "x"; - lidar_msg.fields[1].name = "y"; + lidar_msg.fields[0].name = "x"; + lidar_msg.fields[1].name = "y"; lidar_msg.fields[2].name = "z"; int offset = 0; @@ -828,8 +829,8 @@ sensor_msgs::MagneticField AirsimROSWrapper::get_mag_msg_from_airsim(const msr:: mag_msg.magnetic_field.x = mag_data.magnetic_field_body.x(); mag_msg.magnetic_field.y = mag_data.magnetic_field_body.y(); mag_msg.magnetic_field.z = mag_data.magnetic_field_body.z(); - std::copy(std::begin(mag_data.magnetic_field_covariance), - std::end(mag_data.magnetic_field_covariance), + std::copy(std::begin(mag_data.magnetic_field_covariance), + std::end(mag_data.magnetic_field_covariance), std::begin(mag_msg.magnetic_field_covariance)); mag_msg.header.stamp = airsim_timestamp_to_ros(mag_data.time_stamp); @@ -842,12 +843,12 @@ sensor_msgs::NavSatFix AirsimROSWrapper::get_gps_msg_from_airsim(const msr::airl sensor_msgs::NavSatFix gps_msg; gps_msg.header.stamp = airsim_timestamp_to_ros(gps_data.time_stamp); gps_msg.latitude = gps_data.gnss.geo_point.latitude; - gps_msg.longitude = gps_data.gnss.geo_point.longitude; + gps_msg.longitude = gps_data.gnss.geo_point.longitude; gps_msg.altitude = gps_data.gnss.geo_point.altitude; gps_msg.status.service = sensor_msgs::NavSatStatus::SERVICE_GLONASS; gps_msg.status.status = gps_data.gnss.fix_type; - // gps_msg.position_covariance_type = - // gps_msg.position_covariance = + // gps_msg.position_covariance_type = + // gps_msg.position_covariance = return gps_msg; } @@ -890,7 +891,7 @@ sensor_msgs::Imu AirsimROSWrapper::get_imu_msg_from_airsim(const msr::airlib::Im imu_msg.angular_velocity.y = imu_data.angular_velocity.y(); imu_msg.angular_velocity.z = imu_data.angular_velocity.z(); - // meters/s2^m + // meters/s2^m imu_msg.linear_acceleration.x = imu_data.linear_acceleration.x(); imu_msg.linear_acceleration.y = imu_data.linear_acceleration.y(); imu_msg.linear_acceleration.z = imu_data.linear_acceleration.z(); @@ -906,7 +907,7 @@ void AirsimROSWrapper::publish_odom_tf(const nav_msgs::Odometry& odom_msg) { geometry_msgs::TransformStamped odom_tf; odom_tf.header = odom_msg.header; - odom_tf.child_frame_id = odom_msg.child_frame_id; + odom_tf.child_frame_id = odom_msg.child_frame_id; odom_tf.transform.translation.x = odom_msg.pose.pose.position.x; odom_tf.transform.translation.y = odom_msg.pose.pose.position.y; odom_tf.transform.translation.z = odom_msg.pose.pose.position.z; @@ -921,7 +922,7 @@ airsim_ros_pkgs::GPSYaw AirsimROSWrapper::get_gps_msg_from_airsim_geo_point(cons { airsim_ros_pkgs::GPSYaw gps_msg; gps_msg.latitude = geo_point.latitude; - gps_msg.longitude = geo_point.longitude; + gps_msg.longitude = geo_point.longitude; gps_msg.altitude = geo_point.altitude; return gps_msg; } @@ -930,7 +931,7 @@ sensor_msgs::NavSatFix AirsimROSWrapper::get_gps_sensor_msg_from_airsim_geo_poin { sensor_msgs::NavSatFix gps_msg; gps_msg.latitude = geo_point.latitude; - gps_msg.longitude = geo_point.longitude; + gps_msg.longitude = geo_point.longitude; gps_msg.altitude = geo_point.altitude; return gps_msg; } @@ -955,7 +956,7 @@ ros::Time AirsimROSWrapper::airsim_timestamp_to_ros(const msr::airlib::TTimePoin void AirsimROSWrapper::drone_state_timer_cb(const ros::TimerEvent& event) { try - { + { // todo this is global origin origin_geo_point_pub_.publish(origin_geo_point_msg_); @@ -1013,7 +1014,7 @@ ros::Time AirsimROSWrapper::update_state() for (auto& vehicle_name_ptr_pair : vehicle_name_ptr_map_) { ros::Time vehicle_time; - // get drone state from airsim + // get drone state from airsim auto& vehicle_ros = vehicle_name_ptr_pair.second; // vehicle environment, we can get ambient temperature here and other truths @@ -1054,20 +1055,20 @@ ros::Time AirsimROSWrapper::update_state() vehicle_ros->gps_sensor_msg.header.stamp = vehicle_time; vehicle_ros->curr_odom = get_odom_msg_from_car_state(car->curr_car_state); - + airsim_ros_pkgs::CarState state_msg = get_roscarstate_msg_from_car_state(car->curr_car_state); state_msg.header.frame_id = vehicle_ros->vehicle_name; car->car_state_msg = state_msg; } vehicle_ros->stamp = vehicle_time; - + airsim_ros_pkgs::Environment env_msg = get_environment_msg_from_airsim(env_data); env_msg.header.frame_id = vehicle_ros->vehicle_name; env_msg.header.stamp = vehicle_time; vehicle_ros->env_msg = env_msg; - // convert airsim drone state to ROS msgs + // convert airsim drone state to ROS msgs vehicle_ros->curr_odom.header.frame_id = vehicle_ros->vehicle_name; vehicle_ros->curr_odom.child_frame_id = vehicle_ros->odom_frame_id; vehicle_ros->curr_odom.header.stamp = vehicle_time; @@ -1108,7 +1109,7 @@ void AirsimROSWrapper::publish_vehicle_state() auto baro_data = airsim_client_->getBarometerData(sensor_publisher.sensor_name, vehicle_ros->vehicle_name); airsim_ros_pkgs::Altimeter alt_msg = get_altimeter_msg_from_airsim(baro_data); alt_msg.header.frame_id = vehicle_ros->vehicle_name; - sensor_publisher.publisher.publish(alt_msg); + sensor_publisher.publisher.publish(alt_msg); break; } case SensorBase::SensorType::Imu: @@ -1169,7 +1170,7 @@ void AirsimROSWrapper::update_commands() if (drone->has_vel_cmd) { std::lock_guard guard(drone_control_mutex_); - static_cast(airsim_client_.get())->moveByVelocityAsync(drone->vel_cmd.x, drone->vel_cmd.y, drone->vel_cmd.z, vel_cmd_duration_, + static_cast(airsim_client_.get())->moveByVelocityAsync(drone->vel_cmd.x, drone->vel_cmd.y, drone->vel_cmd.z, vel_cmd_duration_, msr::airlib::DrivetrainType::MaxDegreeOfFreedom, drone->vel_cmd.yaw_mode, drone->vehicle_name); } drone->has_vel_cmd = false; @@ -1187,7 +1188,7 @@ void AirsimROSWrapper::update_commands() } } - // Only camera rotation, no translation movement of camera + // Only camera rotation, no translation movement of camera if (has_gimbal_cmd_) { std::lock_guard guard(drone_control_mutex_); @@ -1197,7 +1198,7 @@ void AirsimROSWrapper::update_commands() has_gimbal_cmd_ = false; } -// airsim uses nans for zeros in settings.json. we set them to zeros here for handling tfs in ROS +// airsim uses nans for zeros in settings.json. we set them to zeros here for handling tfs in ROS void AirsimROSWrapper::set_nans_to_zeros_in_pose(VehicleSetting& vehicle_setting) const { if (std::isnan(vehicle_setting.position.x())) @@ -1242,27 +1243,6 @@ void AirsimROSWrapper::set_nans_to_zeros_in_pose(const VehicleSetting& vehicle_s } -void AirsimROSWrapper::set_nans_to_zeros_in_pose(const VehicleSetting& vehicle_setting, LidarSetting& lidar_setting) const -{ - if (std::isnan(lidar_setting.position.x())) - lidar_setting.position.x() = vehicle_setting.position.x(); - - if (std::isnan(lidar_setting.position.y())) - lidar_setting.position.y() = vehicle_setting.position.y(); - - if (std::isnan(lidar_setting.position.z())) - lidar_setting.position.z() = vehicle_setting.position.z(); - - if (std::isnan(lidar_setting.rotation.yaw)) - lidar_setting.rotation.yaw = vehicle_setting.rotation.yaw; - - if (std::isnan(lidar_setting.rotation.pitch)) - lidar_setting.rotation.pitch = vehicle_setting.rotation.pitch; - - if (std::isnan(lidar_setting.rotation.roll)) - lidar_setting.rotation.roll = vehicle_setting.rotation.roll; -} - void AirsimROSWrapper::append_static_vehicle_tf(VehicleROS* vehicle_ros, const VehicleSetting& vehicle_setting) { geometry_msgs::TransformStamped vehicle_tf_msg; @@ -1271,7 +1251,7 @@ void AirsimROSWrapper::append_static_vehicle_tf(VehicleROS* vehicle_ros, const V vehicle_tf_msg.child_frame_id = vehicle_ros->vehicle_name; vehicle_tf_msg.transform.translation.x = vehicle_setting.position.x(); vehicle_tf_msg.transform.translation.y = vehicle_setting.position.y(); - vehicle_tf_msg.transform.translation.z = vehicle_setting.position.z(); + vehicle_tf_msg.transform.translation.z = vehicle_setting.position.z(); tf2::Quaternion quat; quat.setRPY(vehicle_setting.rotation.roll, vehicle_setting.rotation.pitch, vehicle_setting.rotation.yaw); vehicle_tf_msg.transform.rotation.x = quat.x(); @@ -1290,20 +1270,18 @@ void AirsimROSWrapper::append_static_vehicle_tf(VehicleROS* vehicle_ros, const V vehicle_ros->static_tf_msg_vec.emplace_back(vehicle_tf_msg); } -void AirsimROSWrapper::append_static_lidar_tf(VehicleROS* vehicle_ros, const std::string& lidar_name, const LidarSetting& lidar_setting) +void AirsimROSWrapper::append_static_lidar_tf(VehicleROS* vehicle_ros, const std::string& lidar_name, const msr::airlib::LidarSimpleParams& lidar_setting) { geometry_msgs::TransformStamped lidar_tf_msg; lidar_tf_msg.header.frame_id = vehicle_ros->vehicle_name + "/" + odom_frame_id_; lidar_tf_msg.child_frame_id = vehicle_ros->vehicle_name + "/" + lidar_name; - lidar_tf_msg.transform.translation.x = lidar_setting.position.x(); - lidar_tf_msg.transform.translation.y = lidar_setting.position.y(); - lidar_tf_msg.transform.translation.z = lidar_setting.position.z(); - tf2::Quaternion quat; - quat.setRPY(lidar_setting.rotation.roll, lidar_setting.rotation.pitch, lidar_setting.rotation.yaw); - lidar_tf_msg.transform.rotation.x = quat.x(); - lidar_tf_msg.transform.rotation.y = quat.y(); - lidar_tf_msg.transform.rotation.z = quat.z(); - lidar_tf_msg.transform.rotation.w = quat.w(); + lidar_tf_msg.transform.translation.x = lidar_setting.relative_pose.position.x(); + lidar_tf_msg.transform.translation.y = lidar_setting.relative_pose.position.y(); + lidar_tf_msg.transform.translation.z = lidar_setting.relative_pose.position.z(); + lidar_tf_msg.transform.rotation.x = lidar_setting.relative_pose.orientation.x(); + lidar_tf_msg.transform.rotation.y = lidar_setting.relative_pose.orientation.y(); + lidar_tf_msg.transform.rotation.z = lidar_setting.relative_pose.orientation.z(); + lidar_tf_msg.transform.rotation.w = lidar_setting.relative_pose.orientation.w(); if (isENU_) { @@ -1345,11 +1323,11 @@ void AirsimROSWrapper::append_static_camera_tf(VehicleROS* vehicle_ros, const st tf2::Quaternion quat_cam_body; tf2::Quaternion quat_cam_optical; tf2::convert(static_cam_tf_body_msg.transform.rotation, quat_cam_body); - tf2::Matrix3x3 mat_cam_body(quat_cam_body); + tf2::Matrix3x3 mat_cam_body(quat_cam_body); tf2::Matrix3x3 mat_cam_optical; - mat_cam_optical.setValue(mat_cam_body.getColumn(1).getX(), mat_cam_body.getColumn(2).getX(), mat_cam_body.getColumn(0).getX(), + mat_cam_optical.setValue(mat_cam_body.getColumn(1).getX(), mat_cam_body.getColumn(2).getX(), mat_cam_body.getColumn(0).getX(), mat_cam_body.getColumn(1).getY(), mat_cam_body.getColumn(2).getY(), mat_cam_body.getColumn(0).getY(), - mat_cam_body.getColumn(1).getZ(), mat_cam_body.getColumn(2).getZ(), mat_cam_body.getColumn(0).getZ()); + mat_cam_body.getColumn(1).getZ(), mat_cam_body.getColumn(2).getZ(), mat_cam_body.getColumn(0).getZ()); mat_cam_optical.getRotation(quat_cam_optical); quat_cam_optical.normalize(); tf2::convert(quat_cam_optical, static_cam_tf_optical_msg.transform.rotation); @@ -1359,7 +1337,7 @@ void AirsimROSWrapper::append_static_camera_tf(VehicleROS* vehicle_ros, const st } void AirsimROSWrapper::img_response_timer_cb(const ros::TimerEvent& event) -{ +{ try { int image_response_idx = 0; @@ -1367,11 +1345,11 @@ void AirsimROSWrapper::img_response_timer_cb(const ros::TimerEvent& event) { const std::vector& img_response = airsim_client_images_.simGetImages(airsim_img_request_vehicle_name_pair.first, airsim_img_request_vehicle_name_pair.second); - if (img_response.size() == airsim_img_request_vehicle_name_pair.first.size()) + if (img_response.size() == airsim_img_request_vehicle_name_pair.first.size()) { process_and_publish_img_response(img_response, image_response_idx, airsim_img_request_vehicle_name_pair.second); image_response_idx += img_response.size(); - } + } } } @@ -1384,7 +1362,7 @@ void AirsimROSWrapper::img_response_timer_cb(const ros::TimerEvent& event) } void AirsimROSWrapper::lidar_timer_cb(const ros::TimerEvent& event) -{ +{ try { for (auto& vehicle_name_ptr_pair : vehicle_name_ptr_map_) @@ -1420,7 +1398,7 @@ cv::Mat AirsimROSWrapper::manual_decode_depth(const ImageResponse& img_response) } sensor_msgs::ImagePtr AirsimROSWrapper::get_img_msg_from_response(const ImageResponse& img_response, - const ros::Time curr_ros_time, + const ros::Time curr_ros_time, const std::string frame_id) { sensor_msgs::ImagePtr img_msg_ptr = boost::make_shared(); @@ -1441,7 +1419,7 @@ sensor_msgs::ImagePtr AirsimROSWrapper::get_depth_img_msg_from_response(const Im const ros::Time curr_ros_time, const std::string frame_id) { - // todo using img_response.image_data_float direclty as done get_img_msg_from_response() throws an error, + // todo using img_response.image_data_float direclty as done get_img_msg_from_response() throws an error, // hence the dependency on opencv and cv_bridge. however, this is an extremely fast op, so no big deal. cv::Mat depth_img = manual_decode_depth(img_response); sensor_msgs::ImagePtr depth_img_msg = cv_bridge::CvImage(std_msgs::Header(), "32FC1", depth_img).toImageMsg(); @@ -1462,28 +1440,28 @@ sensor_msgs::CameraInfo AirsimROSWrapper::generate_cam_info(const std::string& c float f_x = (capture_setting.width / 2.0) / tan(math_common::deg2rad(capture_setting.fov_degrees / 2.0)); // todo focal length in Y direction should be same as X it seems. this can change in future a scene capture component which exactly correponds to a cine camera // float f_y = (capture_setting.height / 2.0) / tan(math_common::deg2rad(fov_degrees / 2.0)); - cam_info_msg.K = {f_x, 0.0, capture_setting.width / 2.0, - 0.0, f_x, capture_setting.height / 2.0, + cam_info_msg.K = {f_x, 0.0, capture_setting.width / 2.0, + 0.0, f_x, capture_setting.height / 2.0, 0.0, 0.0, 1.0}; cam_info_msg.P = {f_x, 0.0, capture_setting.width / 2.0, 0.0, - 0.0, f_x, capture_setting.height / 2.0, 0.0, + 0.0, f_x, capture_setting.height / 2.0, 0.0, 0.0, 0.0, 1.0, 0.0}; return cam_info_msg; } void AirsimROSWrapper::process_and_publish_img_response(const std::vector& img_response_vec, const int img_response_idx, const std::string& vehicle_name) -{ +{ // todo add option to use airsim time (image_response.TTimePoint) like Gazebo /use_sim_time param - ros::Time curr_ros_time = ros::Time::now(); + ros::Time curr_ros_time = ros::Time::now(); int img_response_idx_internal = img_response_idx; for (const auto& curr_img_response : img_response_vec) { - // todo publishing a tf for each capture type seems stupid. but it foolproofs us against render thread's async stuff, I hope. - // Ideally, we should loop over cameras and then captures, and publish only one tf. + // todo publishing a tf for each capture type seems stupid. but it foolproofs us against render thread's async stuff, I hope. + // Ideally, we should loop over cameras and then captures, and publish only one tf. publish_camera_tf(curr_img_response, curr_ros_time, vehicle_name, curr_img_response.camera_name); - // todo simGetCameraInfo is wrong + also it's only for image type -1. + // todo simGetCameraInfo is wrong + also it's only for image type -1. // msr::airlib::CameraInfo camera_info = airsim_client_.simGetCameraInfo(curr_img_response.camera_name); // update timestamp of saved cam info msgs @@ -1493,15 +1471,15 @@ void AirsimROSWrapper::process_and_publish_img_response(const std::vector Date: Tue, 27 Apr 2021 18:35:30 -0700 Subject: [PATCH 23/37] script to test flying up high --- PythonClient/multirotor/high.py | 52 +++++++++++++++++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 PythonClient/multirotor/high.py diff --git a/PythonClient/multirotor/high.py b/PythonClient/multirotor/high.py new file mode 100644 index 0000000000..afdcadff91 --- /dev/null +++ b/PythonClient/multirotor/high.py @@ -0,0 +1,52 @@ +import setup_path +import airsim + +import sys +import time + +print("""This script is designed to fly on the streets of the Neighborhood environment +and assumes the unreal position of the drone is [160, -1500, 120].""") + +client = airsim.MultirotorClient() +client.confirmConnection() +client.enableApiControl(True) + +print("arming the drone...") +client.armDisarm(True) + +state = client.getMultirotorState() +if state.landed_state == airsim.LandedState.Landed: + print("taking off...") + client.takeoffAsync().join() +else: + client.hoverAsync().join() + +time.sleep(1) + +state = client.getMultirotorState() +if state.landed_state == airsim.LandedState.Landed: + print("take off failed...") + sys.exit(1) + +# AirSim uses NED coordinates so negative axis is up. +# z of -50 is 50 meters above the original launch point. +z = -50 +print("make sure we are hovering at 50 meters...") +client.moveToZAsync(z, 1).join() + +# see https://github.com/Microsoft/AirSim/wiki/moveOnPath-demo + +# this method is async and we are not waiting for the result since we are passing timeout_sec=0. + +time.sleep(1) + +# come down quickly +z = -7 +client.moveToZAsync(z, 5).join() + +print("landing...") +client.landAsync().join() +print("disarming...") +client.armDisarm(False) +client.enableApiControl(False) +print("done.") From 0b81265bee0e028dec4ae1218cd4033376780c93 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Wed, 28 Apr 2021 09:42:01 -0700 Subject: [PATCH 24/37] fix missing stopLoggingReceiveMessage --- .../multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index d2be5f7183..09eda7ad4c 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -368,11 +368,15 @@ namespace msr { namespace airlib { auto con = mav_vehicle_->getConnection(); if (con != nullptr) { con->stopLoggingSendMessage(); - addStatusMessage(Utils::stringf("Closing log file: %s", log_file_name_.c_str())); + con->stopLoggingReceiveMessage(); + } + if (connection_ != nullptr) { + connection_->stopLoggingSendMessage(); + connection_->stopLoggingReceiveMessage(); } - connection_->stopLoggingSendMessage(); } if (log_ != nullptr) { + addStatusMessage(Utils::stringf("Closing log file: %s", log_file_name_.c_str())); log_->close(); log_ = nullptr; } From 62b08da606f101b4c08972d96c4410aa1a5d514e Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Wed, 28 Apr 2021 11:32:08 -0700 Subject: [PATCH 25/37] consistency with logviewer logging and add docs. --- .../mavlink/MavLinkMultirotorApi.hpp | 34 ++++++++++++++++--- docs/log_viewer.md | 10 ++++-- docs/px4_logging.md | 4 ++- 3 files changed, 39 insertions(+), 9 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 63385391fe..49b7105b6c 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -832,15 +832,30 @@ class MavLinkMultirotorApi : public MultirotorApiBase MavLinkLogViewerLog(std::shared_ptr proxy) { proxy_ = proxy; } + ~MavLinkLogViewerLog() { + proxy_ = nullptr; + } void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override { - unused(timestamp); - mavlinkcom::MavLinkMessage copy; - ::memcpy(©, &msg, sizeof(mavlinkcom::MavLinkMessage)); - proxy_->sendMessage(copy); + if (proxy_ != nullptr) { + unused(timestamp); + mavlinkcom::MavLinkMessage copy; + ::memcpy(©, &msg, sizeof(mavlinkcom::MavLinkMessage)); + try { + proxy_->sendMessage(copy); + } + catch (std::exception&) { + failures++; + if (failures == 100) { + // hmmm, doesn't like the proxy, bad socket perhaps, so stop trying... + proxy_ = nullptr; + } + } + } } private: std::shared_ptr proxy_; + int failures = 0; }; @@ -873,6 +888,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase setNormalMode(); } + connection_->stopLoggingSendMessage(); + connection_->stopLoggingReceiveMessage(); connection_->close(); } @@ -884,6 +901,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase auto c = mav_vehicle_->getConnection(); if (c != nullptr) { c->stopLoggingSendMessage(); + c->stopLoggingReceiveMessage(); } mav_vehicle_->close(); mav_vehicle_ = nullptr; @@ -1139,7 +1157,13 @@ class MavLinkMultirotorApi : public MultirotorApiBase logviewer_out_proxy_ = nullptr; } else if (mav_vehicle_ != nullptr) { - mav_vehicle_->getConnection()->startLoggingSendMessage(std::make_shared(logviewer_out_proxy_)); + auto proxylog = std::make_shared(logviewer_out_proxy_); + mav_vehicle_->getConnection()->startLoggingSendMessage(proxylog); + mav_vehicle_->getConnection()->startLoggingReceiveMessage(proxylog); + if (connection_ != nullptr) { + connection_->startLoggingSendMessage(proxylog); + connection_->startLoggingReceiveMessage(proxylog); + } } } return logviewer_proxy_ != nullptr; diff --git a/docs/log_viewer.md b/docs/log_viewer.md index 61e17106f3..2f97249481 100644 --- a/docs/log_viewer.md +++ b/docs/log_viewer.md @@ -20,7 +20,7 @@ log files so you can compare the data from each. ### Realtime -You can also get a realtime view if you connect the LogViewer `before` you run the simulation. +You can also get a realtime view if you connect the LogViewer `before` you run the simulation. ![connect](images/log_viewer_connect.png) @@ -38,9 +38,13 @@ For this to work you need to configure the `settings.json` with the following se } } ``` + +Note: do not use the "Logs" setting when you want realtime LogViewer logging. Logging to +a file using "Logs" is mutually exclusive. with LogViewer logging. + Simply press the blue connector button on the top right corner of the window, select the Socket -`tab`, enter the port number `14388`, and your `localhost` network. If you are using WSL 2 on -Windows then select `vEthernet (WSL)`. +`tab`, enter the port number `14388`, and your `localhost` network. If you are using WSL 2 on +Windows then select `vEthernet (WSL)`. If you do choose `vEthernet (WSL)` then make sure you also set `LocalHostIp` and `LogViewerHostIp` to the matching WSL ethernet address, something like `172.31.64.1`. diff --git a/docs/px4_logging.md b/docs/px4_logging.md index e23b710ad8..68a81e7c3e 100644 --- a/docs/px4_logging.md +++ b/docs/px4_logging.md @@ -25,10 +25,12 @@ You will then see log files organized by date in d:\temp\logs, specifically *inp ## MavLink LogViewer For MavLink enabled drones, you can also use our [Log Viewer](log_viewer.md) to visualize the streams of data. +If you enable this form of realtime logging you should not use the "Logs" setting above, these two forms of logging +are mutually exclusive. ## PX4 Log in SITL Mode -In SITL mode, please a log file is produced when drone is armed. The SITL terminal will contain the path to the log file, it should look something like this +In SITL mode, please a log file is produced when drone is armed. The SITL terminal will contain the path to the log file, it should look something like this ``` INFO [logger] Opened log file: rootfs/fs/microsd/log/2017-03-27/20_02_49.ulg ``` From 6db1f215eef16c6d8cbbcdc4fe8797850bbb44aa Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Wed, 28 Apr 2021 14:26:49 -0700 Subject: [PATCH 26/37] Pause physics update loop while waiting for actuator controls during lockstep enabled mavlink multirotor update loop. --- AirLib/include/common/UpdatableContainer.hpp | 19 +++++++++++--- AirLib/include/common/UpdatableObject.hpp | 19 +++++++++++++- AirLib/include/physics/FastPhysicsEngine.hpp | 3 ++- AirLib/include/physics/PhysicsBody.hpp | 2 ++ AirLib/include/physics/PhysicsEngineBase.hpp | 26 +------------------ AirLib/include/physics/PhysicsWorld.hpp | 5 +++- AirLib/include/physics/World.hpp | 8 +++++- .../multirotor/MultiRotorPhysicsBody.hpp | 2 ++ .../mavlink/MavLinkMultirotorApi.hpp | 17 ++++++++++++ 9 files changed, 68 insertions(+), 33 deletions(-) diff --git a/AirLib/include/common/UpdatableContainer.hpp b/AirLib/include/common/UpdatableContainer.hpp index b841d8f44b..e55168f530 100644 --- a/AirLib/include/common/UpdatableContainer.hpp +++ b/AirLib/include/common/UpdatableContainer.hpp @@ -24,10 +24,21 @@ class UpdatableContainer : public UpdatableObject { const TUpdatableObjectPtr& at(uint index) const { members_.at(index); } TUpdatableObjectPtr& at(uint index) { return members_.at(index); } //allow to override membership modifications - virtual void clear() { members_.clear(); } - virtual void insert(TUpdatableObjectPtr member) { members_.push_back(member); } - virtual void erase_remove(TUpdatableObjectPtr obj) { - members_.erase(std::remove(members_.begin(), members_.end(), obj), members_.end()); } + virtual void clear() { + for (auto m : members_) { + m->setParent(nullptr); + } + members_.clear(); + } + virtual void insert(TUpdatableObjectPtr member) { + member->setParent(this); + members_.push_back(member); + } + virtual void erase_remove(TUpdatableObjectPtr member) { + member->setParent(nullptr); + members_.erase(std::remove(members_.begin(), members_.end(), member), members_.end()); + } + public: //*** Start: UpdatableState implementation ***// diff --git a/AirLib/include/common/UpdatableObject.hpp b/AirLib/include/common/UpdatableObject.hpp index 579f2350fb..620f54e7d1 100644 --- a/AirLib/include/common/UpdatableObject.hpp +++ b/AirLib/include/common/UpdatableObject.hpp @@ -24,7 +24,6 @@ Do not call reset() from constructor or initialization because that will produce init->reset calls for base-derived class that would be incorrect. */ - class UpdatableObject { public: void reset() @@ -73,6 +72,22 @@ class UpdatableObject { return ClockFactory::get(); } + UpdatableObject* getParent() { + return parent_; + } + + void setParent(UpdatableObject* container) { + parent_ = container; + } + + std::string getName(){ + return name_; + } + + void setName(const std::string& name) { + this->name_ = name; + } + protected: virtual void resetImplementation() = 0; virtual void failResetUpdateOrdering(std::string err) @@ -84,6 +99,8 @@ class UpdatableObject { bool reset_called = false; bool update_called = false; bool reset_in_progress = false; + UpdatableObject* parent_ = nullptr; + std::string name_; }; }} //namespace diff --git a/AirLib/include/physics/FastPhysicsEngine.hpp b/AirLib/include/physics/FastPhysicsEngine.hpp index ad962a00ab..035f89d0fc 100644 --- a/AirLib/include/physics/FastPhysicsEngine.hpp +++ b/AirLib/include/physics/FastPhysicsEngine.hpp @@ -20,7 +20,8 @@ class FastPhysicsEngine : public PhysicsEngineBase { public: FastPhysicsEngine(bool enable_ground_lock = true, Vector3r wind = Vector3r::Zero()) : enable_ground_lock_(enable_ground_lock), wind_(wind) - { + { + setName("FastPhysicsEngine"); } //*** Start: UpdatableState implementation ***// diff --git a/AirLib/include/physics/PhysicsBody.hpp b/AirLib/include/physics/PhysicsBody.hpp index d2749259b3..a20daffc7c 100644 --- a/AirLib/include/physics/PhysicsBody.hpp +++ b/AirLib/include/physics/PhysicsBody.hpp @@ -84,7 +84,9 @@ class PhysicsBody : public UpdatableObject { inertia_ = inertia; inertia_inv_ = inertia_.inverse(); environment_ = environment; + environment_->setParent(this); kinematics_ = kinematics; + kinematics_->setParent(this); } //enable physics body detection diff --git a/AirLib/include/physics/PhysicsEngineBase.hpp b/AirLib/include/physics/PhysicsEngineBase.hpp index a8b09f28ba..dd06c3f829 100644 --- a/AirLib/include/physics/PhysicsEngineBase.hpp +++ b/AirLib/include/physics/PhysicsEngineBase.hpp @@ -10,7 +10,7 @@ namespace msr { namespace airlib { -class PhysicsEngineBase : public UpdatableObject { +class PhysicsEngineBase : public UpdatableContainer { public: virtual void update() override { @@ -23,31 +23,7 @@ class PhysicsEngineBase : public UpdatableObject { //default nothing to report for physics engine } - //TODO: reduce copy-past from UpdatableContainer which has same code - /********************** Container interface **********************/ - typedef PhysicsBody* TUpdatableObjectPtr; - typedef vector MembersContainer; - typedef typename MembersContainer::iterator iterator; - typedef typename MembersContainer::const_iterator const_iterator; - typedef typename MembersContainer::value_type value_type; - - iterator begin() { return members_.begin(); } - iterator end() { return members_.end(); } - const_iterator begin() const { return members_.begin(); } - const_iterator end() const { return members_.end(); } - uint size() const { return static_cast(members_.size()); } - const TUpdatableObjectPtr &at(uint index) const { return members_.at(index); } - TUpdatableObjectPtr &at(uint index) { return members_.at(index); } - //allow to override membership modifications - virtual void clear() { members_.clear(); } - virtual void insert(TUpdatableObjectPtr member) { members_.push_back(member); } - virtual void erase_remove(TUpdatableObjectPtr obj) { - members_.erase(std::remove(members_.begin(), members_.end(), obj), members_.end()); } - virtual void setWind(const Vector3r& wind) { unused(wind); }; - -private: - MembersContainer members_; }; diff --git a/AirLib/include/physics/PhysicsWorld.hpp b/AirLib/include/physics/PhysicsWorld.hpp index dbf0ec8302..b56fc8eb92 100644 --- a/AirLib/include/physics/PhysicsWorld.hpp +++ b/AirLib/include/physics/PhysicsWorld.hpp @@ -13,7 +13,7 @@ namespace msr { namespace airlib { -class PhysicsWorld { +class PhysicsWorld : UpdatableObject { public: PhysicsWorld(std::unique_ptr physics_engine, const std::vector& bodies, uint64_t update_period_nanos = 3000000LL, bool state_reporter_enabled = false, @@ -21,6 +21,7 @@ class PhysicsWorld { ) : world_(std::move(physics_engine)) { + setName("PhysicsWorld"); enableStateReport(state_reporter_enabled); update_period_nanos_ = update_period_nanos; initializeWorld(bodies, start_async_updator); @@ -108,6 +109,8 @@ class PhysicsWorld { world_.setFrameNumber(frameNumber); } + void resetImplementation() override {} + private: void initializeWorld(const std::vector& bodies, bool start_async_updator) { diff --git a/AirLib/include/physics/World.hpp b/AirLib/include/physics/World.hpp index bf88c188b6..b8c0cc2fd3 100644 --- a/AirLib/include/physics/World.hpp +++ b/AirLib/include/physics/World.hpp @@ -20,7 +20,8 @@ class World : public UpdatableContainer { : physics_engine_(std::move(physics_engine)) { World::clear(); - + setName("World"); + physics_engine_->setParent(this); if (physics_engine) physics_engine_->clear(); } @@ -118,6 +119,11 @@ class World : public UpdatableContainer { return executor_.isPaused(); } + void pauseForTime(double seconds) + { + executor_.pauseForTime(seconds); + } + void continueForTime(double seconds) { executor_.continueForTime(seconds); diff --git a/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp b/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp index 81902d6cfb..f0fe7ca87e 100644 --- a/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp +++ b/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp @@ -22,6 +22,8 @@ class MultiRotorPhysicsBody : public PhysicsBody { Kinematics* kinematics, Environment* environment) : params_(params), vehicle_api_(vehicle_api) { + setName("MultiRotorPhysicsBody"); + vehicle_api_->setParent(this); initialize(kinematics, environment); } diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 49b7105b6c..52ba5841d6 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -29,6 +29,7 @@ #include "vehicles/multirotor/api/MultirotorApiBase.hpp" #include "common/PidController.hpp" #include "sensors/SensorCollection.hpp" +#include "physics/World.hpp" //sensors #include "sensors/barometer/BarometerBase.hpp" @@ -87,6 +88,15 @@ class MavLinkMultirotorApi : public MultirotorApiBase { // note this is called AFTER "initialize" when we've connected to the drone // so this method cannot reset any of that connection state. + world_ = nullptr; + + for (UpdatableObject* container = this->getParent(); container != nullptr; container = container->getParent()) { + if (container->getName() == "World") { + // cool beans! + // note: cannot use dynamic_cast because Unreal builds with /GR- for some unknown reason... + world_ = static_cast(container); + } + } MultirotorApiBase::resetImplementation(); was_reset_ = true; } @@ -1598,6 +1608,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase std::lock_guard guard(telemetry_mutex_); actuator_delay_ += delay; } + if (world_ != nullptr) { + world_->pause(false); + } } void processMavMessages(const mavlinkcom::MavLinkMessage& msg) @@ -1762,6 +1775,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase if (hil_node_ != nullptr) { hil_node_->sendMessage(hil_sensor); received_actuator_controls_ = false; + if (lock_step_enabled_ && world_ != nullptr) { + world_->pauseForTime(0.1); // 100 millisecond delay max waiting for actuator controls. + } } std::lock_guard guard(last_message_mutex_); @@ -1992,6 +2008,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase common_utils::Timer gcs_message_timer_; std::shared_ptr log_; std::string log_file_name_; + World* world_; //every time we return status update, we need to check if we have new data //this is why below two variables are marked as mutable From 6fdb9b77514f27805bcda8a8222c0dc8497fe5fc Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Wed, 28 Apr 2021 14:35:00 -0700 Subject: [PATCH 27/37] add missing update --- .../common/common_utils/ScheduledExecutor.hpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/AirLib/include/common/common_utils/ScheduledExecutor.hpp b/AirLib/include/common/common_utils/ScheduledExecutor.hpp index d62cea1be4..68781dd661 100644 --- a/AirLib/include/common/common_utils/ScheduledExecutor.hpp +++ b/AirLib/include/common/common_utils/ScheduledExecutor.hpp @@ -49,6 +49,7 @@ class ScheduledExecutor { void pause(bool is_paused) { paused_ = is_paused; + pause_period_start_ = 0; // cancel any pause period. } bool isPaused() const @@ -56,6 +57,13 @@ class ScheduledExecutor { return paused_; } + void pauseForTime(double seconds) + { + pause_period_start_ = nanos(); + pause_period_ = static_cast(1E9 * seconds); + paused_ = true; + } + void continueForTime(double seconds) { pause_period_start_ = nanos(); @@ -65,6 +73,7 @@ class ScheduledExecutor { void continueForFrames(uint32_t frames) { + pause_period_start_ = 0; // cancel any pause period. frame_countdown_enabled_ = true; targetFrameNumber_ = frames + currentFrameNumber_; paused_ = false; @@ -174,9 +183,7 @@ class ScheduledExecutor { if (pause_period_start_ > 0) { if (nanos() - pause_period_start_ >= pause_period_) { - if (! isPaused()) - pause(true); - + pause(!isPaused()); pause_period_start_ = 0; } } From d28ace6b97b8d8fbbb74810bf89c5012b6e63b60 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Wed, 28 Apr 2021 14:52:23 -0700 Subject: [PATCH 28/37] cleanup unnecessary cmake messages. --- cmake/cmake-modules/CommonSetup.cmake | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/cmake/cmake-modules/CommonSetup.cmake b/cmake/cmake-modules/CommonSetup.cmake index 22241de7d7..f2da040fc8 100644 --- a/cmake/cmake-modules/CommonSetup.cmake +++ b/cmake/cmake-modules/CommonSetup.cmake @@ -24,12 +24,8 @@ macro(SetupConsoleBuild) endmacro(SetupConsoleBuild) macro(CommonSetup) - message(STATUS "Running CommonSetup...") - find_package(Threads REQUIRED) - - find_path(AIRSIM_ROOT NAMES AirSim.sln PATHS ".." "../.." "../../.." "../../../.." "../../../../.." "../../../../../..") - message(STATUS "found AIRSIM_ROOT=${AIRSIM_ROOT}") + find_path(AIRSIM_ROOT NAMES AirSim.sln PATHS ".." "../.." "../../.." "../../../.." "../../../../.." "../../../../../.." REQUIRED) #setup output paths set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/output/lib) From f28f32b6907828eb631633a7c75e3487e159cc06 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 29 Apr 2021 15:59:31 -0700 Subject: [PATCH 29/37] Fix code formatting --- AirLib/include/common/AirSimSettings.hpp | 81 +++-- AirLib/include/common/UpdatableContainer.hpp | 12 +- AirLib/include/common/UpdatableObject.hpp | 15 +- .../common/common_utils/FileSystem.hpp | 32 +- .../common/common_utils/ScheduledExecutor.hpp | 10 +- AirLib/include/physics/FastPhysicsEngine.hpp | 30 +- AirLib/include/physics/PhysicsBody.hpp | 41 +-- AirLib/include/physics/PhysicsEngineBase.hpp | 3 +- AirLib/include/physics/PhysicsWorld.hpp | 3 +- AirLib/include/physics/World.hpp | 3 +- AirLib/include/sensors/SensorBase.hpp | 3 +- AirLib/include/sensors/SensorFactory.hpp | 3 +- .../sensors/barometer/BarometerSimple.hpp | 3 +- .../barometer/BarometerSimpleParams.hpp | 3 +- .../sensors/distance/DistanceSimple.hpp | 3 +- .../sensors/distance/DistanceSimpleParams.hpp | 3 +- AirLib/include/sensors/gps/GpsSimple.hpp | 3 +- .../include/sensors/gps/GpsSimpleParams.hpp | 3 +- AirLib/include/sensors/imu/ImuSimple.hpp | 3 +- .../include/sensors/imu/ImuSimpleParams.hpp | 9 +- AirLib/include/sensors/lidar/LidarSimple.hpp | 3 +- .../sensors/lidar/LidarSimpleParams.hpp | 3 +- .../magnetometer/MagnetometerSimple.hpp | 6 +- .../magnetometer/MagnetometerSimpleParams.hpp | 3 +- .../include/vehicles/car/api/CarApiBase.hpp | 5 +- .../car/firmwares/ardurover/ArduRoverApi.hpp | 3 +- .../vehicles/multirotor/MultiRotorParams.hpp | 3 +- .../multirotor/MultiRotorPhysicsBody.hpp | 3 +- .../firmwares/arducopter/ArduCopterApi.hpp | 3 +- .../firmwares/mavlink/ArduCopterSoloApi.hpp | 9 +- .../mavlink/MavLinkMultirotorApi.hpp | 96 +++--- MavLinkCom/common_utils/Utils.hpp | 81 +++-- MavLinkCom/include/AsyncResult.hpp | 247 +++++++------- MavLinkCom/include/MavLinkConnection.hpp | 264 +++++++-------- MavLinkCom/include/MavLinkDebugLog.hpp | 41 +-- MavLinkCom/include/MavLinkLog.hpp | 56 ++-- MavLinkCom/include/MavLinkMessageBase.hpp | 315 +++++++++--------- MavLinkCom/include/MavLinkNode.hpp | 149 +++++---- MavLinkCom/include/MavLinkVehicle.hpp | 101 +++--- MavLinkCom/src/MavLinkLog.cpp | 309 +++++++++-------- MavLinkCom/src/MavLinkMessageBase.cpp | 12 +- MavLinkCom/src/MavLinkVehicle.cpp | 6 +- MavLinkCom/src/impl/MavLinkConnectionImpl.cpp | 42 +-- MavLinkCom/src/impl/MavLinkVehicleImpl.cpp | 21 +- MavLinkCom/src/impl/MavLinkVehicleImpl.hpp | 119 +++---- PythonClient/multirotor/path.py | 6 +- .../UnitySensors/UnitySensorFactory.cpp | 25 +- .../Source/UnitySensors/UnitySensorFactory.h | 10 +- docs/log_viewer.md | 2 +- docs/px4_setup.md | 18 +- docs/px4_sitl.md | 6 +- 51 files changed, 1149 insertions(+), 1084 deletions(-) diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index 37ee6374c5..4d685cbe14 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -17,7 +17,8 @@ namespace msr { namespace airlib { -struct AirSimSettings { +struct AirSimSettings +{ private: typedef common_utils::Utils Utils; typedef ImageCaptureBase::ImageType ImageType; @@ -39,7 +40,8 @@ struct AirSimSettings { static constexpr char const * kSimModeTypeCar = "Car"; static constexpr char const * kSimModeTypeComputerVision = "ComputerVision"; - struct SubwindowSetting { + struct SubwindowSetting + { int window_index; ImageType image_type; bool visible; @@ -54,7 +56,8 @@ struct AirSimSettings { } }; - struct RecordingSetting { + struct RecordingSetting + { bool record_on_move = false; float record_interval = 0.05f; std::string folder = ""; @@ -73,7 +76,8 @@ struct AirSimSettings { } }; - struct PawnPath { + struct PawnPath + { std::string pawn_bp; std::string slippery_mat; std::string non_slippery_mat; @@ -86,12 +90,14 @@ struct AirSimSettings { } }; - struct RCSettings { + struct RCSettings + { int remote_control_id = -1; bool allow_api_when_disconnected = false; }; - struct Rotation { + struct Rotation + { float yaw = 0; float pitch = 0; float roll = 0; @@ -113,13 +119,15 @@ struct AirSimSettings { }; - struct GimbalSetting { + struct GimbalSetting + { float stabilization = 0; //bool is_world_frame = false; Rotation rotation = Rotation::nanRotation(); }; - struct CaptureSetting { + struct CaptureSetting + { //below settings_json are obtained by using Unreal console command (press ~): // ShowFlag.VisualizeHDR 1. //to replicate camera settings_json to SceneCapture2D @@ -145,7 +153,8 @@ struct AirSimSettings { float ortho_width = Utils::nan(); }; - struct NoiseSetting { + struct NoiseSetting + { int ImageType = 0; bool Enabled = false; @@ -168,7 +177,8 @@ struct AirSimSettings { float HorzDistortionStrength = 0.002f; }; - struct CameraSetting { + struct CameraSetting + { //nan means keep the default values set in components Vector3r position = VectorMath::nanVector(); Rotation rotation = Rotation::nanRotation(); @@ -184,38 +194,47 @@ struct AirSimSettings { } }; - struct CameraDirectorSetting { + struct CameraDirectorSetting + { Vector3r position = VectorMath::nanVector(); Rotation rotation = Rotation::nanRotation(); float follow_distance = Utils::nan(); }; - struct SensorSetting { + struct SensorSetting + { SensorBase::SensorType sensor_type; std::string sensor_name; bool enabled = true; Settings settings; // imported json data that needs to be parsed by specific sensors. }; - struct BarometerSetting : SensorSetting { + struct BarometerSetting : SensorSetting + { }; - struct ImuSetting : SensorSetting { + struct ImuSetting : SensorSetting + { }; - struct GpsSetting : SensorSetting { + struct GpsSetting : SensorSetting + { }; - struct MagnetometerSetting : SensorSetting { + struct MagnetometerSetting : SensorSetting + { }; - struct DistanceSetting : SensorSetting { + struct DistanceSetting : SensorSetting + { }; - struct LidarSetting : SensorSetting { + struct LidarSetting : SensorSetting + { }; - struct VehicleSetting { + struct VehicleSetting + { //required std::string vehicle_name; std::string vehicle_type; @@ -240,7 +259,8 @@ struct AirSimSettings { RCSettings rc; }; - struct MavLinkConnectionInfo { + struct MavLinkConnectionInfo + { /* Default values are requires so uninitialized instance doesn't have random values */ bool use_serial = true; // false means use UDP or TCP instead @@ -292,11 +312,13 @@ struct AirSimSettings { std::string logs; }; - struct MavLinkVehicleSetting : public VehicleSetting { + struct MavLinkVehicleSetting : public VehicleSetting + { MavLinkConnectionInfo connection_info; }; - struct SegmentationSetting { + struct SegmentationSetting + { enum class InitMethodType { None, CommonObjectsRandomIDs }; @@ -310,7 +332,8 @@ struct AirSimSettings { MeshNamingMethodType mesh_naming_method = MeshNamingMethodType::OwnerName; }; - struct TimeOfDaySetting { + struct TimeOfDaySetting + { bool enabled = false; std::string start_datetime = ""; //format: %Y-%m-%d %H:%M:%S bool is_start_datetime_dst = false; @@ -711,13 +734,11 @@ struct AirSimSettings { connection_info.control_port_remote = settings_json.getInt("ControlPortRemote", connection_info.control_port_remote); std::string sitlip = settings_json.getString("SitlIp", connection_info.control_ip_address); - if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0) - { + if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0) { // backwards compat connection_info.control_ip_address = sitlip; } - if (settings_json.hasKey("SitlPort")) - { + if (settings_json.hasKey("SitlPort")) { // backwards compat connection_info.control_port_local = settings_json.getInt("SitlPort", connection_info.control_port_local); } @@ -738,8 +759,7 @@ struct AirSimSettings { if (settings_json.getChild("Parameters", params)) { std::vector keys; params.getChildNames(keys); - for (auto key: keys) - { + for (auto key: keys) { connection_info.params[key] = params.getFloat(key, 0); } } @@ -1170,8 +1190,7 @@ struct AirSimSettings { //for multirotors we select steppable fixed interval clock unless we have //PX4 enabled vehicle clock_type = "SteppableClock"; - for (auto const& vehicle : vehicles) - { + for (auto const& vehicle : vehicles) { if (vehicle.second->auto_create && vehicle.second->vehicle_type == kVehicleTypePX4) { clock_type = "ScalableClock"; diff --git a/AirLib/include/common/UpdatableContainer.hpp b/AirLib/include/common/UpdatableContainer.hpp index e55168f530..2b9d476930 100644 --- a/AirLib/include/common/UpdatableContainer.hpp +++ b/AirLib/include/common/UpdatableContainer.hpp @@ -10,7 +10,8 @@ namespace msr { namespace airlib { template -class UpdatableContainer : public UpdatableObject { +class UpdatableContainer : public UpdatableObject +{ public: //limited container interface typedef vector MembersContainer; typedef typename MembersContainer::iterator iterator; @@ -24,17 +25,20 @@ class UpdatableContainer : public UpdatableObject { const TUpdatableObjectPtr& at(uint index) const { members_.at(index); } TUpdatableObjectPtr& at(uint index) { return members_.at(index); } //allow to override membership modifications - virtual void clear() { + virtual void clear() + { for (auto m : members_) { m->setParent(nullptr); } members_.clear(); } - virtual void insert(TUpdatableObjectPtr member) { + virtual void insert(TUpdatableObjectPtr member) + { member->setParent(this); members_.push_back(member); } - virtual void erase_remove(TUpdatableObjectPtr member) { + virtual void erase_remove(TUpdatableObjectPtr member) + { member->setParent(nullptr); members_.erase(std::remove(members_.begin(), members_.end(), member), members_.end()); } diff --git a/AirLib/include/common/UpdatableObject.hpp b/AirLib/include/common/UpdatableObject.hpp index 620f54e7d1..9f40e3bafb 100644 --- a/AirLib/include/common/UpdatableObject.hpp +++ b/AirLib/include/common/UpdatableObject.hpp @@ -24,7 +24,8 @@ Do not call reset() from constructor or initialization because that will produce init->reset calls for base-derived class that would be incorrect. */ -class UpdatableObject { +class UpdatableObject +{ public: void reset() { @@ -72,19 +73,23 @@ class UpdatableObject { return ClockFactory::get(); } - UpdatableObject* getParent() { + UpdatableObject* getParent() + { return parent_; } - void setParent(UpdatableObject* container) { + void setParent(UpdatableObject* container) + { parent_ = container; } - std::string getName(){ + std::string getName() + { return name_; } - void setName(const std::string& name) { + void setName(const std::string& name) + { this->name_ = name; } diff --git a/AirLib/include/common/common_utils/FileSystem.hpp b/AirLib/include/common/common_utils/FileSystem.hpp index 2d3ae8f994..5b7849d627 100644 --- a/AirLib/include/common/common_utils/FileSystem.hpp +++ b/AirLib/include/common/common_utils/FileSystem.hpp @@ -50,23 +50,27 @@ class FileSystem static std::string getUserDocumentsFolder(); - static std::string getExecutableFolder(); + static std::string getExecutableFolder(); - static std::string getAppDataFolder() { + static std::string getAppDataFolder() + { return ensureFolder(combine(getUserDocumentsFolder(), ProductFolderName)); } - static std::string ensureFolder(const std::string& fullpath) { + static std::string ensureFolder(const std::string& fullpath) + { // make sure this directory exists. return createDirectory(fullpath); } - static std::string ensureFolder(const std::string& parentFolder, const std::string& child) { + static std::string ensureFolder(const std::string& parentFolder, const std::string& child) + { // make sure this directory exists. return createDirectory(combine(parentFolder, child)); } - static std::string combine(const std::string& parentFolder, const std::string& child) { + static std::string combine(const std::string& parentFolder, const std::string& child) + { if (child.size() == 0) return parentFolder; @@ -83,7 +87,8 @@ class FileSystem return parentFolder + kPathSeparator + child; } - static void removeLeaf(std::string& path) { + static void removeLeaf(std::string& path) + { size_t size = path.size(); size_t pos = path.find_last_of('/'); if (pos != std::string::npos) { @@ -98,8 +103,7 @@ class FileSystem int len = static_cast(str.size()); const char* ptr = str.c_str(); int i = 0; - for (i = len - 1; i >= 0; i--) - { + for (i = len - 1; i >= 0; i--) { if (ptr[i] == '.') break; } @@ -138,8 +142,8 @@ class FileSystem //return filename_ss.str(); } - static void openTextFile(const std::string& filepath, std::ifstream& file){ - + static void openTextFile(const std::string& filepath, std::ifstream& file) + { #ifdef _WIN32 // WIN32 will create the wrong file names if we don't first convert them to UTF-16. std::wstring_convert, wchar_t> converter; @@ -150,8 +154,8 @@ class FileSystem #endif } - static void createBinaryFile(const std::string& filepath, std::ofstream& file){ - + static void createBinaryFile(const std::string& filepath, std::ofstream& file) + { #ifdef _WIN32 // WIN32 will create the wrong file names if we don't first convert them to UTF-16. std::wstring_convert, wchar_t> converter; @@ -162,8 +166,8 @@ class FileSystem #endif } - static void createTextFile(const std::string& filepath, std::ofstream& file){ - + static void createTextFile(const std::string& filepath, std::ofstream& file) + { #ifdef _WIN32 // WIN32 will create the wrong file names if we don't first convert them to UTF-16. std::wstring_convert, wchar_t> converter; diff --git a/AirLib/include/common/common_utils/ScheduledExecutor.hpp b/AirLib/include/common/common_utils/ScheduledExecutor.hpp index 68781dd661..8ab23b9e1f 100644 --- a/AirLib/include/common/common_utils/ScheduledExecutor.hpp +++ b/AirLib/include/common/common_utils/ScheduledExecutor.hpp @@ -14,18 +14,22 @@ namespace common_utils { -class ScheduledExecutor { +class ScheduledExecutor +{ public: ScheduledExecutor() {} + ScheduledExecutor(const std::function& callback, uint64_t period_nanos) { initialize(callback, period_nanos); } + ~ScheduledExecutor() { stop(); } + void initialize(const std::function& callback, uint64_t period_nanos) { callback_ = callback; @@ -95,8 +99,8 @@ class ScheduledExecutor { th_.join(); } } - catch(const std::system_error& /* e */) - { } + catch(const std::system_error& /* e */) { + } } } diff --git a/AirLib/include/physics/FastPhysicsEngine.hpp b/AirLib/include/physics/FastPhysicsEngine.hpp index 035f89d0fc..ff024462bb 100644 --- a/AirLib/include/physics/FastPhysicsEngine.hpp +++ b/AirLib/include/physics/FastPhysicsEngine.hpp @@ -16,7 +16,8 @@ namespace msr { namespace airlib { -class FastPhysicsEngine : public PhysicsEngineBase { +class FastPhysicsEngine : public PhysicsEngineBase +{ public: FastPhysicsEngine(bool enable_ground_lock = true, Vector3r wind = Vector3r::Zero()) : enable_ground_lock_(enable_ground_lock), wind_(wind) @@ -51,8 +52,8 @@ class FastPhysicsEngine : public PhysicsEngineBase { { for (PhysicsBody* body_ptr : *this) { reporter.writeValue("Phys", debug_string_.str()); - reporter.writeValue("Is Grounded", body_ptr->isGrounded()); - reporter.writeValue("Force (world)", body_ptr->getWrench().force); + reporter.writeValue("Is Grounded", body_ptr->isGrounded()); + reporter.writeValue("Force (world)", body_ptr->getWrench().force); reporter.writeValue("Torque (body)", body_ptr->getWrench().torque); } //call base @@ -106,12 +107,12 @@ class FastPhysicsEngine : public PhysicsEngineBase { body.unlock(); - //TODO: this is now being done in PawnSimApi::update. We need to re-think this sequence + //TODO: this is now being done in PawnSimApi::update. We need to re-think this sequence //with below commented out - Arducopter GPS may not work. - //body.getEnvironment().setPosition(next.pose.position); - //body.getEnvironment().update(); - - } + //body.getEnvironment().setPosition(next.pose.position); + //body.getEnvironment().update(); + + } static void updateCollisionResponseInfo(const CollisionInfo& collision_info, const Kinematics::State& next, bool is_collision_response, CollisionResponse& collision_response) @@ -232,7 +233,7 @@ class FastPhysicsEngine : public PhysicsEngineBase { // also eliminate any linear velocity due to twist - since we are sitting on the ground there shouldn't be any. next.twist.linear = Vector3r::Zero(); next.pose.position = collision_info.position; - body.setGrounded(true); + body.setGrounded(true); // but we do want to "feel" the ground when we hit it (we should see a small z-acc bump) // equal and opposite our downward velocity. @@ -240,8 +241,7 @@ class FastPhysicsEngine : public PhysicsEngineBase { //throttledLogOutput("*** Triggering ground lock", 0.1); } - else - { + else { //else keep the orientation next.pose.position = collision_info.position + (collision_info.normal * collision_info.penetration_depth) + next.twist.linear * (dt_real * kCollisionResponseCycles); } @@ -256,8 +256,7 @@ class FastPhysicsEngine : public PhysicsEngineBase { { TTimeDelta dt = clock()->elapsedSince(last_message_time); const real_T dt_real = static_cast(dt); - if (dt_real > seconds) - { + if (dt_real > seconds) { Utils::log(msg); last_message_time = clock()->nowNanos(); } @@ -341,10 +340,9 @@ class FastPhysicsEngine : public PhysicsEngineBase { float external_force_magnitude = body_wrench.force.squaredNorm(); Vector3r weight = body.getMass() * body.getEnvironment().getState().gravity; float weight_magnitude = weight.squaredNorm(); - if (external_force_magnitude >= weight_magnitude) - { + if (external_force_magnitude >= weight_magnitude) { //throttledLogOutput("*** Losing ground lock due to body_wrench " + VectorMath::toString(body_wrench.force), 0.1); - body.setGrounded(false); + body.setGrounded(false); } next_wrench.force = Vector3r::Zero(); next_wrench.torque = Vector3r::Zero(); diff --git a/AirLib/include/physics/PhysicsBody.hpp b/AirLib/include/physics/PhysicsBody.hpp index a20daffc7c..8e98155196 100644 --- a/AirLib/include/physics/PhysicsBody.hpp +++ b/AirLib/include/physics/PhysicsBody.hpp @@ -15,7 +15,8 @@ namespace msr { namespace airlib { -class PhysicsBody : public UpdatableObject { +class PhysicsBody : public UpdatableObject +{ public: //interface virtual real_T getRestitution() const = 0; virtual real_T getFriction() const = 0; @@ -104,7 +105,7 @@ class PhysicsBody : public UpdatableObject { wrench_ = Wrench::zero(); collision_info_ = CollisionInfo(); collision_response_ = CollisionResponse(); - grounded_ = false; + grounded_ = false; //update individual vertices for (uint vertex_index = 0; vertex_index < wrenchVertexCount(); ++vertex_index) { @@ -218,24 +219,24 @@ class PhysicsBody : public UpdatableObject { return collision_response_; } - bool isGrounded() const - { - return grounded_; - } - void setGrounded(bool grounded) - { - grounded_ = grounded; - } + bool isGrounded() const + { + return grounded_; + } + void setGrounded(bool grounded) + { + grounded_ = grounded; + } - void lock() - { - mutex_.lock(); - } + void lock() + { + mutex_.lock(); + } - void unlock() - { - mutex_.unlock(); - } + void unlock() + { + mutex_.unlock(); + } public: //for use in physics engine: //TODO: use getter/setter or friend method? @@ -254,8 +255,8 @@ class PhysicsBody : public UpdatableObject { CollisionInfo collision_info_; CollisionResponse collision_response_; - bool grounded_ = false; - std::mutex mutex_; + bool grounded_ = false; + std::mutex mutex_; }; }} //namespace diff --git a/AirLib/include/physics/PhysicsEngineBase.hpp b/AirLib/include/physics/PhysicsEngineBase.hpp index dd06c3f829..0d41967f49 100644 --- a/AirLib/include/physics/PhysicsEngineBase.hpp +++ b/AirLib/include/physics/PhysicsEngineBase.hpp @@ -10,7 +10,8 @@ namespace msr { namespace airlib { -class PhysicsEngineBase : public UpdatableContainer { +class PhysicsEngineBase : public UpdatableContainer +{ public: virtual void update() override { diff --git a/AirLib/include/physics/PhysicsWorld.hpp b/AirLib/include/physics/PhysicsWorld.hpp index b56fc8eb92..7dbcc8ae26 100644 --- a/AirLib/include/physics/PhysicsWorld.hpp +++ b/AirLib/include/physics/PhysicsWorld.hpp @@ -13,7 +13,8 @@ namespace msr { namespace airlib { -class PhysicsWorld : UpdatableObject { +class PhysicsWorld : UpdatableObject +{ public: PhysicsWorld(std::unique_ptr physics_engine, const std::vector& bodies, uint64_t update_period_nanos = 3000000LL, bool state_reporter_enabled = false, diff --git a/AirLib/include/physics/World.hpp b/AirLib/include/physics/World.hpp index b8c0cc2fd3..94f738e84e 100644 --- a/AirLib/include/physics/World.hpp +++ b/AirLib/include/physics/World.hpp @@ -14,7 +14,8 @@ namespace msr { namespace airlib { -class World : public UpdatableContainer { +class World : public UpdatableContainer +{ public: World(std::unique_ptr physics_engine) : physics_engine_(std::move(physics_engine)) diff --git a/AirLib/include/sensors/SensorBase.hpp b/AirLib/include/sensors/SensorBase.hpp index 44bd8531aa..d56f46b3de 100644 --- a/AirLib/include/sensors/SensorBase.hpp +++ b/AirLib/include/sensors/SensorBase.hpp @@ -18,7 +18,8 @@ namespace msr { namespace airlib { After construction of the derived class an initialize(...) must be made which would set the sensor in good-to-use state by call to reset. */ -class SensorBase : public UpdatableObject { +class SensorBase : public UpdatableObject +{ public: enum class SensorType : uint { Barometer = 1, diff --git a/AirLib/include/sensors/SensorFactory.hpp b/AirLib/include/sensors/SensorFactory.hpp index 0c93412ec5..1f25312a13 100644 --- a/AirLib/include/sensors/SensorFactory.hpp +++ b/AirLib/include/sensors/SensorFactory.hpp @@ -15,7 +15,8 @@ namespace msr { namespace airlib { -class SensorFactory { +class SensorFactory +{ public: // creates one sensor from settings diff --git a/AirLib/include/sensors/barometer/BarometerSimple.hpp b/AirLib/include/sensors/barometer/BarometerSimple.hpp index 515ae21e57..eda67bf092 100644 --- a/AirLib/include/sensors/barometer/BarometerSimple.hpp +++ b/AirLib/include/sensors/barometer/BarometerSimple.hpp @@ -16,7 +16,8 @@ namespace msr { namespace airlib { -class BarometerSimple : public BarometerBase { +class BarometerSimple : public BarometerBase +{ public: BarometerSimple(const AirSimSettings::BarometerSetting& setting = AirSimSettings::BarometerSetting()) : BarometerBase(setting.sensor_name) diff --git a/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp b/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp index 45b4f6601c..ef128e78a1 100644 --- a/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp +++ b/AirLib/include/sensors/barometer/BarometerSimpleParams.hpp @@ -11,7 +11,8 @@ namespace msr { namespace airlib { -struct BarometerSimpleParams { +struct BarometerSimpleParams +{ //user specified sea level pressure is specified in hPa units real_T qnh = EarthUtils::SeaLevelPressure / 100.0f; // hPa diff --git a/AirLib/include/sensors/distance/DistanceSimple.hpp b/AirLib/include/sensors/distance/DistanceSimple.hpp index 63de52c15a..81f7a4858e 100644 --- a/AirLib/include/sensors/distance/DistanceSimple.hpp +++ b/AirLib/include/sensors/distance/DistanceSimple.hpp @@ -14,7 +14,8 @@ namespace msr { namespace airlib { -class DistanceSimple : public DistanceBase { +class DistanceSimple : public DistanceBase +{ public: DistanceSimple(const AirSimSettings::DistanceSetting& setting = AirSimSettings::DistanceSetting()) : DistanceBase(setting.sensor_name) diff --git a/AirLib/include/sensors/distance/DistanceSimpleParams.hpp b/AirLib/include/sensors/distance/DistanceSimpleParams.hpp index f223c03e85..3afadd29c1 100644 --- a/AirLib/include/sensors/distance/DistanceSimpleParams.hpp +++ b/AirLib/include/sensors/distance/DistanceSimpleParams.hpp @@ -11,7 +11,8 @@ namespace msr { namespace airlib { -struct DistanceSimpleParams { +struct DistanceSimpleParams +{ real_T min_distance = 20.0f / 100; //m real_T max_distance = 4000.0f / 100; //m diff --git a/AirLib/include/sensors/gps/GpsSimple.hpp b/AirLib/include/sensors/gps/GpsSimple.hpp index dd32cfd22b..8645a3b609 100644 --- a/AirLib/include/sensors/gps/GpsSimple.hpp +++ b/AirLib/include/sensors/gps/GpsSimple.hpp @@ -15,7 +15,8 @@ namespace msr { namespace airlib { -class GpsSimple : public GpsBase { +class GpsSimple : public GpsBase +{ public: //methods GpsSimple(const AirSimSettings::GpsSetting& setting = AirSimSettings::GpsSetting()) : GpsBase(setting.sensor_name) diff --git a/AirLib/include/sensors/gps/GpsSimpleParams.hpp b/AirLib/include/sensors/gps/GpsSimpleParams.hpp index 18e9949dd8..b8715fd16e 100644 --- a/AirLib/include/sensors/gps/GpsSimpleParams.hpp +++ b/AirLib/include/sensors/gps/GpsSimpleParams.hpp @@ -9,7 +9,8 @@ namespace msr { namespace airlib { -struct GpsSimpleParams { +struct GpsSimpleParams +{ real_T eph_time_constant = 0.9f, epv_time_constant = 0.9f; real_T eph_initial = 100.0f, epv_initial = 100.0f; //initially fully diluted positions real_T eph_final = 0.1f, epv_final = 0.1f; // PX4 won't converge GPS sensor fusion until we get to 10% accuracty. diff --git a/AirLib/include/sensors/imu/ImuSimple.hpp b/AirLib/include/sensors/imu/ImuSimple.hpp index fbf38c730c..38bac02795 100644 --- a/AirLib/include/sensors/imu/ImuSimple.hpp +++ b/AirLib/include/sensors/imu/ImuSimple.hpp @@ -11,7 +11,8 @@ namespace msr { namespace airlib { -class ImuSimple : public ImuBase { +class ImuSimple : public ImuBase +{ public: //constructors ImuSimple(const AirSimSettings::ImuSetting& setting = AirSimSettings::ImuSetting()) diff --git a/AirLib/include/sensors/imu/ImuSimpleParams.hpp b/AirLib/include/sensors/imu/ImuSimpleParams.hpp index 78f8de4dc0..115f65294e 100644 --- a/AirLib/include/sensors/imu/ImuSimpleParams.hpp +++ b/AirLib/include/sensors/imu/ImuSimpleParams.hpp @@ -15,7 +15,8 @@ namespace msr { namespace airlib { // A description of the parameters: // https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model-and-Intrinsics -struct ImuSimpleParams { +struct ImuSimpleParams +{ /* ref: Parameter values are for MPU 6000 IMU from InvenSense Design and Characterization of a Low Cost MEMS IMU Cluster for Precision Navigation Daniel R. Greenheck, 2009, sec 2.2, pp 17 @@ -24,7 +25,8 @@ struct ImuSimpleParams { https://www.invensense.com/wp-content/uploads/2015/02/MPU-6000-Datasheet1.pdf For Allan Variance/Deviation plots see http://www.invensense.com/wp-content/uploads/2015/02/MPU-3300-Datasheet.pdf */ - struct Gyroscope { + struct Gyroscope + { //angular random walk (ARW) real_T arw = 0.30f / sqrt(3600.0f) * M_PIf / 180; //deg/sqrt(hour) converted to rad/sqrt(sec) //Bias Stability (tau = 500s) @@ -33,7 +35,8 @@ struct ImuSimpleParams { Vector3r turn_on_bias = Vector3r::Zero(); //assume calibration is done } gyro; - struct Accelerometer { + struct Accelerometer + { //velocity random walk (ARW) real_T vrw = 0.24f * EarthUtils::Gravity / 1.0E3f; //mg converted to m/s^2 //Bias Stability (tau = 800s) diff --git a/AirLib/include/sensors/lidar/LidarSimple.hpp b/AirLib/include/sensors/lidar/LidarSimple.hpp index db6f4b05a7..f05f21b127 100644 --- a/AirLib/include/sensors/lidar/LidarSimple.hpp +++ b/AirLib/include/sensors/lidar/LidarSimple.hpp @@ -13,7 +13,8 @@ namespace msr { namespace airlib { -class LidarSimple : public LidarBase { +class LidarSimple : public LidarBase +{ public: LidarSimple(const AirSimSettings::LidarSetting& setting = AirSimSettings::LidarSetting()) : LidarBase(setting.sensor_name) diff --git a/AirLib/include/sensors/lidar/LidarSimpleParams.hpp b/AirLib/include/sensors/lidar/LidarSimpleParams.hpp index 15ea6a89fd..e53922f817 100644 --- a/AirLib/include/sensors/lidar/LidarSimpleParams.hpp +++ b/AirLib/include/sensors/lidar/LidarSimpleParams.hpp @@ -9,7 +9,8 @@ namespace msr { namespace airlib { -struct LidarSimpleParams { +struct LidarSimpleParams +{ // Velodyne VLP-16 Puck config // https://velodynelidar.com/vlp-16.html diff --git a/AirLib/include/sensors/magnetometer/MagnetometerSimple.hpp b/AirLib/include/sensors/magnetometer/MagnetometerSimple.hpp index b2a1556611..c77eee9829 100644 --- a/AirLib/include/sensors/magnetometer/MagnetometerSimple.hpp +++ b/AirLib/include/sensors/magnetometer/MagnetometerSimple.hpp @@ -15,7 +15,8 @@ namespace msr { namespace airlib { -class MagnetometerSimple : public MagnetometerBase { +class MagnetometerSimple : public MagnetometerBase +{ public: MagnetometerSimple(const AirSimSettings::MagnetometerSetting& setting = AirSimSettings::MagnetometerSetting()) : MagnetometerBase(setting.sensor_name) @@ -66,8 +67,7 @@ class MagnetometerSimple : public MagnetometerBase { private: //methods void updateReference(const GroundTruth& ground_truth) { - switch (params_.ref_source) - { + switch (params_.ref_source) { case MagnetometerSimpleParams::ReferenceSource::ReferenceSource_Constant: // Constant magnetic field for Seattle magnetic_field_true_ = Vector3r(0.34252f, 0.09805f, 0.93438f); diff --git a/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp b/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp index b0a7aab325..884cef5a1a 100644 --- a/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp +++ b/AirLib/include/sensors/magnetometer/MagnetometerSimpleParams.hpp @@ -10,7 +10,8 @@ namespace msr { namespace airlib { -struct MagnetometerSimpleParams { +struct MagnetometerSimpleParams +{ enum ReferenceSource { ReferenceSource_Constant, ReferenceSource_DipoleModel diff --git a/AirLib/include/vehicles/car/api/CarApiBase.hpp b/AirLib/include/vehicles/car/api/CarApiBase.hpp index 2cbbb1cfb9..7d69420d43 100644 --- a/AirLib/include/vehicles/car/api/CarApiBase.hpp +++ b/AirLib/include/vehicles/car/api/CarApiBase.hpp @@ -14,7 +14,8 @@ namespace msr { namespace airlib { -class CarApiBase : public VehicleApiBase { +class CarApiBase : public VehicleApiBase +{ public: struct CarControls { float throttle = 0; /* 1 to -1 */ @@ -83,7 +84,7 @@ class CarApiBase : public VehicleApiBase { public: // TODO: Temporary constructor for the Unity implementation which does not use the new Sensor Configuration Settings implementation. - //CarApiBase() {} + //CarApiBase() {} CarApiBase(const AirSimSettings::VehicleSetting* vehicle_setting, std::shared_ptr sensor_factory, diff --git a/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp b/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp index b1c24cbf6b..ae61993aad 100644 --- a/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp +++ b/AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp @@ -28,7 +28,8 @@ namespace msr { namespace airlib { -class ArduRoverApi : public CarApiBase { +class ArduRoverApi : public CarApiBase +{ public: ArduRoverApi(const AirSimSettings::VehicleSetting* vehicle_setting, std::shared_ptr sensor_factory, diff --git a/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp b/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp index 75f24ea1c6..bb730c8540 100644 --- a/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp +++ b/AirLib/include/vehicles/multirotor/MultiRotorParams.hpp @@ -12,7 +12,8 @@ namespace msr { namespace airlib { -class MultiRotorParams { +class MultiRotorParams +{ //All units are SI public: //types struct RotorPose { diff --git a/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp b/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp index f0fe7ca87e..b6ac4ec992 100644 --- a/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp +++ b/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp @@ -16,7 +16,8 @@ namespace msr { namespace airlib { -class MultiRotorPhysicsBody : public PhysicsBody { +class MultiRotorPhysicsBody : public PhysicsBody +{ public: MultiRotorPhysicsBody(MultiRotorParams* params, VehicleApiBase* vehicle_api, Kinematics* kinematics, Environment* environment) diff --git a/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp index e6ea24f8fe..9bd5e3014d 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/arducopter/ArduCopterApi.hpp @@ -31,7 +31,8 @@ namespace msr { namespace airlib { -class ArduCopterApi : public MultirotorApiBase { +class ArduCopterApi : public MultirotorApiBase +{ public: ArduCopterApi(const MultiRotorParams* vehicle_params, const AirSimSettings::MavLinkConnectionInfo& connection_info) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp index bc1db991f7..bbeeeb43b5 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp @@ -71,8 +71,7 @@ class ArduCopterSoloApi : public MavLinkMultirotorApi packet.magic = 0x4c56414f; - if (udpSocket_ != nullptr) - { + if (udpSocket_ != nullptr) { std::vector msg(sizeof(packet)); memcpy(msg.data(), &packet, sizeof(packet)); udpSocket_->sendMessage(msg); @@ -170,8 +169,7 @@ class ArduCopterSoloApi : public MavLinkMultirotorApi void rotorPowerMessageHandler(std::shared_ptr connection, const std::vector &msg) { - if (msg.size() != sizeof(RotorControlMessage)) - { + if (msg.size() != sizeof(RotorControlMessage)) { Utils::log("Got rotor control message of size " + std::to_string(msg.size()) + " when we were expecting size " + std::to_string(sizeof(RotorControlMessage)), Utils::kLogLevelError); return; } @@ -201,8 +199,7 @@ class ArduCopterSoloApi : public MavLinkMultirotorApi float phiDot = p + tan(theta)*(q*sin(phi) + r * cos(phi)); float thetaDot = q * cos(phi) - r * sin(phi); - if (fabs(cos(theta)) < 1.0e-20) - { + if (fabs(cos(theta)) < 1.0e-20) { theta += 1.0e-10f; } diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 52ba5841d6..e0b297a050 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -46,8 +46,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase virtual ~MavLinkMultirotorApi() { closeAllConnection(); - if (this->connect_thread_.joinable()) - { + if (this->connect_thread_.joinable()) { this->connect_thread_.join(); } if (this->telemetry_thread_.joinable()) { @@ -101,7 +100,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase was_reset_ = true; } - unsigned long long getSimTime() { + unsigned long long getSimTime() + { // This ensures HIL_SENSOR and HIL_GPS have matching clocks. if (lock_step_enabled_) { if (sim_time_us_ == 0) { @@ -114,7 +114,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } - void advanceTime() { + void advanceTime() + { sim_time_us_ = clock()->nowNanos() / 1000; } @@ -294,6 +295,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase updateState(); return Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); } + virtual Vector3r getVelocity() const override { updateState(); @@ -320,6 +322,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase std::lock_guard guard(hil_controls_mutex_); return rotor_controls_[rotor_index]; } + virtual size_t getActuatorCount() const override { return RotorControlsCount; @@ -341,7 +344,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase return rc; } - void onArmed() { + void onArmed() + { if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { auto con = mav_vehicle_->getConnection(); if (con != nullptr) { @@ -350,8 +354,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase log_ = nullptr; } - try - { + try { std::time_t t = std::time(0); // get time now std::tm* now = std::localtime(&t); auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday); @@ -378,7 +381,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } - void onDisarmed() { + void onDisarmed() + { if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { auto con = mav_vehicle_->getConnection(); if (con != nullptr) { @@ -416,8 +420,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase addStatusMessage("Waiting for z-position to stabilize..."); if (!waitForFunction([&]() { return ground_variance_ <= GroundTolerance; - }, timeout_sec).isComplete()) - { + }, timeout_sec).isComplete()) { auto msg = Utils::stringf("Ground is not stable, variance is %f", ground_variance_); throw VehicleMoveException(msg); } @@ -459,8 +462,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase checkValidVehicle(); if (current_state_.home.is_set) { bool rc = false; - if (!mav_vehicle_->land(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.home.global_pos.alt).wait(10000, &rc)) - { + if (!mav_vehicle_->land(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.home.global_pos.alt).wait(10000, &rc)) { throw VehicleMoveException("Landing command - timeout waiting for response from drone"); } else if (!rc) { @@ -477,8 +479,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase }, timeout_sec); // Wait for landed state (or user cancellation) - if (!waiter.isComplete()) - { + if (!waiter.isComplete()) { throw VehicleMoveException("Drone hasn't reported a landing state"); } return waiter.isComplete(); @@ -567,10 +568,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase checkValidVehicle(); mavlinkcom::AsyncResult result = mav_vehicle_->loiter(); //auto start_time = std::chrono::system_clock::now(); - while (!getCancelToken().isCancelled()) - { - if (result.wait(100, &rc)) - { + while (!getCancelToken().isCancelled()) { + if (result.wait(100, &rc)) { break; } } @@ -637,8 +636,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase data.messages_received += gcs.messages_received; data.messages_sent += gcs.messages_sent; - if (gcs.messages_received == 0) - { + if (gcs.messages_received == 0) { if (!gcs_message_timer_.started()) { gcs_message_timer_.start(); } @@ -689,10 +687,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } - void start_telemtry_thread() { - - if (this->telemetry_thread_.joinable()) - { + void start_telemtry_thread() + { + if (this->telemetry_thread_.joinable()) { this->telemetry_thread_.join(); } @@ -704,9 +701,9 @@ class MavLinkMultirotorApi : public MultirotorApiBase this->telemetry_thread_ = std::thread(&MavLinkMultirotorApi::telemtry_thread, this); } - void telemtry_thread() { + void telemtry_thread() + { while (log_ != nullptr) { - std::this_thread::sleep_for(std::chrono::seconds(1)); writeTelemetry(1); } @@ -716,12 +713,14 @@ class MavLinkMultirotorApi : public MultirotorApiBase { return 1.0f / 50; //1 period of 50hz } + virtual float getTakeoffZ() const override { // pick a number, PX4 doesn't have a fixed limit here, but 3 meters is probably safe // enough to get out of the backwash turbulence. Negative due to NED coordinate system. return -3.0f; } + virtual float getDistanceAccuracy() const override { return 0.5f; //measured in simulator by firing commands "MoveToLocation -x 0 -y 0" multiple times and looking at distance traveled @@ -771,16 +770,19 @@ class MavLinkMultirotorApi : public MultirotorApiBase float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); mav_vehicle_->moveByAttitude(roll, pitch, 0, 0, 0, yaw_rate, thrust); } + virtual void commandRollPitchYawThrottle(float roll, float pitch, float yaw, float throttle) override { checkValidVehicle(); mav_vehicle_->moveByAttitude(roll, pitch, yaw, 0, 0, 0, throttle); } + virtual void commandRollPitchYawrateThrottle(float roll, float pitch, float yaw_rate, float throttle) override { checkValidVehicle(); mav_vehicle_->moveByAttitude(roll, pitch, 0, 0, 0, yaw_rate, throttle); } + virtual void commandAngleRatesZ(float roll_rate, float pitch_rate, float yaw_rate, float z) override { if (target_height_ != -z) { @@ -792,6 +794,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); mav_vehicle_->moveByAttitude(0, 0, 0, roll_rate, pitch_rate, yaw_rate, thrust); } + virtual void commandAngleRatesThrottle(float roll_rate, float pitch_rate, float yaw_rate, float throttle) override { checkValidVehicle(); @@ -804,12 +807,14 @@ class MavLinkMultirotorApi : public MultirotorApiBase float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; mav_vehicle_->moveByLocalVelocity(vx, vy, vz, !yaw_mode.is_rate, yaw); } + virtual void commandVelocityZ(float vx, float vy, float z, const YawMode& yaw_mode) override { checkValidVehicle(); float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; mav_vehicle_->moveByLocalVelocityWithAltHold(vx, vy, z, !yaw_mode.is_rate, yaw); } + virtual void commandPosition(float x, float y, float z, const YawMode& yaw_mode) override { checkValidVehicle(); @@ -829,6 +834,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase { startOffboardMode(); } + virtual void afterTask() override { endOffboardMode(); @@ -839,13 +845,18 @@ class MavLinkMultirotorApi : public MultirotorApiBase class MavLinkLogViewerLog : public mavlinkcom::MavLinkLog { public: - MavLinkLogViewerLog(std::shared_ptr proxy) { + MavLinkLogViewerLog(std::shared_ptr proxy) + { proxy_ = proxy; } - ~MavLinkLogViewerLog() { + + ~MavLinkLogViewerLog() + { proxy_ = nullptr; } - void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override { + + void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override + { if (proxy_ != nullptr) { unused(timestamp); mavlinkcom::MavLinkMessage copy; @@ -874,15 +885,15 @@ class MavLinkMultirotorApi : public MultirotorApiBase { if (!connecting_) { connecting_ = true; - if (this->connect_thread_.joinable()) - { + if (this->connect_thread_.joinable()) { this->connect_thread_.join(); } this->connect_thread_ = std::thread(&MavLinkMultirotorApi::connect_thread, this); } } - virtual void disconnect() { + virtual void disconnect() + { addStatusMessage("Disconnecting mavlink vehicle"); connected_ = false; connecting_ = false; @@ -1088,7 +1099,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } - void checkValidVehicle() { + void checkValidVehicle() + { if (mav_vehicle_ == nullptr || connection_ == nullptr || !connection_->isOpen() || !connected_) { throw std::logic_error("Cannot perform operation when no vehicle is connected or vehicle is not responding"); } @@ -1100,8 +1112,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase StatusLock lock(this); if (mav_vehicle_ != nullptr) { int version = mav_vehicle_->getVehicleStateVersion(); - if (version != state_version_) - { + if (version != state_version_) { current_state_ = mav_vehicle_->getVehicleState(); state_version_ = version; } @@ -1127,7 +1138,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } - bool sendTestMessage(std::shared_ptr node) { + bool sendTestMessage(std::shared_ptr node) + { try { // try and send a test message. mavlinkcom::MavLinkHeartbeat test; @@ -1239,8 +1251,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase std::string portName_str; - for (wchar_t ch : info.portName) - { + for (wchar_t ch : info.portName) { portName_str.push_back(static_cast(ch)); } return portName_str; @@ -1590,7 +1601,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase } } - void handleLockStep() { + void handleLockStep() + { received_actuator_controls_ = true; // if the timestamps match then it means we are in lockstep mode. if (!lock_step_enabled_) { @@ -1707,8 +1719,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase } else if (msg.msgid == mavlinkcom::MavLinkLocalPositionNed::kMessageId) { // we are getting position information... so we can use this to check the stability of the z coordinate before takeoff. - if (current_state_.controls.landed) - { + if (current_state_.controls.landed) { monitorGroundAltitude(); } } @@ -1784,7 +1795,8 @@ class MavLinkMultirotorApi : public MultirotorApiBase last_sensor_message_ = hil_sensor; } - void sendSystemTime() { + void sendSystemTime() + { // SYSTEM TIME from host auto tu = getSimTime(); uint32_t ms = (uint32_t)(tu / 1000); diff --git a/MavLinkCom/common_utils/Utils.hpp b/MavLinkCom/common_utils/Utils.hpp index 7c0bd91c85..40146937d5 100644 --- a/MavLinkCom/common_utils/Utils.hpp +++ b/MavLinkCom/common_utils/Utils.hpp @@ -86,7 +86,8 @@ void unused(T const & result) { static_cast(result); } namespace mavlink_utils { -class Utils { +class Utils +{ private: typedef std::chrono::system_clock system_clock; typedef std::chrono::steady_clock steady_clock; @@ -99,7 +100,8 @@ class Utils { public: - static void enableImmediateConsoleFlush() { + static void enableImmediateConsoleFlush() + { //disable buffering setbuf(stdout, NULL); } @@ -113,16 +115,20 @@ class Utils { return gaussian_dist(random_gen) * stddev + mean; } - static constexpr double degreesToRadians(double degrees) { + static constexpr double degreesToRadians(double degrees) + { return static_cast(M_PIl * degrees / 180.0); } - static constexpr float degreesToRadians(float degrees) { + static constexpr float degreesToRadians(float degrees) + { return static_cast(M_PIf * degrees / 180.0f); } - static constexpr double radiansToDegrees(double radians) { + static constexpr double radiansToDegrees(double radians) + { return static_cast(radians * 180.0 / M_PIl); } - static constexpr float radiansToDegrees(float radians) { + static constexpr float radiansToDegrees(float radians) + { return static_cast(radians * 180.0f / M_PIf); } @@ -135,13 +141,15 @@ class Utils { } template - static int sign(T val) { + static int sign(T val) + { return T(0) < val ? 1 : (T(0) > val ? -1 : 0); } /// Limits absolute value whole preserving sign template - static T limitAbsValue(T val, T min_value, T max_value) { + static T limitAbsValue(T val, T min_value, T max_value) + { T val_abs = std::abs(val); T val_limited = std::max(val_abs, min_value); val_limited = std::min(val_limited, max_value); @@ -150,7 +158,8 @@ class Utils { /// Limits absolute value whole preserving sign template - static T clip(T val, T min_value, T max_value) { + static T clip(T val, T min_value, T max_value) + { return std::max(min_value, std::min(val, max_value)); } @@ -167,8 +176,7 @@ class Utils { stringstream ss; ss << prefix; - for (Iterator i = start; i != last; ++i) - { + for (Iterator i = start; i != last; ++i) { if (i != start) ss << delim; ss << *i; @@ -183,8 +191,7 @@ class Utils { int len = static_cast(str.size()); const char* ptr = str.c_str(); int i = 0; - for (i = len - 1; i >= 0; i--) - { + for (i = len - 1; i >= 0; i--) { if (ptr[i] == '.') break; } @@ -223,14 +230,12 @@ class Utils { int len = static_cast(str.size()); const char* ptr = str.c_str(); int i = 0; - for (i = 0; i < len; i++) - { + for (i = 0; i < len; i++) { if (ptr[i] != ch) break; } int j = 0; - for (j = len - 1; j >= i; j--) - { + for (j = len - 1; j >= i; j--) { if (ptr[j] != ch) break; } @@ -241,29 +246,24 @@ class Utils { { auto start = s.begin(); std::vector result; - for (auto it = s.begin(); it != s.end(); it++) - { + for (auto it = s.begin(); it != s.end(); it++) { char ch = *it; bool split = false; - for (int i = 0; i < numSplitChars; i++) - { + for (int i = 0; i < numSplitChars; i++) { if (ch == splitChars[i]) { split = true; break; } } - if (split) - { - if (start < it) - { + if (split) { + if (start < it) { result.push_back(string(start, it)); } start = it; start++; } } - if (start < s.end()) - { + if (start < s.end()) { result.push_back(string(start, s.end())); } return result; @@ -277,14 +277,12 @@ class Utils { auto start = line.begin(); std::vector result; auto end = line.end(); - for (auto it = line.begin(); it != end; ) - { + for (auto it = line.begin(); it != end; ) { bool split = false; char ch = *it; if (ch == '\'' || ch == '"') { // skip quoted literal - if (start < it) - { + if (start < it) { result.push_back(string(start, it)); } it++; @@ -303,10 +301,8 @@ class Utils { } } } - if (split) - { - if (start < it) - { + if (split) { + if (start < it) { result.push_back(string(start, it)); } start = it; @@ -316,8 +312,7 @@ class Utils { it++; } } - if (start < end) - { + if (start < end) { result.push_back(string(start, end)); } return result; @@ -333,8 +328,7 @@ class Utils { _strlwr_s(buf.get(), len + 1U); #else char* p = buf.get(); - for (int i = len; i > 0; i--) - { + for (int i = len; i > 0; i--) { *p = tolower(*p); p++; } @@ -368,15 +362,18 @@ class Utils { } template - static constexpr T nan() { + static constexpr T nan() + { return std::numeric_limits::quiet_NaN(); } template - static constexpr T max() { + static constexpr T max() + { return std::numeric_limits::max(); } template - static constexpr T min() { + static constexpr T min() + { return std::numeric_limits::min(); } diff --git a/MavLinkCom/include/AsyncResult.hpp b/MavLinkCom/include/AsyncResult.hpp index 64fb1ba310..f778c5556c 100644 --- a/MavLinkCom/include/AsyncResult.hpp +++ b/MavLinkCom/include/AsyncResult.hpp @@ -13,147 +13,166 @@ namespace mavlinkcom { - template - class AsyncResultState - { - public: - typedef std::function CompletionHandler; - mavlink_utils::Semaphore resultReceived_; - T result_; - CompletionHandler owner_; - int state_ = 0; - bool completed_ = false; - - AsyncResultState(CompletionHandler owner) { - owner_ = owner; - } +template +class AsyncResultState +{ +public: + typedef std::function CompletionHandler; + mavlink_utils::Semaphore resultReceived_; + T result_; + CompletionHandler owner_; + int state_ = 0; + bool completed_ = false; + + AsyncResultState(CompletionHandler owner) + { + owner_ = owner; + } - ~AsyncResultState() { - complete(); - } + ~AsyncResultState() + { + complete(); + } - int getState() { - return state_; - } - void setState(int s) { - state_ = s; - } - T getResult() { - resultReceived_.wait(); - return result_; - } - void setResult(T result) { - result_ = result; - resultReceived_.post(); + int getState() + { + return state_; + } + void setState(int s) + { + state_ = s; + } + T getResult() + { + resultReceived_.wait(); + return result_; + } + void setResult(T result) + { + result_ = result; + resultReceived_.post(); + complete(); + } + bool getResult(int millisecondTimeout, T* r) + { + if (!resultReceived_.timed_wait(millisecondTimeout)) { + // timeout on wait, so complete the task in this case too. complete(); + return false; } - bool getResult(int millisecondTimeout, T* r) { - if (!resultReceived_.timed_wait(millisecondTimeout)) { - // timeout on wait, so complete the task in this case too. - complete(); - return false; - } - *r = result_; - return true; - } - void complete() { - CompletionHandler rh = owner_; - owner_ = nullptr; - - completed_ = true; - if (rh != nullptr) { - rh(state_); - } + *r = result_; + return true; + } + void complete() + { + CompletionHandler rh = owner_; + owner_ = nullptr; + + completed_ = true; + if (rh != nullptr) { + rh(state_); } - bool isCompleted() { return completed_; } - }; + } + bool isCompleted() { return completed_; } +}; + +template +class AsyncResult +{ +public: + typedef std::function ResultHandler; + typedef std::function CompletionHandler; - template - class AsyncResult + AsyncResult(CompletionHandler owner) { - public: - typedef std::function ResultHandler; - typedef std::function CompletionHandler; + state_ = std::make_shared>(owner); + } + ~AsyncResult() + { + state_ = nullptr; + } - AsyncResult(CompletionHandler owner) - { - state_ = std::make_shared>(owner); - } - ~AsyncResult() - { - state_ = nullptr; - } + static AsyncResult Completed(T state) + { + AsyncResult r(nullptr); + r.setResult(state); + return r; + } - static AsyncResult Completed(T state) { - AsyncResult r(nullptr); - r.setResult(state); - return r; - } + void then(ResultHandler handler) + { + // keep state alive while we wait for async result. + std::shared_ptr> safe(state_); + T result = std::async(std::launch::async, getResult, safe).get(); + handler(result); + } - void then(ResultHandler handler) - { - // keep state alive while we wait for async result. - std::shared_ptr> safe(state_); - T result = std::async(std::launch::async, getResult, safe).get(); - handler(result); - } + int getState() + { + return state_->getState(); + } - int getState() { - return state_->getState(); + void setState(int s) const + { + state_->setState(s); + } + void setResult(T result) const + { + if (state_ != nullptr) { + state_->setResult(result); } + } - void setState(int s) const { - state_->setState(s); - } - void setResult(T result) const { - if (state_ != nullptr) { - state_->setResult(result); - } - } + AsyncResult(const AsyncResult& other) + { + this->state_ = other.state_; + } - AsyncResult(const AsyncResult& other) { + AsyncResult& operator=(const AsyncResult& other) + { + if (this != &other) { this->state_ = other.state_; } + return *this; + } - AsyncResult& operator=(const AsyncResult& other) { - if (this != &other) { - this->state_ = other.state_; - } - return *this; - } + AsyncResult(AsyncResult&& other) + { + this->state_ = other.state_; + other.state_ = nullptr; + } - AsyncResult(AsyncResult&& other) { + AsyncResult& operator=(AsyncResult&& other) + { + if (this != &other) { this->state_ = other.state_; other.state_ = nullptr; } + return *this; + } - AsyncResult& operator=(AsyncResult&& other) { - if (this != &other) { - this->state_ = other.state_; - other.state_ = nullptr; - } - return *this; - } - - bool wait(int millisecondTimeout, T* r) { - // keep the state alive while we wait. - std::shared_ptr> safe(state_); - return state_->getResult(millisecondTimeout, r); - } + bool wait(int millisecondTimeout, T* r) + { + // keep the state alive while we wait. + std::shared_ptr> safe(state_); + return state_->getResult(millisecondTimeout, r); + } - bool isCompleted() { - return state_->isCompleted(); - } + bool isCompleted() + { + return state_->isCompleted(); + } - private: - static T getResult(std::shared_ptr> state) { - return state->getResult(); - } +private: + static T getResult(std::shared_ptr> state) + { + return state->getResult(); + } - std::shared_ptr> state_; - }; + std::shared_ptr> state_; +}; } #endif diff --git a/MavLinkCom/include/MavLinkConnection.hpp b/MavLinkCom/include/MavLinkConnection.hpp index c77693b770..3760072db0 100644 --- a/MavLinkCom/include/MavLinkConnection.hpp +++ b/MavLinkCom/include/MavLinkConnection.hpp @@ -21,142 +21,142 @@ class Port; namespace mavlinkcom_impl { - class MavLinkConnectionImpl; - class MavLinkTcpServerImpl; - class MavLinkNodeImpl; +class MavLinkConnectionImpl; +class MavLinkTcpServerImpl; +class MavLinkNodeImpl; } namespace mavlinkcom { - class MavLinkConnection; - class MavLinkNode; - - // This callback is invoked when a MavLink message is read from the connection. - typedef std::function connection, const MavLinkMessage& msg)> MessageHandler; - - // This callback is invoked when a new TCP connection is accepted via acceptTcp(). - typedef std::function port)> MavLinkConnectionHandler; - - struct SerialPortInfo { - std::wstring displayName; - std::wstring portName; - int vid; - int pid; - }; - - // This class represents a single connection to a remote mavlink node connected either over UDP, TCP or Serial port. - // You can use this connection in a MavLinkNode to send a message directly to that node, and start listening to messages - // from that remote node. You can handle those messages directly using subscribe. - class MavLinkConnection : public std::enable_shared_from_this - { - public: - MavLinkConnection(); - - // Find available serial ports for the given vendor id/product id pair. If a matching port is found it returns the - // SerialPortInfo of that port, the portName can then be used connectSerial. Pass 0 for vid and pid to find all - // available serial ports. - static std::vector findSerialPorts(int vid, int pid); - - // create connection over serial port (e.g. /dev/ttyACM0 or on windows "com5"). - // pass initial string to write to the port, which can be used to configure the port. - // For example, on PX4 you can send "sh /etc/init.d/rc.usb\n" to turn on lots of mavlink streams. - static std::shared_ptr connectSerial(const std::string& nodeName, const std::string& portName, int baudrate = 115200, const std::string& initString = ""); - - // Start listening on a specific local port for packets from any remote computer. Once a packet is received - // it will remember the remote address of the sender so that subsequend sendMessage calls will go back to that sender. - // This is useful if the remote sender already knows which local port you plan to listen on. - // The localAddr can also a specific local ip address if you need to specify which - // network interface to use, for example, a corporate wired ethernet usually does not transmit UDP packets - // to a wifi connected device, so in that case the localAddress needs to be the IP address of a specific wifi internet - // adapter rather than 127.0.0.1. - static std::shared_ptr connectLocalUdp(const std::string& nodeName, const std::string& localAddr, int localPort); - - // Connect to a specific remote machine that is already listening on a specific port for messages from any computer. - // This will use any free local port that is available. - // The localAddr can also a specific local ip address if you need to specify which - // network interface to use, for example, a corporate wired ethernet usually does not transmit UDP packets - // to a wifi connected device, so in that case the localAddress needs to be the IP address of a specific wifi internet - // adapter rather than 127.0.0.1. - static std::shared_ptr connectRemoteUdp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteAddr, int remotePort); - - // This method sets up a tcp connection to the specified remote host and port. The remote host - // must already be listening and accepting TCP socket connections for this to succeed. - // The localAddr can also a specific local ip address if you need to specify which - // NIC to use, for example, wifi versus hard wired ethernet adapter. For localhost pass 127.0.0.1. - static std::shared_ptr connectTcp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteIpAddr, int remotePort); - - // This method accepts one tcp connection from a remote host on a given port. - // You may need to open this port in your firewall. - // The localAddr can also a specific local ip address if you need to specify which - // NIC to use, for example, wifi versus hard wired ethernet adapter. For localhost pass 127.0.0.1. - // It returns the address of the remote machine that connected. - std::string acceptTcp(const std::string& nodeName, const std::string& localAddr, int listeningPort); - - // instance methods - std::string getName(); - int getTargetComponentId(); - int getTargetSystemId(); - bool isOpen(); - void close(); - - // provide a callback function that will be called for every message "received" from the remote mavlink node. - int subscribe(MessageHandler handler); - void unsubscribe(int id); - - // log every message that is "sent" using sendMessage. - void startLoggingSendMessage(std::shared_ptr log); - void stopLoggingSendMessage(); - - // log every message that is "received" by a subscriber. - void startLoggingReceiveMessage(std::shared_ptr log); - void stopLoggingReceiveMessage(); - - uint8_t getNextSequence(); - - // Advanced method that create a bridge between two connections. For example, if you use connectRemoteUdp to connect to - // QGroundControl port 14550, and connectSerial to connect to PX4, then you can call this method to join the two so that - // all messages from PX4 are sent to QGroundControl and vice versa. - void join(std::shared_ptr remote, bool subscribeToLeft = true, bool subscribeToRight = true); - - // Pack and send the given message, assuming the compid and sysid have been set by the caller. - void sendMessage(const MavLinkMessageBase& msg); - - // Send the given already encoded message, assuming the compid and sysid have been set by the caller. - void sendMessage(const MavLinkMessage& msg); - - // get the next telemetry snapshot, then clear the internal counters and start over. This way each snapshot - // gives you a picture of what happened in whatever timeslice you decide to call this method. This is packaged - // in a mavlink message so you can easily send it to the LogViewer. - void getTelemetry(MavLinkTelemetry& result); - - //add the message in to list of ignored messages. These messages will not be sent in the sendMessage() call. - //this does not effect reception of message, however. This is typically useful in scenario where many connections - //are bridged and you don't want certain connection to read ceratin messages. - void ignoreMessage(uint8_t message_id); - - // Compute crc checksums, and pack according to mavlink1 or mavlink2 (depending on what target node supports) and do optional - // message signing according to the target node we are communicating with, and return the message length. - int prepareForSending(MavLinkMessage& msg); - - // Returns true if we are on the publishing thread. Certain blocing operations that wait for messages from mavlin vehicle are not - // allowed on this thread. - bool isPublishThread() const; - - protected: - void startListening(const std::string& nodeName, std::shared_ptr connectedPort); - - public: - //needed for piml pattern - ~MavLinkConnection(); - //MavLinkConnection(MavLinkConnection&&); - //MavLinkConnection& operator=(MavLinkConnection&&); - private: - std::unique_ptr pImpl; - friend class MavLinkNode; - friend class mavlinkcom_impl::MavLinkNodeImpl; - friend class mavlinkcom_impl::MavLinkConnectionImpl; - friend class mavlinkcom_impl::MavLinkTcpServerImpl; - }; +class MavLinkConnection; +class MavLinkNode; + +// This callback is invoked when a MavLink message is read from the connection. +typedef std::function connection, const MavLinkMessage& msg)> MessageHandler; + +// This callback is invoked when a new TCP connection is accepted via acceptTcp(). +typedef std::function port)> MavLinkConnectionHandler; + +struct SerialPortInfo { + std::wstring displayName; + std::wstring portName; + int vid; + int pid; +}; + +// This class represents a single connection to a remote mavlink node connected either over UDP, TCP or Serial port. +// You can use this connection in a MavLinkNode to send a message directly to that node, and start listening to messages +// from that remote node. You can handle those messages directly using subscribe. +class MavLinkConnection : public std::enable_shared_from_this +{ +public: + MavLinkConnection(); + + // Find available serial ports for the given vendor id/product id pair. If a matching port is found it returns the + // SerialPortInfo of that port, the portName can then be used connectSerial. Pass 0 for vid and pid to find all + // available serial ports. + static std::vector findSerialPorts(int vid, int pid); + + // create connection over serial port (e.g. /dev/ttyACM0 or on windows "com5"). + // pass initial string to write to the port, which can be used to configure the port. + // For example, on PX4 you can send "sh /etc/init.d/rc.usb\n" to turn on lots of mavlink streams. + static std::shared_ptr connectSerial(const std::string& nodeName, const std::string& portName, int baudrate = 115200, const std::string& initString = ""); + + // Start listening on a specific local port for packets from any remote computer. Once a packet is received + // it will remember the remote address of the sender so that subsequend sendMessage calls will go back to that sender. + // This is useful if the remote sender already knows which local port you plan to listen on. + // The localAddr can also a specific local ip address if you need to specify which + // network interface to use, for example, a corporate wired ethernet usually does not transmit UDP packets + // to a wifi connected device, so in that case the localAddress needs to be the IP address of a specific wifi internet + // adapter rather than 127.0.0.1. + static std::shared_ptr connectLocalUdp(const std::string& nodeName, const std::string& localAddr, int localPort); + + // Connect to a specific remote machine that is already listening on a specific port for messages from any computer. + // This will use any free local port that is available. + // The localAddr can also a specific local ip address if you need to specify which + // network interface to use, for example, a corporate wired ethernet usually does not transmit UDP packets + // to a wifi connected device, so in that case the localAddress needs to be the IP address of a specific wifi internet + // adapter rather than 127.0.0.1. + static std::shared_ptr connectRemoteUdp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteAddr, int remotePort); + + // This method sets up a tcp connection to the specified remote host and port. The remote host + // must already be listening and accepting TCP socket connections for this to succeed. + // The localAddr can also a specific local ip address if you need to specify which + // NIC to use, for example, wifi versus hard wired ethernet adapter. For localhost pass 127.0.0.1. + static std::shared_ptr connectTcp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteIpAddr, int remotePort); + + // This method accepts one tcp connection from a remote host on a given port. + // You may need to open this port in your firewall. + // The localAddr can also a specific local ip address if you need to specify which + // NIC to use, for example, wifi versus hard wired ethernet adapter. For localhost pass 127.0.0.1. + // It returns the address of the remote machine that connected. + std::string acceptTcp(const std::string& nodeName, const std::string& localAddr, int listeningPort); + + // instance methods + std::string getName(); + int getTargetComponentId(); + int getTargetSystemId(); + bool isOpen(); + void close(); + + // provide a callback function that will be called for every message "received" from the remote mavlink node. + int subscribe(MessageHandler handler); + void unsubscribe(int id); + + // log every message that is "sent" using sendMessage. + void startLoggingSendMessage(std::shared_ptr log); + void stopLoggingSendMessage(); + + // log every message that is "received" by a subscriber. + void startLoggingReceiveMessage(std::shared_ptr log); + void stopLoggingReceiveMessage(); + + uint8_t getNextSequence(); + + // Advanced method that create a bridge between two connections. For example, if you use connectRemoteUdp to connect to + // QGroundControl port 14550, and connectSerial to connect to PX4, then you can call this method to join the two so that + // all messages from PX4 are sent to QGroundControl and vice versa. + void join(std::shared_ptr remote, bool subscribeToLeft = true, bool subscribeToRight = true); + + // Pack and send the given message, assuming the compid and sysid have been set by the caller. + void sendMessage(const MavLinkMessageBase& msg); + + // Send the given already encoded message, assuming the compid and sysid have been set by the caller. + void sendMessage(const MavLinkMessage& msg); + + // get the next telemetry snapshot, then clear the internal counters and start over. This way each snapshot + // gives you a picture of what happened in whatever timeslice you decide to call this method. This is packaged + // in a mavlink message so you can easily send it to the LogViewer. + void getTelemetry(MavLinkTelemetry& result); + + //add the message in to list of ignored messages. These messages will not be sent in the sendMessage() call. + //this does not effect reception of message, however. This is typically useful in scenario where many connections + //are bridged and you don't want certain connection to read ceratin messages. + void ignoreMessage(uint8_t message_id); + + // Compute crc checksums, and pack according to mavlink1 or mavlink2 (depending on what target node supports) and do optional + // message signing according to the target node we are communicating with, and return the message length. + int prepareForSending(MavLinkMessage& msg); + + // Returns true if we are on the publishing thread. Certain blocing operations that wait for messages from mavlin vehicle are not + // allowed on this thread. + bool isPublishThread() const; + +protected: + void startListening(const std::string& nodeName, std::shared_ptr connectedPort); + +public: + //needed for piml pattern + ~MavLinkConnection(); + //MavLinkConnection(MavLinkConnection&&); + //MavLinkConnection& operator=(MavLinkConnection&&); +private: + std::unique_ptr pImpl; + friend class MavLinkNode; + friend class mavlinkcom_impl::MavLinkNodeImpl; + friend class mavlinkcom_impl::MavLinkConnectionImpl; + friend class mavlinkcom_impl::MavLinkTcpServerImpl; +}; } #endif diff --git a/MavLinkCom/include/MavLinkDebugLog.hpp b/MavLinkCom/include/MavLinkDebugLog.hpp index 4dada3d665..14e2cceb7b 100644 --- a/MavLinkCom/include/MavLinkDebugLog.hpp +++ b/MavLinkCom/include/MavLinkDebugLog.hpp @@ -9,29 +9,30 @@ namespace mavlinkcom { - class MavLinkDebugLog { - public: - virtual void log(int level, const std::string& message) - { - if (level >= 0) - std::cout << message; - else - std::cerr << message; - } +class MavLinkDebugLog +{ +public: + virtual void log(int level, const std::string& message) + { + if (level >= 0) + std::cout << message; + else + std::cerr << message; + } - static MavLinkDebugLog* getSetLogger(MavLinkDebugLog* logger = nullptr) - { - static MavLinkDebugLog logger_default_; - static MavLinkDebugLog* logger_; + static MavLinkDebugLog* getSetLogger(MavLinkDebugLog* logger = nullptr) + { + static MavLinkDebugLog logger_default_; + static MavLinkDebugLog* logger_; - if (logger != nullptr) - logger_ = logger; - else if (logger_ == nullptr) - logger_ = &logger_default_; + if (logger != nullptr) + logger_ = logger; + else if (logger_ == nullptr) + logger_ = &logger_default_; - return logger_; - } - }; + return logger_; + } +}; } #endif \ No newline at end of file diff --git a/MavLinkCom/include/MavLinkLog.hpp b/MavLinkCom/include/MavLinkLog.hpp index 3c22f95b84..922dfeaa47 100644 --- a/MavLinkCom/include/MavLinkLog.hpp +++ b/MavLinkCom/include/MavLinkLog.hpp @@ -14,34 +14,34 @@ namespace mavlinkcom { - // This abstract class defines the interface for logging MavLinkMessages. - class MavLinkLog - { - public: - virtual void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) = 0; - virtual ~MavLinkLog() = default; - }; - - // This implementation of MavLinkLog reads/writes MavLinkMessages to a local file. - class MavLinkFileLog : public MavLinkLog - { - std::string file_name_; - FILE* ptr_; - bool reading_; - bool writing_; - bool json_; - std::mutex log_lock_; - public: - MavLinkFileLog(); - virtual ~MavLinkFileLog(); - bool isOpen(); - void openForReading(const std::string& filename); - void openForWriting(const std::string& filename, bool json = false); - void close(); - virtual void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override; - bool read(mavlinkcom::MavLinkMessage& msg, uint64_t& timestamp); - static uint64_t getTimeStamp(); - }; +// This abstract class defines the interface for logging MavLinkMessages. +class MavLinkLog +{ +public: + virtual void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) = 0; + virtual ~MavLinkLog() = default; +}; + +// This implementation of MavLinkLog reads/writes MavLinkMessages to a local file. +class MavLinkFileLog : public MavLinkLog +{ + std::string file_name_; + FILE* ptr_; + bool reading_; + bool writing_; + bool json_; + std::mutex log_lock_; +public: + MavLinkFileLog(); + virtual ~MavLinkFileLog(); + bool isOpen(); + void openForReading(const std::string& filename); + void openForWriting(const std::string& filename, bool json = false); + void close(); + virtual void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override; + bool read(mavlinkcom::MavLinkMessage& msg, uint64_t& timestamp); + static uint64_t getTimeStamp(); +}; } diff --git a/MavLinkCom/include/MavLinkMessageBase.hpp b/MavLinkCom/include/MavLinkMessageBase.hpp index 570e0b654f..9444ee397a 100644 --- a/MavLinkCom/include/MavLinkMessageBase.hpp +++ b/MavLinkCom/include/MavLinkMessageBase.hpp @@ -14,167 +14,170 @@ namespace mavlinkcom_impl { } namespace mavlinkcom { - class MavLinkConnection; +class MavLinkConnection; #define PayloadSize ((255 + 2 + 7) / 8) - // This is the raw undecoded message, use the msgid field to figure out which strongly typed - // MavLinkMessageBase subclass can be used to decode this message. For example, a heartbeat: - // MavLinkMessage msg; - // if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) { - // MavLinkHeartbeat heartbeat; - // heartbeat.decode(msg); - // ... - // } - class MavLinkMessage { - public: - uint16_t checksum; ///< sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t incompat_flags; ///< flags that must be understood - uint8_t compat_flags; ///< flags that can be ignored if not understood - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint32_t msgid : 24; ///< ID of message in payload - uint64_t payload64[PayloadSize]; - uint8_t ck[2]; ///< incoming checksum bytes - uint8_t signature[13]; - uint8_t protocol_version; - - // initialize checksum - int update_checksum(); - }; - - // This is the base class for all the strongly typed messages define in MavLinkMessages.hpp - class MavLinkMessageBase - { - public: - uint32_t msgid = 0; - uint8_t sysid = 0; ///< ID of message sender system/aircraft - uint8_t compid = 0; ///< ID of the message sender component - uint64_t timestamp = 0; - uint8_t protocol_version = 0; - - // unpack the given message - void decode(const MavLinkMessage& msg); - // pack this message into given message buffer - void encode(MavLinkMessage& msg) const; - - // find what type of message this is and decode it on the heap (call delete when you are done with it). - static MavLinkMessageBase* lookup(const MavLinkMessage& msg); - virtual std::string toJSon() = 0; - virtual ~MavLinkMessageBase() {} - protected: - virtual int pack(char* buffer) const = 0; - virtual int unpack(const char* buffer) = 0; - - void pack_uint8_t(char* buffer, const uint8_t* field, int offset) const; - void pack_int8_t(char* buffer, const int8_t* field, int offset) const; - void pack_int16_t(char* buffer, const int16_t* field, int offset) const; - void pack_uint16_t(char* buffer, const uint16_t* field, int offset) const; - void pack_uint32_t(char* buffer, const uint32_t* field, int offset) const; - void pack_int32_t(char* buffer, const int32_t* field, int offset) const; - void pack_uint64_t(char* buffer, const uint64_t* field, int offset) const; - void pack_int64_t(char* buffer, const int64_t* field, int offset) const; - void pack_float(char* buffer, const float* field, int offset) const; - void pack_char_array(int len, char* buffer, const char* field, int offset) const; - void pack_uint8_t_array(int len, char* buffer, const uint8_t* field, int offset) const; - void pack_int8_t_array(int len, char* buffer, const int8_t* field, int offset) const; - void pack_uint16_t_array(int len, char* buffer, const uint16_t* field, int offset) const; - void pack_int16_t_array(int len, char* buffer, const int16_t* field, int offset) const; - void pack_float_array(int len, char* buffer, const float* field, int offset) const; +// This is the raw undecoded message, use the msgid field to figure out which strongly typed +// MavLinkMessageBase subclass can be used to decode this message. For example, a heartbeat: +// MavLinkMessage msg; +// if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) { +// MavLinkHeartbeat heartbeat; +// heartbeat.decode(msg); +// ... +// } +class MavLinkMessage +{ +public: + uint16_t checksum; ///< sent at end of packet + uint8_t magic; ///< protocol magic marker + uint8_t len; ///< Length of payload + uint8_t incompat_flags; ///< flags that must be understood + uint8_t compat_flags; ///< flags that can be ignored if not understood + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint32_t msgid : 24; ///< ID of message in payload + uint64_t payload64[PayloadSize]; + uint8_t ck[2]; ///< incoming checksum bytes + uint8_t signature[13]; + uint8_t protocol_version; + + // initialize checksum + int update_checksum(); +}; + +// This is the base class for all the strongly typed messages define in MavLinkMessages.hpp +class MavLinkMessageBase +{ +public: + uint32_t msgid = 0; + uint8_t sysid = 0; ///< ID of message sender system/aircraft + uint8_t compid = 0; ///< ID of the message sender component + uint64_t timestamp = 0; + uint8_t protocol_version = 0; + + // unpack the given message + void decode(const MavLinkMessage& msg); + // pack this message into given message buffer + void encode(MavLinkMessage& msg) const; + + // find what type of message this is and decode it on the heap (call delete when you are done with it). + static MavLinkMessageBase* lookup(const MavLinkMessage& msg); + virtual std::string toJSon() = 0; + virtual ~MavLinkMessageBase() {} +protected: + virtual int pack(char* buffer) const = 0; + virtual int unpack(const char* buffer) = 0; + + void pack_uint8_t(char* buffer, const uint8_t* field, int offset) const; + void pack_int8_t(char* buffer, const int8_t* field, int offset) const; + void pack_int16_t(char* buffer, const int16_t* field, int offset) const; + void pack_uint16_t(char* buffer, const uint16_t* field, int offset) const; + void pack_uint32_t(char* buffer, const uint32_t* field, int offset) const; + void pack_int32_t(char* buffer, const int32_t* field, int offset) const; + void pack_uint64_t(char* buffer, const uint64_t* field, int offset) const; + void pack_int64_t(char* buffer, const int64_t* field, int offset) const; + void pack_float(char* buffer, const float* field, int offset) const; + void pack_char_array(int len, char* buffer, const char* field, int offset) const; + void pack_uint8_t_array(int len, char* buffer, const uint8_t* field, int offset) const; + void pack_int8_t_array(int len, char* buffer, const int8_t* field, int offset) const; + void pack_uint16_t_array(int len, char* buffer, const uint16_t* field, int offset) const; + void pack_int16_t_array(int len, char* buffer, const int16_t* field, int offset) const; + void pack_float_array(int len, char* buffer, const float* field, int offset) const; - void unpack_uint8_t(const char* buffer, uint8_t* field, int offset); - void unpack_int8_t(const char* buffer, int8_t* field, int offset); - void unpack_int16_t(const char* buffer, int16_t* field, int offset); - void unpack_uint16_t(const char* buffer, uint16_t* field, int offset); - void unpack_uint32_t(const char* buffer, uint32_t* field, int offset); - void unpack_int32_t(const char* buffer, int32_t* field, int offset); - void unpack_uint64_t(const char* buffer, uint64_t* field, int offset); - void unpack_int64_t(const char* buffer, int64_t* field, int offset); - void unpack_float(const char* buffer, float* field, int offset); - void unpack_char_array(int len, const char* buffer, char* field, int offset); - void unpack_uint8_t_array(int len, const char* buffer, uint8_t* field, int offset); - void unpack_int8_t_array(int len, const char* buffer, int8_t* field, int offset); - void unpack_uint16_t_array(int len, const char* buffer, uint16_t* field, int offset); - void unpack_int16_t_array(int len, const char* buffer, int16_t* field, int offset); - void unpack_float_array(int len, const char* buffer, float* field, int offset); - - std::string char_array_tostring(int len, const char* field); - std::string uint8_t_array_tostring(int len, const uint8_t* field); - std::string int8_t_array_tostring(int len, const int8_t* field); - std::string int16_t_array_tostring(int len, const int16_t* field); - std::string uint16_t_array_tostring(int len, const uint16_t* field); - std::string float_array_tostring(int len, const float* field); - std::string float_tostring(float value); - }; - - // Base class for all strongly typed MavLinkCommand classes defined in MavLinkMessages.hpp - class MavLinkCommand { - public: - uint16_t command = 0; - protected: - virtual void pack() = 0; - virtual void unpack() = 0; - - float param1 = 0; - float param2 = 0; - float param3 = 0; - float param4 = 0; - float param5 = 0; - float param6 = 0; - float param7 = 0; - - friend class mavlinkcom_impl::MavLinkNodeImpl; - friend class mavlinkcom_impl::MavLinkConnectionImpl; - }; - - - // The location of a landing area captured from a downward facing camera - class MavLinkTelemetry : public MavLinkMessageBase { - public: - const static uint8_t kMessageId = 204; // in the user range 180-229. - const static int MessageLength = 12 * 4; - MavLinkTelemetry() { msgid = kMessageId; } - uint32_t messages_sent = 0; // number of messages sent since the last telemetry message - uint32_t messages_received = 0; // number of messages received since the last telemetry message - uint32_t messages_handled = 0; // number of messages handled since the last telemetry message - uint32_t crc_errors = 0; // # crc errors detected in mavlink stream since the last telemetry message - uint32_t handler_microseconds = 0; // total time spent in the handlers in microseconds since the last telemetry message - uint32_t render_time = 0; // total time spent rendering frames since the last telemetry message - int32_t wifi_rssi = 0; // if this device is communicating over wifi this is the signal strength. - uint32_t udpate_rate = 0; // rate at which update() is being called on MavLinkMultiRotorApi - uint32_t actuation_delay = 0; // delay from HIL_SENSOR to HIL_ACTUATORCONTROLS response - uint32_t sensor_rate = 0; // rate we are sending HIL_SENSOR messages - uint32_t lock_step_resets = 0; // total number of lock_step resets - uint32_t update_time = 0; // time inside MavLinkMultiRotorApi::update() method + void unpack_uint8_t(const char* buffer, uint8_t* field, int offset); + void unpack_int8_t(const char* buffer, int8_t* field, int offset); + void unpack_int16_t(const char* buffer, int16_t* field, int offset); + void unpack_uint16_t(const char* buffer, uint16_t* field, int offset); + void unpack_uint32_t(const char* buffer, uint32_t* field, int offset); + void unpack_int32_t(const char* buffer, int32_t* field, int offset); + void unpack_uint64_t(const char* buffer, uint64_t* field, int offset); + void unpack_int64_t(const char* buffer, int64_t* field, int offset); + void unpack_float(const char* buffer, float* field, int offset); + void unpack_char_array(int len, const char* buffer, char* field, int offset); + void unpack_uint8_t_array(int len, const char* buffer, uint8_t* field, int offset); + void unpack_int8_t_array(int len, const char* buffer, int8_t* field, int offset); + void unpack_uint16_t_array(int len, const char* buffer, uint16_t* field, int offset); + void unpack_int16_t_array(int len, const char* buffer, int16_t* field, int offset); + void unpack_float_array(int len, const char* buffer, float* field, int offset); + + std::string char_array_tostring(int len, const char* field); + std::string uint8_t_array_tostring(int len, const uint8_t* field); + std::string int8_t_array_tostring(int len, const int8_t* field); + std::string int16_t_array_tostring(int len, const int16_t* field); + std::string uint16_t_array_tostring(int len, const uint16_t* field); + std::string float_array_tostring(int len, const float* field); + std::string float_tostring(float value); +}; + +// Base class for all strongly typed MavLinkCommand classes defined in MavLinkMessages.hpp +class MavLinkCommand +{ +public: + uint16_t command = 0; +protected: + virtual void pack() = 0; + virtual void unpack() = 0; + + float param1 = 0; + float param2 = 0; + float param3 = 0; + float param4 = 0; + float param5 = 0; + float param6 = 0; + float param7 = 0; + + friend class mavlinkcom_impl::MavLinkNodeImpl; + friend class mavlinkcom_impl::MavLinkConnectionImpl; +}; + + +// The location of a landing area captured from a downward facing camera +class MavLinkTelemetry : public MavLinkMessageBase +{ +public: + const static uint8_t kMessageId = 204; // in the user range 180-229. + const static int MessageLength = 12 * 4; + MavLinkTelemetry() { msgid = kMessageId; } + uint32_t messages_sent = 0; // number of messages sent since the last telemetry message + uint32_t messages_received = 0; // number of messages received since the last telemetry message + uint32_t messages_handled = 0; // number of messages handled since the last telemetry message + uint32_t crc_errors = 0; // # crc errors detected in mavlink stream since the last telemetry message + uint32_t handler_microseconds = 0; // total time spent in the handlers in microseconds since the last telemetry message + uint32_t render_time = 0; // total time spent rendering frames since the last telemetry message + int32_t wifi_rssi = 0; // if this device is communicating over wifi this is the signal strength. + uint32_t udpate_rate = 0; // rate at which update() is being called on MavLinkMultiRotorApi + uint32_t actuation_delay = 0; // delay from HIL_SENSOR to HIL_ACTUATORCONTROLS response + uint32_t sensor_rate = 0; // rate we are sending HIL_SENSOR messages + uint32_t lock_step_resets = 0; // total number of lock_step resets + uint32_t update_time = 0; // time inside MavLinkMultiRotorApi::update() method - // not serialized - const char* wifiInterfaceName = nullptr; // the name of the wifi interface we are measuring RSSI on. - virtual std::string toJSon() { - - std::ostringstream result; - result << "\"MavLinkTelemetry\"" << " : { "; - result << "\"messages_sent\":" << this->messages_sent << ","; - result << "\"messages_received\":" << this->messages_received << ","; - result << "\"messages_handled\":" << this->messages_handled << ","; - result << "\"crc_errors\":" << this->crc_errors << ","; - result << "\"handler_microseconds\":" << this->handler_microseconds << ","; - result << "\"render_time\":" << this->render_time; - result << "\"wifi_rssi\":" << this->wifi_rssi; - result << "\"udpate_rate\":" << this->udpate_rate; - result << "\"actuation_delay\":" << this->actuation_delay; - result << "\"sensor_rate\":" << this->sensor_rate; - result << "\"lock_step_resets\":" << this->lock_step_resets; - result << "\"udpate_time\":" << this->update_time; - result << "}"; - return result.str(); - } - protected: - virtual int pack(char* buffer) const; - virtual int unpack(const char* buffer); - }; + // not serialized + const char* wifiInterfaceName = nullptr; // the name of the wifi interface we are measuring RSSI on. + virtual std::string toJSon() { + + std::ostringstream result; + result << "\"MavLinkTelemetry\"" << " : { "; + result << "\"messages_sent\":" << this->messages_sent << ","; + result << "\"messages_received\":" << this->messages_received << ","; + result << "\"messages_handled\":" << this->messages_handled << ","; + result << "\"crc_errors\":" << this->crc_errors << ","; + result << "\"handler_microseconds\":" << this->handler_microseconds << ","; + result << "\"render_time\":" << this->render_time; + result << "\"wifi_rssi\":" << this->wifi_rssi; + result << "\"udpate_rate\":" << this->udpate_rate; + result << "\"actuation_delay\":" << this->actuation_delay; + result << "\"sensor_rate\":" << this->sensor_rate; + result << "\"lock_step_resets\":" << this->lock_step_resets; + result << "\"udpate_time\":" << this->update_time; + result << "}"; + return result.str(); + } +protected: + virtual int pack(char* buffer) const; + virtual int unpack(const char* buffer); +}; } diff --git a/MavLinkCom/include/MavLinkNode.hpp b/MavLinkCom/include/MavLinkNode.hpp index be754090eb..0483dbbcc7 100644 --- a/MavLinkCom/include/MavLinkNode.hpp +++ b/MavLinkCom/include/MavLinkNode.hpp @@ -15,94 +15,95 @@ namespace mavlinkcom_impl { } namespace mavlinkcom { - struct MavLinkParameter { - public: - std::string name; - int index = -1; - float value = 0; - uint8_t type = 0; - }; - - class MavLinkCommand; - - // This is the base class for all MavLink objects that represent a single - // mavlink node. This class provides high level state that applies to any - // kind of mavlink node whether it is a vehicle, ground control, simulator - // or log viewer. This base class also implements the heartbeat protocol - // which pings heart beats back to the remote node to ensure it knows our - // connection is still alive. - class MavLinkNode - { - public: - MavLinkNode(int localSystemId, int localComponentId); - ~MavLinkNode(); - - // start listening to this connection - void connect(std::shared_ptr connection); - - // stop listening to the connection. - void close(); - - // Send heartbeat to drone. You should not do this if some other node is - // already doing it. - void startHeartbeat(); - - // get the list of configurable parameters supported by this node. - std::vector getParamList(); +struct MavLinkParameter +{ +public: + std::string name; + int index = -1; + float value = 0; + uint8_t type = 0; +}; + +class MavLinkCommand; + +// This is the base class for all MavLink objects that represent a single +// mavlink node. This class provides high level state that applies to any +// kind of mavlink node whether it is a vehicle, ground control, simulator +// or log viewer. This base class also implements the heartbeat protocol +// which pings heart beats back to the remote node to ensure it knows our +// connection is still alive. +class MavLinkNode +{ +public: + MavLinkNode(int localSystemId, int localComponentId); + ~MavLinkNode(); + + // start listening to this connection + void connect(std::shared_ptr connection); + + // stop listening to the connection. + void close(); + + // Send heartbeat to drone. You should not do this if some other node is + // already doing it. + void startHeartbeat(); + + // get the list of configurable parameters supported by this node. + std::vector getParamList(); - // get the parameter from last getParamList download. - MavLinkParameter getCachedParameter(const std::string& name); + // get the parameter from last getParamList download. + MavLinkParameter getCachedParameter(const std::string& name); - // get a single parameter by name. - AsyncResult getParameter(const std::string& name); + // get a single parameter by name. + AsyncResult getParameter(const std::string& name); - // set a new value on a given parameter. - // it is best if you use getParameter to get the current value, see if it - // needs changing, change the value, then call setParameter with the same parameter object. - AsyncResult setParameter(MavLinkParameter p); + // set a new value on a given parameter. + // it is best if you use getParameter to get the current value, see if it + // needs changing, change the value, then call setParameter with the same parameter object. + AsyncResult setParameter(MavLinkParameter p); - // get the connection - std::shared_ptr getConnection(); + // get the connection + std::shared_ptr getConnection(); - // get the capabilities of the drone - AsyncResult getCapabilities(); + // get the capabilities of the drone + AsyncResult getCapabilities(); - // request that target node sends this message stream at given frequency (specify messages per second that you want). - // where msgId is a MAVLINK_MSG_ID_* enum value. - void setMessageInterval(int msgId, int frequency); + // request that target node sends this message stream at given frequency (specify messages per second that you want). + // where msgId is a MAVLINK_MSG_ID_* enum value. + void setMessageInterval(int msgId, int frequency); - // wait a given amount of time for a heart beat, and return the decoded message. - AsyncResult waitForHeartbeat(); + // wait a given amount of time for a heart beat, and return the decoded message. + AsyncResult waitForHeartbeat(); - // send a single heartbeat - void sendOneHeartbeat(); + // send a single heartbeat + void sendOneHeartbeat(); - // Get the local system and component id - int getLocalSystemId(); - int getLocalComponentId(); + // Get the local system and component id + int getLocalSystemId(); + int getLocalComponentId(); - // Get the target system and component id on the other end of the connection. - int getTargetSystemId(); - int getTargetComponentId(); + // Get the target system and component id on the other end of the connection. + int getTargetSystemId(); + int getTargetComponentId(); - // Send a message to the remote node - void sendMessage(MavLinkMessageBase& msg); + // Send a message to the remote node + void sendMessage(MavLinkMessageBase& msg); - // Send raw undecoded messge to remote node (this is handy in proxy scenarios where you are simply - // passing a message along). - void sendMessage(MavLinkMessage& msg); + // Send raw undecoded messge to remote node (this is handy in proxy scenarios where you are simply + // passing a message along). + void sendMessage(MavLinkMessage& msg); - // send a command to the remote node - void sendCommand(MavLinkCommand& cmd); + // send a command to the remote node + void sendCommand(MavLinkCommand& cmd); - // send a command to the remote node and get async result that tells you whether it succeeded or not. - AsyncResult sendCommandAndWaitForAck(MavLinkCommand& cmd); - public: - MavLinkNode(); - //MavLinkNode(MavLinkNode&&); - protected: - std::unique_ptr pImpl; - }; + // send a command to the remote node and get async result that tells you whether it succeeded or not. + AsyncResult sendCommandAndWaitForAck(MavLinkCommand& cmd); +public: + MavLinkNode(); + //MavLinkNode(MavLinkNode&&); +protected: + std::unique_ptr pImpl; +}; } #endif diff --git a/MavLinkCom/include/MavLinkVehicle.hpp b/MavLinkCom/include/MavLinkVehicle.hpp index 9607041bbf..c29ae4d4b2 100644 --- a/MavLinkCom/include/MavLinkVehicle.hpp +++ b/MavLinkCom/include/MavLinkVehicle.hpp @@ -17,64 +17,65 @@ namespace mavlinkcom_impl { namespace mavlinkcom { - // This class represents a MavLinkNode that can be controlled, hence a "vehicle" of some sort. - // It also keeps certain state about the vehicle position so you can query it any time. - // All x,y,z coordinates are in the NED coordinate system. - class MavLinkVehicle : public MavLinkNode { - public: - MavLinkVehicle(int localSystemId, int localComponentId); +// This class represents a MavLinkNode that can be controlled, hence a "vehicle" of some sort. +// It also keeps certain state about the vehicle position so you can query it any time. +// All x,y,z coordinates are in the NED coordinate system. +class MavLinkVehicle : public MavLinkNode +{ +public: + MavLinkVehicle(int localSystemId, int localComponentId); - // Send command to arm or disarm the drone. Drone will not fly until it is armed successfully. - // It returns false if the command is rejected. - AsyncResult armDisarm(bool arm); - AsyncResult takeoff(float z = -2.5, float pitch = 0, float yaw = 0); - AsyncResult land(float yaw, float lat = 0, float lon = 0, float altitude = 0); - AsyncResult returnToHome(); - AsyncResult loiter(); - AsyncResult setPositionHoldMode(); - AsyncResult setStabilizedFlightMode(); - AsyncResult setHomePosition(float lat = 0, float lon = 0, float alt = 0); - AsyncResult setMissionMode(); - AsyncResult waitForHomePosition(); - AsyncResult allowFlightControlOverUsb(); - AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0, bool waitForAck = true); + // Send command to arm or disarm the drone. Drone will not fly until it is armed successfully. + // It returns false if the command is rejected. + AsyncResult armDisarm(bool arm); + AsyncResult takeoff(float z = -2.5, float pitch = 0, float yaw = 0); + AsyncResult land(float yaw, float lat = 0, float lon = 0, float altitude = 0); + AsyncResult returnToHome(); + AsyncResult loiter(); + AsyncResult setPositionHoldMode(); + AsyncResult setStabilizedFlightMode(); + AsyncResult setHomePosition(float lat = 0, float lon = 0, float alt = 0); + AsyncResult setMissionMode(); + AsyncResult waitForHomePosition(); + AsyncResult allowFlightControlOverUsb(); + AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0, bool waitForAck = true); - // wait for drone to reach specified local z, ensure it is not just blowing past the z location, - // wait for it to settle down with dz delta, and dvz delta velocity. - AsyncResult waitForAltitude(float z, float dz, float dvz); + // wait for drone to reach specified local z, ensure it is not just blowing past the z location, + // wait for it to settle down with dz delta, and dvz delta velocity. + AsyncResult waitForAltitude(float z, float dz, float dvz); - // request OFFBOARD control. - void requestControl(); - // release OFFBOARD control - void releaseControl(); - // return true if we still have offboard control (can lose this if user flips the switch). - bool hasOffboardControl(); + // request OFFBOARD control. + void requestControl(); + // release OFFBOARD control + void releaseControl(); + // return true if we still have offboard control (can lose this if user flips the switch). + bool hasOffboardControl(); - // offboard control methods. - bool isLocalControlSupported(); - void moveToLocalPosition(float x, float y, float z, bool isYaw, float yawOrRate); - void moveToGlobalPosition(float lat, float lon, float alt, bool isYaw, float yawOrRate); - void moveByLocalVelocity(float vx, float vy, float vz, bool isYaw, float yawOrRate); - void moveByLocalVelocityWithAltHold(float vx, float vy, float z, bool isYaw, float yawOrRate); - void writeMessage(MavLinkMessageBase& message, bool update_stats = true); + // offboard control methods. + bool isLocalControlSupported(); + void moveToLocalPosition(float x, float y, float z, bool isYaw, float yawOrRate); + void moveToGlobalPosition(float lat, float lon, float alt, bool isYaw, float yawOrRate); + void moveByLocalVelocity(float vx, float vy, float vz, bool isYaw, float yawOrRate); + void moveByLocalVelocityWithAltHold(float vx, float vy, float z, bool isYaw, float yawOrRate); + void writeMessage(MavLinkMessageBase& message, bool update_stats = true); - // low level control, only use this one if you really know what you are doing!! - bool isAttitudeControlSupported(); + // low level control, only use this one if you really know what you are doing!! + bool isAttitudeControlSupported(); - // Move drone by directly controlling the attitude of the drone (units are degrees). - // If the rollRate, pitchRate and yawRate are all zero then you will get the default rates provided by the drone. - void moveByAttitude(float roll, float pitch, float yaw, float rollRate, float pitchRate, float yawRate, float thrust); + // Move drone by directly controlling the attitude of the drone (units are degrees). + // If the rollRate, pitchRate and yawRate are all zero then you will get the default rates provided by the drone. + void moveByAttitude(float roll, float pitch, float yaw, float rollRate, float pitchRate, float yawRate, float thrust); - uint32_t getTimeStamp(); - int getVehicleStateVersion(); - const VehicleState& getVehicleState(); + uint32_t getTimeStamp(); + int getVehicleStateVersion(); + const VehicleState& getVehicleState(); - public: - //needed for piml pattern - MavLinkVehicle(); - ~MavLinkVehicle(); - //MavLinkVehicle(MavLinkVehicle&&); - }; +public: + //needed for piml pattern + MavLinkVehicle(); + ~MavLinkVehicle(); + //MavLinkVehicle(MavLinkVehicle&&); +}; } #endif diff --git a/MavLinkCom/src/MavLinkLog.cpp b/MavLinkCom/src/MavLinkLog.cpp index b8824eeabd..838aa0c448 100644 --- a/MavLinkCom/src/MavLinkLog.cpp +++ b/MavLinkCom/src/MavLinkLog.cpp @@ -19,205 +19,204 @@ uint64_t MavLinkFileLog::getTimeStamp() MavLinkFileLog::MavLinkFileLog() { - ptr_ = nullptr; - reading_ = false; - writing_ = false; - json_ = false; + ptr_ = nullptr; + reading_ = false; + writing_ = false; + json_ = false; } MavLinkFileLog::~MavLinkFileLog() { - close(); + close(); } bool MavLinkFileLog::isOpen() { - return reading_ || writing_; + return reading_ || writing_; } void MavLinkFileLog::openForReading(const std::string& filename) { - close(); - file_name_ = filename; - ptr_ = fopen(filename.c_str(), "rb"); - if (ptr_ == nullptr) { - throw std::runtime_error(Utils::stringf("Could not open the file %s, error=%d", filename.c_str(), errno)); - } + close(); + file_name_ = filename; + ptr_ = fopen(filename.c_str(), "rb"); + if (ptr_ == nullptr) { + throw std::runtime_error(Utils::stringf("Could not open the file %s, error=%d", filename.c_str(), errno)); + } fseek(ptr_, 0, SEEK_SET); - reading_ = true; - writing_ = false; + reading_ = true; + writing_ = false; } void MavLinkFileLog::openForWriting(const std::string& filename, bool json) { - close(); - json_ = json; - file_name_ = filename; - ptr_ = fopen(filename.c_str(), "wb"); - if (ptr_ == nullptr) { - throw std::runtime_error(Utils::stringf("Could not open the file %s, error=%d", filename.c_str(), errno)); - } - if (json) { - fprintf(ptr_, "{ \"rows\": [\n"); - } - reading_ = false; - writing_ = true; + close(); + json_ = json; + file_name_ = filename; + ptr_ = fopen(filename.c_str(), "wb"); + if (ptr_ == nullptr) { + throw std::runtime_error(Utils::stringf("Could not open the file %s, error=%d", filename.c_str(), errno)); + } + if (json) { + fprintf(ptr_, "{ \"rows\": [\n"); + } + reading_ = false; + writing_ = true; } void MavLinkFileLog::close() { - FILE* temp = ptr_; - if (json_ && ptr_ != nullptr) { + FILE* temp = ptr_; + if (json_ && ptr_ != nullptr) { fprintf(ptr_, " {}\n"); // so that trailing comma on last row isn't a problem. - fprintf(ptr_, "]}\n"); - } - ptr_ = nullptr; - if (temp != nullptr) { - fclose(temp); - } - reading_ = false; - writing_ = false; + fprintf(ptr_, "]}\n"); + } + ptr_ = nullptr; + if (temp != nullptr) { + fclose(temp); + } + reading_ = false; + writing_ = false; } uint64_t FlipEndianness(uint64_t v) { - uint64_t result = 0; - uint64_t shift = v; - const int size = sizeof(uint64_t); - for (int i = 0; i < size; i++) - { - uint64_t low = (shift & 0xff); - result = (result << 8) + low; - shift >>= 8; - } - return result; + uint64_t result = 0; + uint64_t shift = v; + const int size = sizeof(uint64_t); + for (int i = 0; i < size; i++) { + uint64_t low = (shift & 0xff); + result = (result << 8) + low; + shift >>= 8; + } + return result; } void MavLinkFileLog::write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp) { - if (ptr_ != nullptr) { - if (reading_) { - throw std::runtime_error("Log file was opened for reading"); - } - if (json_) { - MavLinkMessageBase* strongTypedMsg = MavLinkMessageBase::lookup(msg); - if (strongTypedMsg != nullptr) { + if (ptr_ != nullptr) { + if (reading_) { + throw std::runtime_error("Log file was opened for reading"); + } + if (json_) { + MavLinkMessageBase* strongTypedMsg = MavLinkMessageBase::lookup(msg); + if (strongTypedMsg != nullptr) { strongTypedMsg->timestamp = timestamp; - std::string line = strongTypedMsg->toJSon(); - { - std::lock_guard lock(log_lock_); - fprintf(ptr_, " %s\n", line.c_str()); - } + std::string line = strongTypedMsg->toJSon(); + { + std::lock_guard lock(log_lock_); + fprintf(ptr_, " %s\n", line.c_str()); + } delete strongTypedMsg; - } - } - else { + } + } + else { if (timestamp == 0) { timestamp = getTimeStamp(); } - // for compatibility with QGroundControl we have to save the time field in big endian. + // for compatibility with QGroundControl we have to save the time field in big endian. // todo: mavlink2 support? timestamp = FlipEndianness(timestamp); - uint8_t magic = msg.magic; - if (magic != MAVLINK_STX_MAVLINK1) { - // has to be one or the other! - magic = MAVLINK_STX; - } - - std::lock_guard lock(log_lock_); - fwrite(×tamp, sizeof(uint64_t), 1, ptr_); - fwrite(&magic, 1, 1, ptr_); - fwrite(&msg.len, 1, 1, ptr_); - fwrite(&msg.seq, 1, 1, ptr_); - fwrite(&msg.sysid, 1, 1, ptr_); - fwrite(&msg.compid, 1, 1, ptr_); - - if (magic == MAVLINK_STX_MAVLINK1) { - uint8_t msgid = msg.msgid & 0xff; // truncate to mavlink 2 msgid - fwrite(&msgid, 1, 1, ptr_); - } - else { - // 24 bits. - uint8_t msgid = msg.msgid & 0xFF; - fwrite(&msgid, 1, 1, ptr_); - msgid = (msg.msgid >> 8) & 0xFF; - fwrite(&msgid, 1, 1, ptr_); - msgid = (msg.msgid >> 16) & 0xFF; - fwrite(&msgid, 1, 1, ptr_); - } - - fwrite(&msg.payload64, 1, msg.len, ptr_); - fwrite(&msg.checksum, sizeof(uint16_t), 1, ptr_); - } - } + uint8_t magic = msg.magic; + if (magic != MAVLINK_STX_MAVLINK1) { + // has to be one or the other! + magic = MAVLINK_STX; + } + + std::lock_guard lock(log_lock_); + fwrite(×tamp, sizeof(uint64_t), 1, ptr_); + fwrite(&magic, 1, 1, ptr_); + fwrite(&msg.len, 1, 1, ptr_); + fwrite(&msg.seq, 1, 1, ptr_); + fwrite(&msg.sysid, 1, 1, ptr_); + fwrite(&msg.compid, 1, 1, ptr_); + + if (magic == MAVLINK_STX_MAVLINK1) { + uint8_t msgid = msg.msgid & 0xff; // truncate to mavlink 2 msgid + fwrite(&msgid, 1, 1, ptr_); + } + else { + // 24 bits. + uint8_t msgid = msg.msgid & 0xFF; + fwrite(&msgid, 1, 1, ptr_); + msgid = (msg.msgid >> 8) & 0xFF; + fwrite(&msgid, 1, 1, ptr_); + msgid = (msg.msgid >> 16) & 0xFF; + fwrite(&msgid, 1, 1, ptr_); + } + + fwrite(&msg.payload64, 1, msg.len, ptr_); + fwrite(&msg.checksum, sizeof(uint16_t), 1, ptr_); + } + } } bool MavLinkFileLog::read(mavlinkcom::MavLinkMessage& msg, uint64_t& timestamp) { - if (ptr_ != nullptr) { - if (writing_) { - throw std::runtime_error("Log file was opened for writing"); - } - uint64_t time; - - size_t s = fread(&time, 1, sizeof(uint64_t), ptr_); - if (s < sizeof(uint64_t)) { + if (ptr_ != nullptr) { + if (writing_) { + throw std::runtime_error("Log file was opened for writing"); + } + uint64_t time; + + size_t s = fread(&time, 1, sizeof(uint64_t), ptr_); + if (s < sizeof(uint64_t)) { int hr = errno; - return false; - } + return false; + } timestamp = FlipEndianness(time); - s = fread(&msg.magic, 1, 1, ptr_); - if (s == 0) { - return false; - } - s = fread(&msg.len, 1, 1, ptr_); - if (s == 0) { - return false; - } - s = fread(&msg.seq, 1, 1, ptr_); - if (s == 0) { - return false; - } - s = fread(&msg.sysid, 1, 1, ptr_); - if (s == 0) { - return false; - } - s = fread(&msg.compid, 1, 1, ptr_); - if (s == 0) { - return false; - } - - if (msg.magic == MAVLINK_STX_MAVLINK1) { - uint8_t msgid = 0; - s = fread(&msgid, 1, 1, ptr_); - msg.msgid = msgid; - } - else { - // 24 bits. - uint8_t msgid = 0; - s = fread(&msgid, 1, 1, ptr_); - msg.msgid = msgid; - s = fread(&msgid, 1, 1, ptr_); - msg.msgid |= (msgid << 8); - s = fread(&msgid, 1, 1, ptr_); - msg.msgid |= (msgid << 16); - } - - if (s < 1) { - return false; - } - s = fread(&msg.payload64, 1, msg.len, ptr_); - if (s < msg.len) { - return false; - } - s = fread(&msg.checksum, 1, sizeof(uint16_t), ptr_); - if (s < sizeof(uint16_t)) { - return false; - } - return true; - } - return false; + s = fread(&msg.magic, 1, 1, ptr_); + if (s == 0) { + return false; + } + s = fread(&msg.len, 1, 1, ptr_); + if (s == 0) { + return false; + } + s = fread(&msg.seq, 1, 1, ptr_); + if (s == 0) { + return false; + } + s = fread(&msg.sysid, 1, 1, ptr_); + if (s == 0) { + return false; + } + s = fread(&msg.compid, 1, 1, ptr_); + if (s == 0) { + return false; + } + + if (msg.magic == MAVLINK_STX_MAVLINK1) { + uint8_t msgid = 0; + s = fread(&msgid, 1, 1, ptr_); + msg.msgid = msgid; + } + else { + // 24 bits. + uint8_t msgid = 0; + s = fread(&msgid, 1, 1, ptr_); + msg.msgid = msgid; + s = fread(&msgid, 1, 1, ptr_); + msg.msgid |= (msgid << 8); + s = fread(&msgid, 1, 1, ptr_); + msg.msgid |= (msgid << 16); + } + + if (s < 1) { + return false; + } + s = fread(&msg.payload64, 1, msg.len, ptr_); + if (s < msg.len) { + return false; + } + s = fread(&msg.checksum, 1, sizeof(uint16_t), ptr_); + if (s < sizeof(uint16_t)) { + return false; + } + return true; + } + return false; } diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 2e1d3a4dfe..1ad22c0573 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -278,8 +278,7 @@ void MavLinkMessageBase::unpack_int8_t_array(int len, const char* buffer, int8_t } void MavLinkMessageBase::unpack_uint16_t_array(int len, const char* buffer, uint16_t* field, int offset) { - for (int i = 0; i < len; i++) - { + for (int i = 0; i < len; i++) { _mav_get_uint16_t(buffer, offset, field); offset += sizeof(uint16_t); field++; @@ -287,8 +286,7 @@ void MavLinkMessageBase::unpack_uint16_t_array(int len, const char* buffer, uint } void MavLinkMessageBase::unpack_int16_t_array(int len, const char* buffer, int16_t* field, int offset) { - for (int i = 0; i < len; i++) - { + for (int i = 0; i < len; i++) { _mav_get_int16_t(buffer, offset, field); offset += sizeof(int16_t); field++; @@ -296,8 +294,7 @@ void MavLinkMessageBase::unpack_int16_t_array(int len, const char* buffer, int16 } void MavLinkMessageBase::unpack_float_array(int len, const char* buffer, float* field, int offset) { - for (int i = 0; i < len; i++) - { + for (int i = 0; i < len; i++) { _mav_get_float(buffer, offset, field); offset += sizeof(float); field++; @@ -339,8 +336,7 @@ int MavLinkTelemetry::unpack(const char* buffer) { std::string MavLinkMessageBase::char_array_tostring(int len, const char* field) { int i = 0; - for (i= 0; i < len; i++) - { + for (i= 0; i < len; i++) { if (field[i] == '\0') break; } diff --git a/MavLinkCom/src/MavLinkVehicle.cpp b/MavLinkCom/src/MavLinkVehicle.cpp index 8ab9fd3040..ebdc95b60b 100644 --- a/MavLinkCom/src/MavLinkVehicle.cpp +++ b/MavLinkCom/src/MavLinkVehicle.cpp @@ -13,10 +13,12 @@ MavLinkVehicle::MavLinkVehicle(int localSystemId, int localComponentId) pImpl.reset(new MavLinkVehicleImpl(localSystemId, localComponentId)); } -MavLinkVehicle::MavLinkVehicle(){ +MavLinkVehicle::MavLinkVehicle() +{ } -MavLinkVehicle::~MavLinkVehicle() { +MavLinkVehicle::~MavLinkVehicle() +{ pImpl = nullptr; } diff --git a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp index b2c2496871..9b2970e057 100644 --- a/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkConnectionImpl.cpp @@ -215,8 +215,7 @@ void MavLinkConnectionImpl::sendMessage(const MavLinkMessage& m) ::memcpy(&msg, &m, sizeof(MavLinkMessage)); prepareForSending(msg); - if (sendLog_ != nullptr) - { + if (sendLog_ != nullptr) { sendLog_->write(msg); } @@ -364,10 +363,8 @@ int MavLinkConnectionImpl::subscribe(MessageHandler handler) void MavLinkConnectionImpl::unsubscribe(int id) { std::lock_guard guard(listener_mutex); - for (auto ptr = listeners.begin(), end = listeners.end(); ptr != end; ptr++) - { - if ((*ptr).id == id) - { + for (auto ptr = listeners.begin(), end = listeners.end(); ptr != end; ptr++) { + if ((*ptr).id == id) { listeners.erase(ptr); snapshot_stale = true; break; @@ -379,8 +376,7 @@ void MavLinkConnectionImpl::joinLeftSubscriber(std::shared_ptrpImpl->supports_mavlink2_ = true; } @@ -415,11 +411,9 @@ void MavLinkConnectionImpl::readPackets() mavlink_intermediate_status_.parse_state = MAVLINK_PARSE_STATE_IDLE; int channel = 0; int hr = 0; - while (hr == 0 && con_ != nullptr && !closed) - { + while (hr == 0 && con_ != nullptr && !closed) { int read = 0; - if (safePort->isClosed()) - { + if (safePort->isClosed()) { // hmmm, wait till it is opened? std::this_thread::sleep_for(std::chrono::milliseconds(10)); continue; @@ -431,8 +425,7 @@ void MavLinkConnectionImpl::readPackets() std::this_thread::sleep_for(std::chrono::milliseconds(1)); continue; } - for (int i = 0; i < count; i++) - { + for (int i = 0; i < count; i++) { uint8_t frame_state = mavlink_frame_char_buffer(&msgBuffer, &mavlink_intermediate_status_, buffer[i], &msg, &mavlink_status_); if (frame_state == MAVLINK_FRAMING_INCOMPLETE) { @@ -442,24 +435,21 @@ void MavLinkConnectionImpl::readPackets() std::lock_guard guard(telemetry_mutex_); telemetry_.crc_errors++; } - else if (frame_state == MAVLINK_FRAMING_OK) - { + else if (frame_state == MAVLINK_FRAMING_OK) { // pick up the sysid/compid of the remote node we are connected to. if (other_system_id == -1) { other_system_id = msg.sysid; other_component_id = msg.compid; } - if (mavlink_intermediate_status_.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) - { + if (mavlink_intermediate_status_.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { // then this is a mavlink 1 message } else if (!supports_mavlink2_) { // then this mavlink sender supports mavlink 2 supports_mavlink2_ = true; } - if (con_ != nullptr && !closed) - { + if (con_ != nullptr && !closed) { { std::lock_guard guard(telemetry_mutex_); telemetry_.messages_received++; @@ -513,8 +503,7 @@ void MavLinkConnectionImpl::drainQueue() hasMsg = true; } } - if (!hasMsg) - { + if (!hasMsg) { return; } @@ -536,20 +525,17 @@ void MavLinkConnectionImpl::drainQueue() } auto end = snapshot.end(); - if (message.msgid == static_cast(MavLinkMessageIds::MAVLINK_MSG_ID_AUTOPILOT_VERSION)) - { + if (message.msgid == static_cast(MavLinkMessageIds::MAVLINK_MSG_ID_AUTOPILOT_VERSION)) { MavLinkAutopilotVersion cap; cap.decode(message); - if ((cap.capabilities & MAV_PROTOCOL_CAPABILITY_MAVLINK2) != 0) - { + if ((cap.capabilities & MAV_PROTOCOL_CAPABILITY_MAVLINK2) != 0) { this->supports_mavlink2_ = true; } } auto startTime = std::chrono::system_clock::now(); std::shared_ptr sharedPtr = std::shared_ptr(this->con_); - for (auto ptr = snapshot.begin(); ptr != end; ptr++) - { + for (auto ptr = snapshot.begin(); ptr != end; ptr++) { try { (*ptr).handler(sharedPtr, message); } diff --git a/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp b/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp index be5067fa63..f76e2502f2 100644 --- a/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp +++ b/MavLinkCom/src/impl/MavLinkVehicleImpl.cpp @@ -435,8 +435,7 @@ void MavLinkVehicleImpl::handleMessage(std::shared_ptr connec // but we do want to know when we get the ack. So this is async ACK processing! MavLinkCommandAck ack; ack.decode(msg); - if (ack.command == MavCmdNavGuidedEnable::kCommandId) - { + if (ack.command == MavCmdNavGuidedEnable::kCommandId) { MAV_RESULT ackResult = static_cast(ack.result); if (ackResult == MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED) { Utils::log("### command MavCmdNavGuidedEnable result: MAV_RESULT_TEMPORARILY_REJECTED"); @@ -591,13 +590,11 @@ void MavLinkVehicleImpl::releaseControl() void MavLinkVehicleImpl::checkOffboard() { - if (!control_requested_) - { + if (!control_requested_) { throw std::runtime_error("You must call requestControl first."); } - if (control_requested_ && !vehicle_state_.controls.offboard) - { + if (control_requested_ && !vehicle_state_.controls.offboard) { // Ok, now's the time to actually request it since the caller is about to send MavLinkSetPositionTargetGlobalInt, but // PX4 will reject this thinking 'offboard_control_loss_timeout' because we haven't actually sent any offboard messages // yet. I know the PX4 protocol is kind of weird. So we prime the pump here with some dummy messages that tell the @@ -656,14 +653,12 @@ void MavLinkVehicleImpl::moveToGlobalPosition(float lat, float lon, float alt, b msg.type_mask = MAVLINK_MSG_SET_POSITION_TARGET_IGNORE_VELOCITY | MAVLINK_MSG_SET_POSITION_TARGET_IGNORE_ACCELERATION; - if (isYaw) - { + if (isYaw) { msg.type_mask |= MAVLINK_MSG_SET_POSITION_TARGET_IGNORE_YAW_RATE; msg.yaw = yawOrRate; msg.yaw_rate = 0; } - else - { + else { msg.type_mask |= MAVLINK_MSG_SET_POSITION_TARGET_IGNORE_YAW_ANGLE; msg.yaw = 0; msg.yaw_rate = yawOrRate; @@ -803,8 +798,7 @@ void MavLinkVehicleImpl::moveByLocalVelocityWithAltHold(float vx, float vy, floa msg.yaw = yawOrRate; msg.yaw_rate = 0; } - else - { + else { msg.type_mask |= MAVLINK_MSG_SET_POSITION_TARGET_IGNORE_YAW_ANGLE; msg.yaw = 0; msg.yaw_rate = yawOrRate; @@ -833,8 +827,7 @@ void MavLinkVehicleImpl::moveToLocalPosition(float x, float y, float z, bool isY msg.yaw = yawOrRate; msg.yaw_rate = 0; } - else - { + else { msg.type_mask |= MAVLINK_MSG_SET_POSITION_TARGET_IGNORE_YAW_ANGLE; msg.yaw = 0; msg.yaw_rate = yawOrRate; diff --git a/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp b/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp index 23b7b9ce25..377b91dd18 100644 --- a/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp +++ b/MavLinkCom/src/impl/MavLinkVehicleImpl.hpp @@ -22,73 +22,74 @@ using namespace mavlinkcom; namespace mavlinkcom_impl { - class MavLinkVehicleImpl : public MavLinkNodeImpl { - public: - MavLinkVehicleImpl(int localSystemId, int localComponentId); - ~MavLinkVehicleImpl(); - public: - AsyncResult armDisarm(bool arm); - AsyncResult takeoff(float z = -2.5, float pitch = 0, float yaw = 0); - AsyncResult land(float yaw, float lat = 0, float lon = 0, float altitude = 0); - AsyncResult returnToHome(); - AsyncResult loiter(); - AsyncResult setPositionHoldMode(); - AsyncResult setStabilizedFlightMode(); - AsyncResult setHomePosition(float lat = 0, float lon = 0, float alt = 0); - AsyncResult setMissionMode(); - AsyncResult waitForHomePosition(); - AsyncResult allowFlightControlOverUsb(); - AsyncResult waitForAltitude(float z, float dz, float dvz); - AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0, bool waitForAck = true); +class MavLinkVehicleImpl : public MavLinkNodeImpl +{ +public: + MavLinkVehicleImpl(int localSystemId, int localComponentId); + ~MavLinkVehicleImpl(); +public: + AsyncResult armDisarm(bool arm); + AsyncResult takeoff(float z = -2.5, float pitch = 0, float yaw = 0); + AsyncResult land(float yaw, float lat = 0, float lon = 0, float altitude = 0); + AsyncResult returnToHome(); + AsyncResult loiter(); + AsyncResult setPositionHoldMode(); + AsyncResult setStabilizedFlightMode(); + AsyncResult setHomePosition(float lat = 0, float lon = 0, float alt = 0); + AsyncResult setMissionMode(); + AsyncResult waitForHomePosition(); + AsyncResult allowFlightControlOverUsb(); + AsyncResult waitForAltitude(float z, float dz, float dvz); + AsyncResult setMode(int modeFlags, int customMode = 0, int customSubMode = 0, bool waitForAck = true); - // request OFFBOARD control. - void requestControl(); - // release OFFBOARD control - void releaseControl(); + // request OFFBOARD control. + void requestControl(); + // release OFFBOARD control + void releaseControl(); - // return true if we still have offboard control (can lose this if user flips the switch). - bool hasOffboardControl(); - // send this to keep offboard control but do no movement. - void offboardIdle(); + // return true if we still have offboard control (can lose this if user flips the switch). + bool hasOffboardControl(); + // send this to keep offboard control but do no movement. + void offboardIdle(); - // offboard control methods. - bool isLocalControlSupported(); - void moveToLocalPosition(float x, float y, float z, bool isYaw, float yawOrRate); - void moveToGlobalPosition(float lat, float lon, float alt, bool isYaw, float yawOrRate); - void moveByLocalVelocity(float vx, float vy, float vz, bool isYaw, float yawOrRate); - void moveByLocalVelocityWithAltHold(float vx, float vy, float z, bool isYaw, float yawOrRate); + // offboard control methods. + bool isLocalControlSupported(); + void moveToLocalPosition(float x, float y, float z, bool isYaw, float yawOrRate); + void moveToGlobalPosition(float lat, float lon, float alt, bool isYaw, float yawOrRate); + void moveByLocalVelocity(float vx, float vy, float vz, bool isYaw, float yawOrRate); + void moveByLocalVelocityWithAltHold(float vx, float vy, float z, bool isYaw, float yawOrRate); - // low level control, only use this one if you really know what you are doing!! - bool isAttitudeControlSupported(); + // low level control, only use this one if you really know what you are doing!! + bool isAttitudeControlSupported(); - // Move drone by directly controlling the attitude of the drone (units are degrees). - // If the rollRate, pitchRate and yawRate are all zero then you will get the default rates provided by the drone. - void moveByAttitude(float roll, float pitch, float yaw, float rollRate, float pitchRate, float yawRate, float thrust); - void writeMessage(MavLinkMessageBase& message, bool update_stats = true); + // Move drone by directly controlling the attitude of the drone (units are degrees). + // If the rollRate, pitchRate and yawRate are all zero then you will get the default rates provided by the drone. + void moveByAttitude(float roll, float pitch, float yaw, float rollRate, float pitchRate, float yawRate, float thrust); + void writeMessage(MavLinkMessageBase& message, bool update_stats = true); - int getVehicleStateVersion(); - const VehicleState& getVehicleState(); + int getVehicleStateVersion(); + const VehicleState& getVehicleState(); - uint32_t getTimeStamp(); - private: - virtual void handleMessage(std::shared_ptr connection, const MavLinkMessage& message); - void resetCommandParams(MavLinkCommandLong& cmd); - void updateReadStats(const MavLinkMessage& msg); - void checkOffboard(); - bool getRcSwitch(int channel, float threshold); + uint32_t getTimeStamp(); +private: + virtual void handleMessage(std::shared_ptr connection, const MavLinkMessage& message); + void resetCommandParams(MavLinkCommandLong& cmd); + void updateReadStats(const MavLinkMessage& msg); + void checkOffboard(); + bool getRcSwitch(int channel, float threshold); - private: - std::mutex state_mutex_; - int state_version_ = 0; - bool control_requested_ = false; - bool control_request_sent_ = false; - int requested_mode_ = 0; - int previous_mode_ = 0; - // this latch is reset even time we receive a heartbeat, this is useful for operations that we - // want to throttle to the heartbeat rate. - bool heartbeat_throttle_ = false; - VehicleState vehicle_state_; - }; +private: + std::mutex state_mutex_; + int state_version_ = 0; + bool control_requested_ = false; + bool control_request_sent_ = false; + int requested_mode_ = 0; + int previous_mode_ = 0; + // this latch is reset even time we receive a heartbeat, this is useful for operations that we + // want to throttle to the heartbeat rate. + bool heartbeat_throttle_ = false; + VehicleState vehicle_state_; +}; } #endif diff --git a/PythonClient/multirotor/path.py b/PythonClient/multirotor/path.py index d36fc6a900..6d34f13488 100644 --- a/PythonClient/multirotor/path.py +++ b/PythonClient/multirotor/path.py @@ -29,9 +29,9 @@ sys.exit(1) # AirSim uses NED coordinates so negative axis is up. -# z of -7 is 7 meters above the original launch point. -z = -7 -print("make sure we are hovering at 7 meters...") +# z of -5 is 5 meters above the original launch point. +z = -5 +print("make sure we are hovering at {} meters...".format(-z)) client.moveToZAsync(z, 1).join() # see https://github.com/Microsoft/AirSim/wiki/moveOnPath-demo diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp index 75ff5b739b..d25a174b68 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.cpp @@ -3,27 +3,26 @@ UnitySensorFactory::UnitySensorFactory(std::string vehicle_name, const NedTransform* ned_transform) { - setActor(vehicle_name, ned_transform); + setActor(vehicle_name, ned_transform); } void UnitySensorFactory::setActor(std::string vehicle_name, const NedTransform* ned_transform) { - vehicle_name_ = vehicle_name; - ned_transform_ = ned_transform; + vehicle_name_ = vehicle_name; + ned_transform_ = ned_transform; } std::shared_ptr UnitySensorFactory::createSensorFromSettings(const AirSimSettings::SensorSetting * sensor_setting) const { - - using SensorBase = msr::airlib::SensorBase; + + using SensorBase = msr::airlib::SensorBase; - switch (sensor_setting->sensor_type) - { - case SensorBase::SensorType::Distance: - return std::make_shared(vehicle_name_, ned_transform_); - default: - return msr::airlib::SensorFactory::createSensorFromSettings(sensor_setting); - } + switch (sensor_setting->sensor_type) { + case SensorBase::SensorType::Distance: + return std::make_shared(vehicle_name_, ned_transform_); + default: + return msr::airlib::SensorFactory::createSensorFromSettings(sensor_setting); + } - return std::shared_ptr(); + return std::shared_ptr(); } diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h index 75565a7b3d..1a50ed3e51 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/UnitySensors/UnitySensorFactory.h @@ -8,11 +8,11 @@ using namespace msr::airlib; class UnitySensorFactory : public SensorFactory { public: - UnitySensorFactory(std::string vehicle_name, const NedTransform* ned_transform); - void setActor(std::string vehicle_name, const NedTransform* ned_transform); - virtual std::shared_ptr createSensorFromSettings(const AirSimSettings::SensorSetting* sensor_setting) const override; + UnitySensorFactory(std::string vehicle_name, const NedTransform* ned_transform); + void setActor(std::string vehicle_name, const NedTransform* ned_transform); + virtual std::shared_ptr createSensorFromSettings(const AirSimSettings::SensorSetting* sensor_setting) const override; private: - std::string vehicle_name_; - const NedTransform* ned_transform_; + std::string vehicle_name_; + const NedTransform* ned_transform_; }; diff --git a/docs/log_viewer.md b/docs/log_viewer.md index 2f97249481..2934413f71 100644 --- a/docs/log_viewer.md +++ b/docs/log_viewer.md @@ -40,7 +40,7 @@ For this to work you need to configure the `settings.json` with the following se ``` Note: do not use the "Logs" setting when you want realtime LogViewer logging. Logging to -a file using "Logs" is mutually exclusive. with LogViewer logging. +a file using "Logs" is mutually exclusive with LogViewer logging. Simply press the blue connector button on the top right corner of the window, select the Socket `tab`, enter the port number `14388`, and your `localhost` network. If you are using WSL 2 on diff --git a/docs/px4_setup.md b/docs/px4_setup.md index 1a5b1bb178..03914471bf 100644 --- a/docs/px4_setup.md +++ b/docs/px4_setup.md @@ -2,7 +2,7 @@ The [PX4 software stack](http://github.com/px4/firmware) is an open source very popular flight controller with support for wide variety of boards and sensors as well as built-in capability for higher level tasks such as mission planning. Please visit [px4.io](http://px4.io) for more information. -**Warning**: While all releases of AirSim are always tested with PX4 to ensure the support, setting up PX4 is not a trivial task. Unless you have at least intermediate level of experience with PX4 stack, we recommend you use [simple_flight](simple_flight.md), which is now a default in AirSim. +**Warning**: While all releases of AirSim are always tested with PX4 to ensure the support, setting up PX4 is not a trivial task. Unless you have at least intermediate level of experience with PX4 stack, we recommend you use [simple_flight](simple_flight.md), which is now a default in AirSim. ## Supported Hardware @@ -26,7 +26,7 @@ For this you will need one of the supported device listed above. For manual flig 3. Use QGroundControl to flash the latest PX4 Flight Stack. See also [initial firmware setup video](https://docs.px4.io/master/en/config/). 4. In QGroundControl, configure your Pixhawk for HIL simulation by selecting the HIL Quadrocopter X airframe. After PX4 reboots, check that "HIL Quadrocopter X" is indeed selected. -5. In QGroundControl, go to Radio tab and calibrate (make sure the remote control is on and the receiver is showing the indicator for the binding). +5. In QGroundControl, go to Radio tab and calibrate (make sure the remote control is on and the receiver is showing the indicator for the binding). 6. Go to the Flight Mode tab and chose one of the remote control switches as "Mode Channel". Then set (for example) Stabilized and Attitude flight modes for two positions of the switch. 7. Go to the Tuning section of QGroundControl and set appropriate values. For example, for Fly Sky's FS-TH9X remote control, the following settings give a more realistic feel: Hover Throttle = mid+1 mark, Roll and pitch sensitivity = mid-3 mark, Altitude and position control sensitivity = mid-2 mark. 8. In [AirSim settings](settings.md) file, specify PX4 for your vehicle config like this: @@ -37,7 +37,7 @@ See also [initial firmware setup video](https://docs.px4.io/master/en/config/). "Vehicles": { "PX4": { "VehicleType": "PX4Multirotor", - "UseSerial": true,, + "UseSerial": true, "Sensors":{ "Barometer":{ "SensorType": 1, @@ -73,7 +73,7 @@ The PX4 SITL mode doesn't require you to have separate device such as a Pixhawk #### Drone doesn't fly properly, it just goes "crazy". -There are a few reasons that can cause this. First, make sure your drone doesn't fall down large distance when starting the simulator. This might happen if you have created a custom Unreal environment and Player Start is placed too high above the ground. It seems that when this happens internal calibration in PX4 gets confused. +There are a few reasons that can cause this. First, make sure your drone doesn't fall down large distance when starting the simulator. This might happen if you have created a custom Unreal environment and Player Start is placed too high above the ground. It seems that when this happens internal calibration in PX4 gets confused. You should [also use QGroundControl](#setting-up-px4-hardware-in-loop) and make sure you can arm and takeoff in QGroundControl properly. @@ -86,15 +86,15 @@ PX4 custom modes in the MAV_CMD_DO_SET_MODE messages (like PX4_CUSTOM_MAIN_MODE_ #### It is not finding my Pixhawk hardware -Check your settings.json file for this line "SerialPort":"*,115200". The asterisk here means "find any +Check your settings.json file for this line "SerialPort":"*,115200". The asterisk here means "find any serial port that looks like a Pixhawk device, but this doesn't always work for all types of Pixhawk hardware. -So on Windows you can find the actual COM port using Device Manager, look under "Ports (COM & LPT), plug the -device in and see what new COM port shows up. Let's say you see a new port named "USB Serial Port (COM5)". -Well, then change the SerialPort setting to this: "SerialPort":"COM5,115200". +So on Windows you can find the actual COM port using Device Manager, look under "Ports (COM & LPT), plug the +device in and see what new COM port shows up. Let's say you see a new port named "USB Serial Port (COM5)". +Well, then change the SerialPort setting to this: "SerialPort":"COM5,115200". On Linux, the device can be found by running "ls /dev/serial/by-id" if you see a device name listed that looks like this `usb-3D_Robotics_PX4_FMU_v2.x_0-if00` then you can use that name to connect, like this: -"SerialPort":"/dev/serial/by-id/usb-3D_Robotics_PX4_FMU_v2.x_0-if00". Note this long name is actually a symbolic link to the real +"SerialPort":"/dev/serial/by-id/usb-3D_Robotics_PX4_FMU_v2.x_0-if00". Note this long name is actually a symbolic link to the real name, if you use "ls -l ..." you can find that symbolic link, it is usually something like "/dev/ttyACM0", so this will also work "SerialPort":"/dev/ttyACM0,115200". But that mapping is similar to windows, it is automatically assigned and can change, whereas the long name will work even if the actual TTY serial device diff --git a/docs/px4_sitl.md b/docs/px4_sitl.md index 1e960d0eb3..2c664fa111 100644 --- a/docs/px4_sitl.md +++ b/docs/px4_sitl.md @@ -4,7 +4,7 @@ The [PX4](http://dev.px4.io) software provides a "software-in-loop" simulation ( their stack that runs in Linux. If you are on Windows then you can use the [Cygwin Toolchain](https://dev.px4.io/master/en/setup/dev_env_windows_cygwin.html) or you can use the [Windows subsystem for Linux](https://docs.microsoft.com/en-us/windows/wsl/install-win10) and follow -the PX4 Linux toolchain setup. +the PX4 Linux toolchain setup. If you are using WSL2 please read these [additional instructions](px4_sitl_wsl2.md). @@ -22,7 +22,7 @@ instructions](px4_sitl_wsl2.md). mkdir -p PX4 cd PX4 git clone https://github.com/PX4/PX4-Autopilot.git --recursive - bash ./PX4-Autopilot/Tools/setup/ubuntu.sh --no-nuttx --no-sim-tools + bash ./PX4-Autopilot/Tools/setup/ubuntu.sh --no-nuttx --no-sim-tools cd PX4-Autopilot ``` And find the latest stable release from [https://github.com/PX4/PX4-Autopilot/releases](https://github.com/PX4/PX4-Autopilot/releases) @@ -62,7 +62,7 @@ The default ports have changed recently, so check them closely to make sure AirS "UseSerial": false, "UseTcp": true, "TcpPort": 4560, - "ControlPort": 14580,, + "ControlPort": 14580, "Sensors":{ "Barometer":{ "SensorType": 1, From b717da44db009ae65c71b1e751963a4e5f3b7fe0 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 29 Apr 2021 16:12:24 -0700 Subject: [PATCH 30/37] fix typos. --- .../mavlink/MavLinkMultirotorApi.hpp | 2 +- PythonClient/multirotor/speaker.py | 1 - build.cmd | 48 +++++++++---------- 3 files changed, 25 insertions(+), 26 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index e0b297a050..a4946081d4 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -1744,7 +1744,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase } else { // creates too much log output, only do this when debugging this issue specifically. - // Utils::log(Utils::stringf("Ignornig msg %d from %d,%d ", msg.msgid, msg.compid, msg.sysid)); + // Utils::log(Utils::stringf("Ignoring msg %d from %d,%d ", msg.msgid, msg.compid, msg.sysid)); } } diff --git a/PythonClient/multirotor/speaker.py b/PythonClient/multirotor/speaker.py index c3beccefb0..acee778942 100644 --- a/PythonClient/multirotor/speaker.py +++ b/PythonClient/multirotor/speaker.py @@ -17,7 +17,6 @@ def __init__(self): self.audio = pyaudio.PyAudio() def open(self, audio_format, num_channels, rate): - # open speakers so we can hear what it is processing... self.output_stream = self.audio.open(format=audio_format, channels=num_channels, diff --git a/build.cmd b/build.cmd index 2476ebbb02..efc7395e7a 100644 --- a/build.cmd +++ b/build.cmd @@ -65,33 +65,33 @@ if ERRORLEVEL 1 ( REM //---------- get rpclib ---------- IF NOT EXIST external\rpclib mkdir external\rpclib IF NOT EXIST external\rpclib\rpclib-2.2.1 ( - REM //leave some blank lines because %powershell% shows download banner at top of console - ECHO( - ECHO( - ECHO( - ECHO ***************************************************************************************** - ECHO Downloading rpclib - ECHO ***************************************************************************************** - @echo on + REM //leave some blank lines because %powershell% shows download banner at top of console + ECHO( + ECHO( + ECHO( + ECHO ***************************************************************************************** + ECHO Downloading rpclib + ECHO ***************************************************************************************** + @echo on if "%PWSHV7%" == "" ( %powershell% -command "& { [Net.ServicePointManager]::SecurityProtocol = [Net.SecurityProtocolType]::Tls12; iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip }" ) else ( - %powershell% -command "iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip" + %powershell% -command "iwr https://github.com/madratman/rpclib/archive/v2.2.1.zip -OutFile external\rpclib.zip" + ) + @echo off + + REM //remove any previous versions + rmdir external\rpclib /q /s + + %powershell% -command "Expand-Archive -Path external\rpclib.zip -DestinationPath external\rpclib" + del external\rpclib.zip /q + + REM //Don't fail the build if the high-poly car is unable to be downloaded + REM //Instead, just notify users that the gokart will be used. + IF NOT EXIST external\rpclib\rpclib-2.2.1 ( + ECHO Unable to download high-polycount SUV. Your AirSim build will use the default vehicle. + goto :buildfailed ) - @echo off - - REM //remove any previous versions - rmdir external\rpclib /q /s - - %powershell% -command "Expand-Archive -Path external\rpclib.zip -DestinationPath external\rpclib" - del external\rpclib.zip /q - - REM //Don't fail the build if the high-poly car is unable to be downloaded - REM //Instead, just notify users that the gokart will be used. - IF NOT EXIST external\rpclib\rpclib-2.2.1 ( - ECHO Unable to download high-polycount SUV. Your AirSim build will use the default vehicle. - goto :buildfailed - ) ) REM //---------- Build rpclib ------------ @@ -148,7 +148,7 @@ IF NOT EXIST Unreal\Plugins\AirSim\Content\VehicleAdv\SUV\v1.2.0 ( %powershell% -command "iwr https://github.com/Microsoft/AirSim/releases/download/v1.2.0/car_assets.zip -OutFile suv_download_tmp\car_assets.zip" ) @echo off - rmdir /S /Q Unreal\Plugins\AirSim\Content\VehicleAdv\SUV + rmdir /S /Q Unreal\Plugins\AirSim\Content\VehicleAdv\SUV %powershell% -command "Expand-Archive -Path suv_download_tmp\car_assets.zip -DestinationPath Unreal\Plugins\AirSim\Content\VehicleAdv" rmdir suv_download_tmp /q /s From 609031bd0ec9c7b4628b84e60a72cda83a69b25d Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 29 Apr 2021 16:19:32 -0700 Subject: [PATCH 31/37] fix typo in udpate_rate --- .../multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp | 2 +- MavLinkCom/include/MavLinkMessageBase.hpp | 4 ++-- MavLinkCom/src/MavLinkMessageBase.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index a4946081d4..11e7a5441d 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -660,7 +660,7 @@ class MavLinkMultirotorApi : public MultirotorApiBase average_update = static_cast(update_time_ / hil_sensor_count_); } - data.udpate_rate = update_count_; + data.update_rate = update_count_; data.sensor_rate = hil_sensor_count_; data.actuation_delay = average_delay; data.lock_step_resets = lock_step_resets_; diff --git a/MavLinkCom/include/MavLinkMessageBase.hpp b/MavLinkCom/include/MavLinkMessageBase.hpp index 9444ee397a..071228fbd7 100644 --- a/MavLinkCom/include/MavLinkMessageBase.hpp +++ b/MavLinkCom/include/MavLinkMessageBase.hpp @@ -147,7 +147,7 @@ class MavLinkTelemetry : public MavLinkMessageBase uint32_t handler_microseconds = 0; // total time spent in the handlers in microseconds since the last telemetry message uint32_t render_time = 0; // total time spent rendering frames since the last telemetry message int32_t wifi_rssi = 0; // if this device is communicating over wifi this is the signal strength. - uint32_t udpate_rate = 0; // rate at which update() is being called on MavLinkMultiRotorApi + uint32_t update_rate = 0; // rate at which update() is being called on MavLinkMultiRotorApi uint32_t actuation_delay = 0; // delay from HIL_SENSOR to HIL_ACTUATORCONTROLS response uint32_t sensor_rate = 0; // rate we are sending HIL_SENSOR messages uint32_t lock_step_resets = 0; // total number of lock_step resets @@ -166,7 +166,7 @@ class MavLinkTelemetry : public MavLinkMessageBase result << "\"handler_microseconds\":" << this->handler_microseconds << ","; result << "\"render_time\":" << this->render_time; result << "\"wifi_rssi\":" << this->wifi_rssi; - result << "\"udpate_rate\":" << this->udpate_rate; + result << "\"update_rate\":" << this->update_rate; result << "\"actuation_delay\":" << this->actuation_delay; result << "\"sensor_rate\":" << this->sensor_rate; result << "\"lock_step_resets\":" << this->lock_step_resets; diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 1ad22c0573..8abd846a29 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -309,7 +309,7 @@ int MavLinkTelemetry::pack(char* buffer) const { pack_int32_t(buffer, reinterpret_cast(&this->handler_microseconds), 16); pack_int32_t(buffer, reinterpret_cast(&this->render_time), 20); pack_int32_t(buffer, reinterpret_cast(&this->wifi_rssi), 24); - pack_int32_t(buffer, reinterpret_cast(&this->udpate_rate), 28); + pack_int32_t(buffer, reinterpret_cast(&this->update_rate), 28); pack_int32_t(buffer, reinterpret_cast(&this->actuation_delay), 32); pack_int32_t(buffer, reinterpret_cast(&this->sensor_rate), 36); pack_int32_t(buffer, reinterpret_cast(&this->lock_step_resets), 40); @@ -325,7 +325,7 @@ int MavLinkTelemetry::unpack(const char* buffer) { unpack_int32_t(buffer, reinterpret_cast(&this->handler_microseconds), 16); unpack_int32_t(buffer, reinterpret_cast(&this->render_time), 20); unpack_int32_t(buffer, reinterpret_cast(&this->wifi_rssi), 24); - unpack_int32_t(buffer, reinterpret_cast(&this->udpate_rate), 28); + unpack_int32_t(buffer, reinterpret_cast(&this->update_rate), 28); unpack_int32_t(buffer, reinterpret_cast(&this->actuation_delay), 32); unpack_int32_t(buffer, reinterpret_cast(&this->sensor_rate), 36); unpack_int32_t(buffer, reinterpret_cast(&this->lock_step_resets), 40); From def8bc09a53ce5a98e04460ee3a17880faaa77be Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 29 Apr 2021 17:33:34 -0700 Subject: [PATCH 32/37] fix bugs. --- PythonClient/multirotor/hello_drone.py | 7 ++++--- PythonClient/requirements.txt | 1 + 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/PythonClient/multirotor/hello_drone.py b/PythonClient/multirotor/hello_drone.py index e51556e1c3..a9b4a4fa9c 100644 --- a/PythonClient/multirotor/hello_drone.py +++ b/PythonClient/multirotor/hello_drone.py @@ -1,4 +1,4 @@ -import setup_path +import setup_path import airsim import numpy as np @@ -11,7 +11,6 @@ client = airsim.MultirotorClient() client.confirmConnection() client.enableApiControl(True) -client.armDisarm(True) state = client.getMultirotorState() s = pprint.pformat(state) @@ -34,6 +33,8 @@ print("gps_data: %s" % s) airsim.wait_key('Press any key to takeoff') +print("Taking off...") +client.armDisarm(True) client.takeoffAsync().join() state = client.getMultirotorState() @@ -82,8 +83,8 @@ airsim.wait_key('Press any key to reset to original state') -client.armDisarm(False) client.reset() +client.armDisarm(False) # that's enough fun for now. let's quit cleanly client.enableApiControl(False) diff --git a/PythonClient/requirements.txt b/PythonClient/requirements.txt index e329ca18d3..1713d945ac 100644 --- a/PythonClient/requirements.txt +++ b/PythonClient/requirements.txt @@ -1,3 +1,4 @@ msgpack-rpc-python numpy pyaudio +opencv-contrib-python From c04924f058354499dc0a57b22262bd6e4dc95c2c Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 29 Apr 2021 17:51:45 -0700 Subject: [PATCH 33/37] clang format --- .clang-format | 56 + .../mavlink/MavLinkMultirotorApi.hpp | 3308 ++++++++--------- 2 files changed, 1709 insertions(+), 1655 deletions(-) create mode 100644 .clang-format diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000000..9f7e399e1d --- /dev/null +++ b/.clang-format @@ -0,0 +1,56 @@ +--- +# clang-format documentation +# http://clang.llvm.org/docs/ClangFormat.html +# http://clang.llvm.org/docs/ClangFormatStyleOptions.html + +# Preexisting formats: +# LLVM +# Google +# Chromium +# Mozilla +# WebKit + +Language: Cpp +BasedOnStyle: Mozilla + +AccessModifierOffset: -4 +AlignAfterOpenBracket: Align +AlignTrailingComments: false +AllowShortBlocksOnASingleLine: false +AllowShortFunctionsOnASingleLine: Inline +AllowShortIfStatementsOnASingleLine: true +AlwaysBreakAfterDefinitionReturnType: None +AlwaysBreakAfterReturnType: None +BinPackArguments: false +BinPackParameters: true +BreakBeforeBraces: Custom +BraceWrapping: + AfterClass: true + AfterControlStatement: false + AfterEnum: true + AfterFunction: true + AfterNamespace: true + AfterObjCDeclaration: false + AfterStruct: true + AfterUnion: true + BeforeCatch: true + BeforeElse: true + IndentBraces: false +ContinuationIndentWidth: 4 +ConstructorInitializerIndentWidth: 4 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +ColumnLimit: 0 +Cpp11BracedListStyle: false +IndentWidth: 4 +IndentCaseLabels: false +# KeepEmptyLinesAtTheStartOfBlocks: false +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: Inner +ReflowComments: false +PenaltyBreakBeforeFirstCallParameter: 100000 +PenaltyBreakComment: 100000 +SortIncludes: true +SpaceAfterTemplateKeyword: true +# Standard: Cpp11 # Broken +UseTab: Never +... diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 11e7a5441d..6e1977cee9 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -4,2029 +4,2027 @@ #ifndef msr_airlib_MavLinkDroneController_hpp #define msr_airlib_MavLinkDroneController_hpp -#include "MavLinkVehicle.hpp" #include "MavLinkConnection.hpp" #include "MavLinkMessages.hpp" #include "MavLinkNode.hpp" +#include "MavLinkVehicle.hpp" #include "MavLinkVideoStream.hpp" -#include +#include +#include #include +#include #include -#include -#include -#include #include #include +#include +#include "common/AirSimSettings.hpp" #include "common/Common.hpp" +#include "common/CommonStructs.hpp" +#include "common/PidController.hpp" +#include "common/VectorMath.hpp" #include "common/common_utils/FileSystem.hpp" #include "common/common_utils/SmoothingFilter.hpp" #include "common/common_utils/Timer.hpp" -#include "common/CommonStructs.hpp" -#include "common/VectorMath.hpp" -#include "common/AirSimSettings.hpp" -#include "vehicles/multirotor/api/MultirotorApiBase.hpp" -#include "common/PidController.hpp" -#include "sensors/SensorCollection.hpp" #include "physics/World.hpp" +#include "sensors/SensorCollection.hpp" +#include "vehicles/multirotor/api/MultirotorApiBase.hpp" //sensors #include "sensors/barometer/BarometerBase.hpp" -#include "sensors/imu/ImuBase.hpp" +#include "sensors/distance/DistanceSimple.hpp" #include "sensors/gps/GpsBase.hpp" +#include "sensors/imu/ImuBase.hpp" #include "sensors/magnetometer/MagnetometerBase.hpp" -#include "sensors/distance/DistanceSimple.hpp" -namespace msr { namespace airlib { - -class MavLinkMultirotorApi : public MultirotorApiBase +namespace msr +{ +namespace airlib { -public: //methods - virtual ~MavLinkMultirotorApi() - { - closeAllConnection(); - if (this->connect_thread_.joinable()) { - this->connect_thread_.join(); - } - if (this->telemetry_thread_.joinable()) { - this->telemetry_thread_.join(); - } - } - //non-base interface specific to MavLinKDroneController - void initialize(const AirSimSettings::MavLinkConnectionInfo& connection_info, const SensorCollection* sensors, bool is_simulation) + class MavLinkMultirotorApi : public MultirotorApiBase { - connection_info_ = connection_info; - sensors_ = sensors; - is_simulation_mode_ = is_simulation; - - try { - openAllConnections(); - is_ready_ = true; - } - catch (std::exception& ex) { - is_ready_ = false; - is_ready_message_ = Utils::stringf("Failed to connect: %s", ex.what()); + public: //methods + virtual ~MavLinkMultirotorApi() + { + closeAllConnection(); + if (this->connect_thread_.joinable()) { + this->connect_thread_.join(); + } + if (this->telemetry_thread_.joinable()) { + this->telemetry_thread_.join(); + } } - } - - Pose getMocapPose() - { - std::lock_guard guard(mocap_pose_mutex_); - return mocap_pose_; - } - virtual const SensorCollection& getSensors() const override - { - return *sensors_; - } - - //reset PX4 stack - virtual void resetImplementation() override - { - // note this is called AFTER "initialize" when we've connected to the drone - // so this method cannot reset any of that connection state. - world_ = nullptr; + //non-base interface specific to MavLinKDroneController + void initialize(const AirSimSettings::MavLinkConnectionInfo& connection_info, const SensorCollection* sensors, bool is_simulation) + { + connection_info_ = connection_info; + sensors_ = sensors; + is_simulation_mode_ = is_simulation; - for (UpdatableObject* container = this->getParent(); container != nullptr; container = container->getParent()) { - if (container->getName() == "World") { - // cool beans! - // note: cannot use dynamic_cast because Unreal builds with /GR- for some unknown reason... - world_ = static_cast(container); + try { + openAllConnections(); + is_ready_ = true; } - } - MultirotorApiBase::resetImplementation(); - was_reset_ = true; - } - - unsigned long long getSimTime() - { - // This ensures HIL_SENSOR and HIL_GPS have matching clocks. - if (lock_step_enabled_) { - if (sim_time_us_ == 0) { - sim_time_us_ = clock()->nowNanos() / 1000; + catch (std::exception& ex) { + is_ready_ = false; + is_ready_message_ = Utils::stringf("Failed to connect: %s", ex.what()); } - return sim_time_us_; - } - else { - return clock()->nowNanos() / 1000; } - } - - void advanceTime() - { - sim_time_us_ = clock()->nowNanos() / 1000; - } - //update sensors in PX4 stack - virtual void update() override - { - try { - auto now = clock()->nowNanos() / 1000; - MultirotorApiBase::update(); + Pose getMocapPose() + { + std::lock_guard guard(mocap_pose_mutex_); + return mocap_pose_; + } - if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) - return; + virtual const SensorCollection& getSensors() const override + { + return *sensors_; + } - { - std::lock_guard guard(telemetry_mutex_); - update_count_++; + //reset PX4 stack + virtual void resetImplementation() override + { + // note this is called AFTER "initialize" when we've connected to the drone + // so this method cannot reset any of that connection state. + world_ = nullptr; + + for (UpdatableObject* container = this->getParent(); container != nullptr; container = container->getParent()) { + if (container->getName() == "World") { + // cool beans! + // note: cannot use dynamic_cast because Unreal builds with /GR- for some unknown reason... + world_ = static_cast(container); + } } + MultirotorApiBase::resetImplementation(); + was_reset_ = true; + } + unsigned long long getSimTime() + { + // This ensures HIL_SENSOR and HIL_GPS have matching clocks. if (lock_step_enabled_) { - if (last_update_time_ + 100000 < now) { - // if 100 ms passes then something is terribly wrong, reset lockstep mode - lock_step_enabled_ = false; - { - std::lock_guard guard(telemetry_mutex_); - lock_step_resets_++; - } - addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); - } - else if (!received_actuator_controls_) { - // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. - return; + if (sim_time_us_ == 0) { + sim_time_us_ = clock()->nowNanos() / 1000; } + return sim_time_us_; } - - last_update_time_ = now; - - { - std::lock_guard guard(telemetry_mutex_); - hil_sensor_count_++; + else { + return clock()->nowNanos() / 1000; } - advanceTime(); + } - //send sensor updates - const auto& imu_output = getImuData(""); - const auto& mag_output = getMagnetometerData(""); - const auto& baro_output = getBarometerData(""); + void advanceTime() + { + sim_time_us_ = clock()->nowNanos() / 1000; + } - sendHILSensor(imu_output.linear_acceleration, - imu_output.angular_velocity, - mag_output.magnetic_field_body, - baro_output.pressure * 0.01f /*Pa to Millibar */, baro_output.altitude); + //update sensors in PX4 stack + virtual void update() override + { + try { + auto now = clock()->nowNanos() / 1000; + MultirotorApiBase::update(); - sendSystemTime(); + if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_) + return; - const uint count_distance_sensors = getSensors().size(SensorBase::SensorType::Distance); - if (count_distance_sensors != 0) { - const auto* distance_sensor = static_cast( - sensors_->getByType(SensorBase::SensorType::Distance)); - // Don't send the data if sending to external controller is disabled in settings - if (distance_sensor && distance_sensor->getParams().external_controller) { - const auto& distance_output = distance_sensor->getOutput(); + { + std::lock_guard guard(telemetry_mutex_); + update_count_++; + } - sendDistanceSensor(distance_output.min_distance * 100, //m -> cm - distance_output.max_distance * 100, //m -> cm - distance_output.distance * 100, //m-> cm - 0, //sensor type: //TODO: allow changing in settings? - 77, //sensor id, //TODO: should this be something real? - distance_output.relative_pose.orientation); //TODO: convert from radians to degrees? + if (lock_step_enabled_) { + if (last_update_time_ + 100000 < now) { + // if 100 ms passes then something is terribly wrong, reset lockstep mode + lock_step_enabled_ = false; + { + std::lock_guard guard(telemetry_mutex_); + lock_step_resets_++; + } + addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode"); + } + else if (!received_actuator_controls_) { + // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage. + return; + } } - } - const uint count_gps_sensors = getSensors().size(SensorBase::SensorType::Gps); - if (count_gps_sensors != 0) { - const auto& gps_output = getGpsData(""); + last_update_time_ = now; - //send GPS - if (gps_output.is_valid && gps_output.gnss.time_utc > last_gps_time_) { - last_gps_time_ = gps_output.gnss.time_utc; - Vector3r gps_velocity = gps_output.gnss.velocity; - Vector3r gps_velocity_xy = gps_velocity; - gps_velocity_xy.z() = 0; - float gps_cog; - if (Utils::isApproximatelyZero(gps_velocity.y(), 1E-2f) && Utils::isApproximatelyZero(gps_velocity.x(), 1E-2f)) - gps_cog = 0; - else - gps_cog = Utils::radiansToDegrees(atan2(gps_velocity.y(), gps_velocity.x())); - if (gps_cog < 0) - gps_cog += 360; + { + std::lock_guard guard(telemetry_mutex_); + hil_sensor_count_++; + } + advanceTime(); + + //send sensor updates + const auto& imu_output = getImuData(""); + const auto& mag_output = getMagnetometerData(""); + const auto& baro_output = getBarometerData(""); + + sendHILSensor(imu_output.linear_acceleration, + imu_output.angular_velocity, + mag_output.magnetic_field_body, + baro_output.pressure * 0.01f /*Pa to Millibar */, + baro_output.altitude); + + sendSystemTime(); + + const uint count_distance_sensors = getSensors().size(SensorBase::SensorType::Distance); + if (count_distance_sensors != 0) { + const auto* distance_sensor = static_cast( + sensors_->getByType(SensorBase::SensorType::Distance)); + // Don't send the data if sending to external controller is disabled in settings + if (distance_sensor && distance_sensor->getParams().external_controller) { + const auto& distance_output = distance_sensor->getOutput(); + + sendDistanceSensor(distance_output.min_distance * 100, //m -> cm + distance_output.max_distance * 100, //m -> cm + distance_output.distance * 100, //m-> cm + 0, //sensor type: //TODO: allow changing in settings? + 77, //sensor id, //TODO: should this be something real? + distance_output.relative_pose.orientation); //TODO: convert from radians to degrees? + } + } - sendHILGps(gps_output.gnss.geo_point, gps_velocity, gps_velocity_xy.norm(), gps_cog, - gps_output.gnss.eph, gps_output.gnss.epv, gps_output.gnss.fix_type, 10); + const uint count_gps_sensors = getSensors().size(SensorBase::SensorType::Gps); + if (count_gps_sensors != 0) { + const auto& gps_output = getGpsData(""); + + //send GPS + if (gps_output.is_valid && gps_output.gnss.time_utc > last_gps_time_) { + last_gps_time_ = gps_output.gnss.time_utc; + Vector3r gps_velocity = gps_output.gnss.velocity; + Vector3r gps_velocity_xy = gps_velocity; + gps_velocity_xy.z() = 0; + float gps_cog; + if (Utils::isApproximatelyZero(gps_velocity.y(), 1E-2f) && Utils::isApproximatelyZero(gps_velocity.x(), 1E-2f)) + gps_cog = 0; + else + gps_cog = Utils::radiansToDegrees(atan2(gps_velocity.y(), gps_velocity.x())); + if (gps_cog < 0) + gps_cog += 360; + + sendHILGps(gps_output.gnss.geo_point, gps_velocity, gps_velocity_xy.norm(), gps_cog, gps_output.gnss.eph, gps_output.gnss.epv, gps_output.gnss.fix_type, 10); + } } - } - auto end = clock()->nowNanos() / 1000; - { - std::lock_guard guard(telemetry_mutex_); - update_time_ += (end - now); + auto end = clock()->nowNanos() / 1000; + { + std::lock_guard guard(telemetry_mutex_); + update_time_ += (end - now); + } + } + catch (std::exception& e) { + addStatusMessage("Exception sending messages to vehicle"); + addStatusMessage(e.what()); + disconnect(); + connect(); // re-start a new connection so PX4 can be restarted and AirSim will happily continue on. } - } - catch (std::exception& e) { - addStatusMessage("Exception sending messages to vehicle"); - addStatusMessage(e.what()); - disconnect(); - connect(); // re-start a new connection so PX4 can be restarted and AirSim will happily continue on. - } - - //must be done at the end - if (was_reset_) - was_reset_ = false; - } + //must be done at the end + if (was_reset_) + was_reset_ = false; + } - virtual bool isReady(std::string& message) const override - { - if (!is_ready_ && is_ready_message_.size() > 0) { - message = is_ready_message_; + virtual bool isReady(std::string& message) const override + { + if (!is_ready_ && is_ready_message_.size() > 0) { + message = is_ready_message_; + } + return is_ready_; } - return is_ready_; - } - virtual bool canArm() const override - { - return is_ready_ && has_gps_lock_; - } + virtual bool canArm() const override + { + return is_ready_ && has_gps_lock_; + } - //TODO: this method can't be const yet because it clears previous messages - virtual void getStatusMessages(std::vector& messages) override - { - updateState(); + //TODO: this method can't be const yet because it clears previous messages + virtual void getStatusMessages(std::vector& messages) override + { + updateState(); - //clear param - messages.clear(); + //clear param + messages.clear(); - //move messages from private vars to param - std::lock_guard guard(status_text_mutex_); - while (!status_messages_.empty()) { - messages.push_back(status_messages_.front()); - status_messages_.pop(); + //move messages from private vars to param + std::lock_guard guard(status_text_mutex_); + while (!status_messages_.empty()) { + messages.push_back(status_messages_.front()); + status_messages_.pop(); + } } - } - virtual Kinematics::State getKinematicsEstimated() const override - { - updateState(); - Kinematics::State state; - //TODO: reduce code duplication in getPosition() etc methods? - state.pose.position = Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); - state.pose.orientation = VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); - state.twist.linear = Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); - state.twist.angular = Vector3r(current_state_.attitude.roll_rate, current_state_.attitude.pitch_rate, current_state_.attitude.yaw_rate); - state.accelerations.linear = Vector3r(current_state_.local_est.acc.x, current_state_.local_est.acc.y, current_state_.local_est.acc.z); - //TODO: how do we get angular acceleration? - return state; - } - - virtual bool isApiControlEnabled() const override - { - return is_api_control_enabled_; - } + virtual Kinematics::State getKinematicsEstimated() const override + { + updateState(); + Kinematics::State state; + //TODO: reduce code duplication in getPosition() etc methods? + state.pose.position = Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); + state.pose.orientation = VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); + state.twist.linear = Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); + state.twist.angular = Vector3r(current_state_.attitude.roll_rate, current_state_.attitude.pitch_rate, current_state_.attitude.yaw_rate); + state.accelerations.linear = Vector3r(current_state_.local_est.acc.x, current_state_.local_est.acc.y, current_state_.local_est.acc.z); + //TODO: how do we get angular acceleration? + return state; + } + + virtual bool isApiControlEnabled() const override + { + return is_api_control_enabled_; + } - virtual void enableApiControl(bool is_enabled) override - { - checkValidVehicle(); - if (is_enabled) { - mav_vehicle_->requestControl(); - is_api_control_enabled_ = true; + virtual void enableApiControl(bool is_enabled) override + { + checkValidVehicle(); + if (is_enabled) { + mav_vehicle_->requestControl(); + is_api_control_enabled_ = true; + } + else { + mav_vehicle_->releaseControl(); + is_api_control_enabled_ = false; + } } - else { - mav_vehicle_->releaseControl(); - is_api_control_enabled_ = false; + + virtual Vector3r getPosition() const override + { + updateState(); + return Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); } - } - virtual Vector3r getPosition() const override - { - updateState(); - return Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z); - } + virtual Vector3r getVelocity() const override + { + updateState(); + return Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); + } - virtual Vector3r getVelocity() const override - { - updateState(); - return Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z); - } + virtual Quaternionr getOrientation() const override + { + updateState(); + return VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); + } - virtual Quaternionr getOrientation() const override - { - updateState(); - return VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw); - } + virtual LandedState getLandedState() const override + { + updateState(); + return current_state_.controls.landed ? LandedState::Landed : LandedState::Flying; + } - virtual LandedState getLandedState() const override - { - updateState(); - return current_state_.controls.landed ? LandedState::Landed : LandedState::Flying; - } + virtual real_T getActuation(unsigned int rotor_index) const override + { + if (!is_simulation_mode_) + throw std::logic_error("Attempt to read motor controls while not in simulation mode"); - virtual real_T getActuation(unsigned int rotor_index) const override - { - if (!is_simulation_mode_) - throw std::logic_error("Attempt to read motor controls while not in simulation mode"); + std::lock_guard guard(hil_controls_mutex_); + return rotor_controls_[rotor_index]; + } - std::lock_guard guard(hil_controls_mutex_); - return rotor_controls_[rotor_index]; - } + virtual size_t getActuatorCount() const override + { + return RotorControlsCount; + } - virtual size_t getActuatorCount() const override - { - return RotorControlsCount; - } + virtual bool armDisarm(bool arm) override + { + SingleCall lock(this); - virtual bool armDisarm(bool arm) override - { - SingleCall lock(this); + checkValidVehicle(); + bool rc = false; + if (arm) { + float timeout_sec = 10; + waitForHomeLocation(timeout_sec); + waitForStableGroundPosition(timeout_sec); + } - checkValidVehicle(); - bool rc = false; - if (arm) { - float timeout_sec = 10; - waitForHomeLocation(timeout_sec); - waitForStableGroundPosition(timeout_sec); + mav_vehicle_->armDisarm(arm).wait(10000, &rc); + return rc; } - mav_vehicle_->armDisarm(arm).wait(10000, &rc); - return rc; - } - - void onArmed() - { - if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { - auto con = mav_vehicle_->getConnection(); - if (con != nullptr) { - if (log_ != nullptr) { - log_->close(); - log_ = nullptr; - } + void onArmed() + { + if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { + auto con = mav_vehicle_->getConnection(); + if (con != nullptr) { + if (log_ != nullptr) { + log_->close(); + log_ = nullptr; + } - try { - std::time_t t = std::time(0); // get time now - std::tm* now = std::localtime(&t); - auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday); - auto path = common_utils::FileSystem::ensureFolder(connection_info_.logs, folder); - auto filename = Utils::stringf("%02d-%02d-%02d.mavlink", now->tm_hour, now->tm_min, now->tm_sec); - auto fullpath = common_utils::FileSystem::combine(path, filename); - addStatusMessage(Utils::stringf("Opening log file: %s", fullpath.c_str())); - log_file_name_ = fullpath; - log_ = std::make_shared(); - log_->openForWriting(fullpath, false); - con->startLoggingSendMessage(log_); - con->startLoggingReceiveMessage(log_); - if (con != connection_) { - // log the SITL channel also - connection_->startLoggingSendMessage(log_); - connection_->startLoggingReceiveMessage(log_); + try { + std::time_t t = std::time(0); // get time now + std::tm* now = std::localtime(&t); + auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday); + auto path = common_utils::FileSystem::ensureFolder(connection_info_.logs, folder); + auto filename = Utils::stringf("%02d-%02d-%02d.mavlink", now->tm_hour, now->tm_min, now->tm_sec); + auto fullpath = common_utils::FileSystem::combine(path, filename); + addStatusMessage(Utils::stringf("Opening log file: %s", fullpath.c_str())); + log_file_name_ = fullpath; + log_ = std::make_shared(); + log_->openForWriting(fullpath, false); + con->startLoggingSendMessage(log_); + con->startLoggingReceiveMessage(log_); + if (con != connection_) { + // log the SITL channel also + connection_->startLoggingSendMessage(log_); + connection_->startLoggingReceiveMessage(log_); + } + start_telemtry_thread(); + } + catch (std::exception& ex) { + addStatusMessage(std::string("Opening log file failed: ") + ex.what()); } - start_telemtry_thread(); - } - catch (std::exception& ex) { - addStatusMessage(std::string("Opening log file failed: ") + ex.what()); } } } - } - void onDisarmed() - { - if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { - auto con = mav_vehicle_->getConnection(); - if (con != nullptr) { - con->stopLoggingSendMessage(); - con->stopLoggingReceiveMessage(); + void onDisarmed() + { + if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) { + auto con = mav_vehicle_->getConnection(); + if (con != nullptr) { + con->stopLoggingSendMessage(); + con->stopLoggingReceiveMessage(); + } + if (connection_ != nullptr) { + connection_->stopLoggingSendMessage(); + connection_->stopLoggingReceiveMessage(); + } } - if (connection_ != nullptr) { - connection_->stopLoggingSendMessage(); - connection_->stopLoggingReceiveMessage(); + if (log_ != nullptr) { + addStatusMessage(Utils::stringf("Closing log file: %s", log_file_name_.c_str())); + log_->close(); + log_ = nullptr; } } - if (log_ != nullptr) { - addStatusMessage(Utils::stringf("Closing log file: %s", log_file_name_.c_str())); - log_->close(); - log_ = nullptr; - } - } - void waitForHomeLocation(float timeout_sec) - { - if (!current_state_.home.is_set) { - addStatusMessage("Waiting for valid GPS home location..."); - if (!waitForFunction([&]() { - return current_state_.home.is_set; - }, timeout_sec).isComplete()) { - throw VehicleMoveException("Vehicle does not have a valid GPS home location"); + void waitForHomeLocation(float timeout_sec) + { + if (!current_state_.home.is_set) { + addStatusMessage("Waiting for valid GPS home location..."); + if (!waitForFunction([&]() { + return current_state_.home.is_set; + }, + timeout_sec) + .isComplete()) { + throw VehicleMoveException("Vehicle does not have a valid GPS home location"); + } } } - } - void waitForStableGroundPosition(float timeout_sec) - { - // wait for ground stabilization - if (ground_variance_ > GroundTolerance) { - addStatusMessage("Waiting for z-position to stabilize..."); - if (!waitForFunction([&]() { - return ground_variance_ <= GroundTolerance; - }, timeout_sec).isComplete()) { - auto msg = Utils::stringf("Ground is not stable, variance is %f", ground_variance_); - throw VehicleMoveException(msg); + void waitForStableGroundPosition(float timeout_sec) + { + // wait for ground stabilization + if (ground_variance_ > GroundTolerance) { + addStatusMessage("Waiting for z-position to stabilize..."); + if (!waitForFunction([&]() { + return ground_variance_ <= GroundTolerance; + }, + timeout_sec) + .isComplete()) { + auto msg = Utils::stringf("Ground is not stable, variance is %f", ground_variance_); + throw VehicleMoveException(msg); + } } } - } - - virtual bool takeoff(float timeout_sec) override - { - SingleCall lock(this); - checkValidVehicle(); - - waitForHomeLocation(timeout_sec); - waitForStableGroundPosition(timeout_sec); - - bool rc = false; - auto vec = getPosition(); - auto yaw = current_state_.attitude.yaw; - float z = vec.z() + getTakeoffZ(); - if (!mav_vehicle_->takeoff(z, 0.0f /* pitch */, yaw).wait(static_cast(timeout_sec * 1000), &rc)) { - throw VehicleMoveException("TakeOff command - timeout waiting for response"); - } - if (!rc) { - throw VehicleMoveException("TakeOff command rejected by drone"); - } - if (timeout_sec <= 0) - return true; // client doesn't want to wait. + virtual bool takeoff(float timeout_sec) override + { + SingleCall lock(this); - return waitForZ(timeout_sec, z, getDistanceAccuracy()); - } + checkValidVehicle(); - virtual bool land(float timeout_sec) override - { - SingleCall lock(this); + waitForHomeLocation(timeout_sec); + waitForStableGroundPosition(timeout_sec); - //TODO: bugbug: really need a downward pointing distance to ground sensor to do this properly, for now - //we assume the ground is relatively flat an we are landing roughly at the home altitude. - updateState(); - checkValidVehicle(); - if (current_state_.home.is_set) { bool rc = false; - if (!mav_vehicle_->land(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.home.global_pos.alt).wait(10000, &rc)) { - throw VehicleMoveException("Landing command - timeout waiting for response from drone"); + auto vec = getPosition(); + auto yaw = current_state_.attitude.yaw; + float z = vec.z() + getTakeoffZ(); + if (!mav_vehicle_->takeoff(z, 0.0f /* pitch */, yaw).wait(static_cast(timeout_sec * 1000), &rc)) { + throw VehicleMoveException("TakeOff command - timeout waiting for response"); } - else if (!rc) { - throw VehicleMoveException("Landing command rejected by drone"); + if (!rc) { + throw VehicleMoveException("TakeOff command rejected by drone"); } - } - else { - throw VehicleMoveException("Cannot land safely with out a home position that tells us the home altitude. Could fix this if we hook up a distance to ground sensor..."); + if (timeout_sec <= 0) + return true; // client doesn't want to wait. + + return waitForZ(timeout_sec, z, getDistanceAccuracy()); } - const auto& waiter = waitForFunction([&]() { - updateState(); - return current_state_.controls.landed; - }, timeout_sec); + virtual bool land(float timeout_sec) override + { + SingleCall lock(this); - // Wait for landed state (or user cancellation) - if (!waiter.isComplete()) { - throw VehicleMoveException("Drone hasn't reported a landing state"); - } - return waiter.isComplete(); - } + //TODO: bugbug: really need a downward pointing distance to ground sensor to do this properly, for now + //we assume the ground is relatively flat an we are landing roughly at the home altitude. + updateState(); + checkValidVehicle(); + if (current_state_.home.is_set) { + bool rc = false; + if (!mav_vehicle_->land(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.home.global_pos.alt).wait(10000, &rc)) { + throw VehicleMoveException("Landing command - timeout waiting for response from drone"); + } + else if (!rc) { + throw VehicleMoveException("Landing command rejected by drone"); + } + } + else { + throw VehicleMoveException("Cannot land safely with out a home position that tells us the home altitude. Could fix this if we hook up a distance to ground sensor..."); + } - virtual bool goHome(float timeout_sec) override - { - SingleCall lock(this); + const auto& waiter = waitForFunction([&]() { + updateState(); + return current_state_.controls.landed; + }, + timeout_sec); - checkValidVehicle(); - bool rc = false; - if (mav_vehicle_ != nullptr && !mav_vehicle_->returnToHome().wait( - static_cast(timeout_sec) * 1000, &rc)) { - throw VehicleMoveException("goHome - timeout waiting for response from drone"); + // Wait for landed state (or user cancellation) + if (!waiter.isComplete()) { + throw VehicleMoveException("Drone hasn't reported a landing state"); + } + return waiter.isComplete(); } - return rc; - } - virtual bool moveToPosition(float x, float y, float z, float velocity, float timeout_sec, DrivetrainType drivetrain, - const YawMode& yaw_mode, float lookahead, float adaptive_lookahead) override - { - SingleTaskCall lock(this); - - unused(adaptive_lookahead); - unused(lookahead); - unused(drivetrain); - - // save current manual, cruise, and max velocity parameters - bool result = false; - mavlinkcom::MavLinkParameter manual_velocity_parameter, cruise_velocity_parameter, max_velocity_parameter; - result = mav_vehicle_->getParameter("MPC_VEL_MANUAL").wait(1000, &manual_velocity_parameter); - result = result && mav_vehicle_->getParameter("MPC_XY_CRUISE").wait(1000, &cruise_velocity_parameter); - result = result && mav_vehicle_->getParameter("MPC_XY_VEL_MAX").wait(1000, &max_velocity_parameter); - - if (result) { - // set max velocity parameter - mavlinkcom::MavLinkParameter p; - p.name = "MPC_XY_VEL_MAX"; - p.value = velocity; - mav_vehicle_->setParameter(p).wait(1000, &result); + virtual bool goHome(float timeout_sec) override + { + SingleCall lock(this); - if (result) { - const Vector3r& goal_pos = Vector3r(x, y, z); - Vector3r goal_dist_vect; - float goal_dist; + checkValidVehicle(); + bool rc = false; + if (mav_vehicle_ != nullptr && !mav_vehicle_->returnToHome().wait( + static_cast(timeout_sec) * 1000, &rc)) { + throw VehicleMoveException("goHome - timeout waiting for response from drone"); + } + return rc; + } - Waiter waiter(getCommandPeriod(), timeout_sec, getCancelToken()); + virtual bool moveToPosition(float x, float y, float z, float velocity, float timeout_sec, DrivetrainType drivetrain, + const YawMode& yaw_mode, float lookahead, float adaptive_lookahead) override + { + SingleTaskCall lock(this); - while (!waiter.isComplete()) { - goal_dist_vect = getPosition() - goal_pos; - const Vector3r& goal_normalized = goal_dist_vect.normalized(); - goal_dist = goal_dist_vect.dot(goal_normalized); + unused(adaptive_lookahead); + unused(lookahead); + unused(drivetrain); - if (goal_dist > getDistanceAccuracy()) { - moveToPositionInternal(goal_pos, yaw_mode); + // save current manual, cruise, and max velocity parameters + bool result = false; + mavlinkcom::MavLinkParameter manual_velocity_parameter, cruise_velocity_parameter, max_velocity_parameter; + result = mav_vehicle_->getParameter("MPC_VEL_MANUAL").wait(1000, &manual_velocity_parameter); + result = result && mav_vehicle_->getParameter("MPC_XY_CRUISE").wait(1000, &cruise_velocity_parameter); + result = result && mav_vehicle_->getParameter("MPC_XY_VEL_MAX").wait(1000, &max_velocity_parameter); - //sleep for rest of the cycle - if (!waiter.sleep()) - return false; - } - else { - waiter.complete(); + if (result) { + // set max velocity parameter + mavlinkcom::MavLinkParameter p; + p.name = "MPC_XY_VEL_MAX"; + p.value = velocity; + mav_vehicle_->setParameter(p).wait(1000, &result); + + if (result) { + const Vector3r& goal_pos = Vector3r(x, y, z); + Vector3r goal_dist_vect; + float goal_dist; + + Waiter waiter(getCommandPeriod(), timeout_sec, getCancelToken()); + + while (!waiter.isComplete()) { + goal_dist_vect = getPosition() - goal_pos; + const Vector3r& goal_normalized = goal_dist_vect.normalized(); + goal_dist = goal_dist_vect.dot(goal_normalized); + + if (goal_dist > getDistanceAccuracy()) { + moveToPositionInternal(goal_pos, yaw_mode); + + //sleep for rest of the cycle + if (!waiter.sleep()) + return false; + } + else { + waiter.complete(); + } } - } - // reset manual, cruise, and max velocity parameters - bool result_temp = false; - mav_vehicle_->setParameter(manual_velocity_parameter).wait(1000, &result); - mav_vehicle_->setParameter(cruise_velocity_parameter).wait(1000, &result_temp); - result = result && result_temp; - mav_vehicle_->setParameter(max_velocity_parameter).wait(1000, &result_temp); - result = result && result_temp; + // reset manual, cruise, and max velocity parameters + bool result_temp = false; + mav_vehicle_->setParameter(manual_velocity_parameter).wait(1000, &result); + mav_vehicle_->setParameter(cruise_velocity_parameter).wait(1000, &result_temp); + result = result && result_temp; + mav_vehicle_->setParameter(max_velocity_parameter).wait(1000, &result_temp); + result = result && result_temp; - return result && waiter.isComplete(); + return result && waiter.isComplete(); + } } - } - return result; - } + return result; + } - virtual bool hover() override - { - SingleCall lock(this); + virtual bool hover() override + { + SingleCall lock(this); - bool rc = false; - checkValidVehicle(); - mavlinkcom::AsyncResult result = mav_vehicle_->loiter(); - //auto start_time = std::chrono::system_clock::now(); - while (!getCancelToken().isCancelled()) { - if (result.wait(100, &rc)) { - break; + bool rc = false; + checkValidVehicle(); + mavlinkcom::AsyncResult result = mav_vehicle_->loiter(); + //auto start_time = std::chrono::system_clock::now(); + while (!getCancelToken().isCancelled()) { + if (result.wait(100, &rc)) { + break; + } } + return rc; } - return rc; - } - virtual GeoPoint getHomeGeoPoint() const override - { - updateState(); - if (current_state_.home.is_set) - return GeoPoint(current_state_.home.global_pos.lat, current_state_.home.global_pos.lon, current_state_.home.global_pos.alt); - else - return GeoPoint(Utils::nan(), Utils::nan(), Utils::nan()); - } - - virtual GeoPoint getGpsLocation() const override - { - updateState(); - return GeoPoint(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.global_est.pos.alt); - } + virtual GeoPoint getHomeGeoPoint() const override + { + updateState(); + if (current_state_.home.is_set) + return GeoPoint(current_state_.home.global_pos.lat, current_state_.home.global_pos.lon, current_state_.home.global_pos.alt); + else + return GeoPoint(Utils::nan(), Utils::nan(), Utils::nan()); + } - virtual void sendTelemetry(float last_interval = -1) override - { - if (connection_ == nullptr || mav_vehicle_ == nullptr) { - return; + virtual GeoPoint getGpsLocation() const override + { + updateState(); + return GeoPoint(current_state_.global_est.pos.lat, current_state_.global_est.pos.lon, current_state_.global_est.pos.alt); } - // This method is called at high frequence from MultirotorPawnSimApi::updateRendering. - mavlinkcom::MavLinkTelemetry data; - connection_->getTelemetry(data); - if (data.messages_received == 0) { - if (!hil_message_timer_.started()) { - hil_message_timer_.start(); + virtual void sendTelemetry(float last_interval = -1) override + { + if (connection_ == nullptr || mav_vehicle_ == nullptr) { + return; + } + + // This method is called at high frequence from MultirotorPawnSimApi::updateRendering. + mavlinkcom::MavLinkTelemetry data; + connection_->getTelemetry(data); + if (data.messages_received == 0) { + if (!hil_message_timer_.started()) { + hil_message_timer_.start(); + } + else if (hil_message_timer_.seconds() > messageReceivedTimeout) { + addStatusMessage("not receiving any messages from HIL, please restart your HIL node and try again"); + } } - else if (hil_message_timer_.seconds() > messageReceivedTimeout) { - addStatusMessage("not receiving any messages from HIL, please restart your HIL node and try again"); + else { + hil_message_timer_.stop(); } } - else { - hil_message_timer_.stop(); - } - } - void writeTelemetry(float last_interval = -1) - { - auto proxy = logviewer_proxy_; - auto log = log_; + void writeTelemetry(float last_interval = -1) + { + auto proxy = logviewer_proxy_; + auto log = log_; - if ((logviewer_proxy_ == nullptr && log_ == nullptr)) { - return; - } + if ((logviewer_proxy_ == nullptr && log_ == nullptr)) { + return; + } - mavlinkcom::MavLinkTelemetry data; - connection_->getTelemetry(data); + mavlinkcom::MavLinkTelemetry data; + connection_->getTelemetry(data); - // listen to the other mavlink connection also - auto mavcon = mav_vehicle_->getConnection(); - if (mavcon != connection_) { - mavlinkcom::MavLinkTelemetry gcs; - mavcon->getTelemetry(gcs); + // listen to the other mavlink connection also + auto mavcon = mav_vehicle_->getConnection(); + if (mavcon != connection_) { + mavlinkcom::MavLinkTelemetry gcs; + mavcon->getTelemetry(gcs); - data.handler_microseconds += gcs.handler_microseconds; - data.messages_handled += gcs.messages_handled; - data.messages_received += gcs.messages_received; - data.messages_sent += gcs.messages_sent; + data.handler_microseconds += gcs.handler_microseconds; + data.messages_handled += gcs.messages_handled; + data.messages_received += gcs.messages_received; + data.messages_sent += gcs.messages_sent; - if (gcs.messages_received == 0) { - if (!gcs_message_timer_.started()) { - gcs_message_timer_.start(); + if (gcs.messages_received == 0) { + if (!gcs_message_timer_.started()) { + gcs_message_timer_.start(); + } + else if (gcs_message_timer_.seconds() > messageReceivedTimeout) { + addStatusMessage("not receiving any messages from GCS port, please restart your SITL node and try again"); + } + } + else { + gcs_message_timer_.stop(); } - else if (gcs_message_timer_.seconds() > messageReceivedTimeout) { - addStatusMessage("not receiving any messages from GCS port, please restart your SITL node and try again"); + } + + data.render_time = static_cast(last_interval * 1000000); // microseconds + + { + std::lock_guard guard(telemetry_mutex_); + uint32_t average_delay = 0; + uint32_t average_update = 0; + if (hil_sensor_count_ != 0) { + average_delay = actuator_delay_ / hil_sensor_count_; + average_update = static_cast(update_time_ / hil_sensor_count_); } + + data.update_rate = update_count_; + data.sensor_rate = hil_sensor_count_; + data.actuation_delay = average_delay; + data.lock_step_resets = lock_step_resets_; + data.update_time = average_update; + // reset the counters we just captured. + update_count_ = 0; + hil_sensor_count_ = 0; + actuator_delay_ = 0; + update_time_ = 0; } - else { - gcs_message_timer_.stop(); + + if (proxy != nullptr) { + proxy->sendMessage(data); } - } - data.render_time = static_cast(last_interval * 1000000);// microseconds + if (log != nullptr) { + mavlinkcom::MavLinkMessage msg; + msg.magic = MAVLINK_STX_MAVLINK1; + data.encode(msg); + msg.update_checksum(); + // disk I/O is unpredictable, so we have to get it out of the update loop + // which is why this thread exists. + log->write(msg); + } + } + void start_telemtry_thread() { - std::lock_guard guard(telemetry_mutex_); - uint32_t average_delay = 0; - uint32_t average_update = 0; - if (hil_sensor_count_ != 0) { - average_delay = actuator_delay_ / hil_sensor_count_; - average_update = static_cast(update_time_ / hil_sensor_count_); + if (this->telemetry_thread_.joinable()) { + this->telemetry_thread_.join(); } - data.update_rate = update_count_; - data.sensor_rate = hil_sensor_count_; - data.actuation_delay = average_delay; - data.lock_step_resets = lock_step_resets_; - data.update_time = average_update; - // reset the counters we just captured. + // reset the counters we use for telemetry. update_count_ = 0; hil_sensor_count_ = 0; actuator_delay_ = 0; - update_time_ = 0; - } - if (proxy != nullptr) { - proxy->sendMessage(data); + this->telemetry_thread_ = std::thread(&MavLinkMultirotorApi::telemtry_thread, this); } - if (log != nullptr) { - mavlinkcom::MavLinkMessage msg; - msg.magic = MAVLINK_STX_MAVLINK1; - data.encode(msg); - msg.update_checksum(); - // disk I/O is unpredictable, so we have to get it out of the update loop - // which is why this thread exists. - log->write(msg); + void telemtry_thread() + { + while (log_ != nullptr) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + writeTelemetry(1); + } } - } - void start_telemtry_thread() - { - if (this->telemetry_thread_.joinable()) { - this->telemetry_thread_.join(); + virtual float getCommandPeriod() const override + { + return 1.0f / 50; //1 period of 50hz } - // reset the counters we use for telemetry. - update_count_ = 0; - hil_sensor_count_ = 0; - actuator_delay_ = 0; - - this->telemetry_thread_ = std::thread(&MavLinkMultirotorApi::telemtry_thread, this); - } - - void telemtry_thread() - { - while (log_ != nullptr) { - std::this_thread::sleep_for(std::chrono::seconds(1)); - writeTelemetry(1); + virtual float getTakeoffZ() const override + { + // pick a number, PX4 doesn't have a fixed limit here, but 3 meters is probably safe + // enough to get out of the backwash turbulence. Negative due to NED coordinate system. + return -3.0f; } - } - - virtual float getCommandPeriod() const override - { - return 1.0f / 50; //1 period of 50hz - } - virtual float getTakeoffZ() const override - { - // pick a number, PX4 doesn't have a fixed limit here, but 3 meters is probably safe - // enough to get out of the backwash turbulence. Negative due to NED coordinate system. - return -3.0f; - } + virtual float getDistanceAccuracy() const override + { + return 0.5f; //measured in simulator by firing commands "MoveToLocation -x 0 -y 0" multiple times and looking at distance traveled + } - virtual float getDistanceAccuracy() const override - { - return 0.5f; //measured in simulator by firing commands "MoveToLocation -x 0 -y 0" multiple times and looking at distance traveled - } + protected: //methods + virtual void setControllerGains(uint8_t controllerType, const vector& kp, const vector& ki, const vector& kd) override + { + unused(controllerType); + unused(kp); + unused(ki); + unused(kd); + Utils::log("Not Implemented: setControllerGains", Utils::kLogLevelInfo); + } -protected: //methods - virtual void setControllerGains(uint8_t controllerType, const vector& kp, const vector& ki, const vector& kd) override - { - unused(controllerType); - unused(kp); - unused(ki); - unused(kd); - Utils::log("Not Implemented: setControllerGains", Utils::kLogLevelInfo); - } - - virtual void commandMotorPWMs(float front_right_pwm, float front_left_pwm, float rear_right_pwm, float rear_left_pwm) override - { - unused(front_right_pwm); - unused(front_left_pwm); - unused(rear_right_pwm); - unused(rear_left_pwm); - Utils::log("Not Implemented: commandMotorPWMs", Utils::kLogLevelInfo); - } - - virtual void commandRollPitchYawZ(float roll, float pitch, float yaw, float z) override - { - if (target_height_ != -z) { - // these PID values were calculated experimentally using AltHoldCommand n MavLinkTest, this provides the best - // control over thrust to achieve minimal over/under shoot in a reasonable amount of time, but it has not - // been tested on a real drone outside jMavSim, so it may need recalibrating... - thrust_controller_.setPoint(-z, .05f, .005f, 0.09f); - target_height_ = -z; - } - checkValidVehicle(); - auto state = mav_vehicle_->getVehicleState(); - float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); - mav_vehicle_->moveByAttitude(roll, pitch, yaw, 0, 0, 0, thrust); - } - virtual void commandRollPitchYawrateZ(float roll, float pitch, float yaw_rate, float z) override - { - if (target_height_ != -z) { - thrust_controller_.setPoint(-z, .05f, .005f, 0.09f); - target_height_ = -z; - } - checkValidVehicle(); - auto state = mav_vehicle_->getVehicleState(); - float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); - mav_vehicle_->moveByAttitude(roll, pitch, 0, 0, 0, yaw_rate, thrust); - } - - virtual void commandRollPitchYawThrottle(float roll, float pitch, float yaw, float throttle) override - { - checkValidVehicle(); - mav_vehicle_->moveByAttitude(roll, pitch, yaw, 0, 0, 0, throttle); - } + virtual void commandMotorPWMs(float front_right_pwm, float front_left_pwm, float rear_right_pwm, float rear_left_pwm) override + { + unused(front_right_pwm); + unused(front_left_pwm); + unused(rear_right_pwm); + unused(rear_left_pwm); + Utils::log("Not Implemented: commandMotorPWMs", Utils::kLogLevelInfo); + } - virtual void commandRollPitchYawrateThrottle(float roll, float pitch, float yaw_rate, float throttle) override - { - checkValidVehicle(); - mav_vehicle_->moveByAttitude(roll, pitch, 0, 0, 0, yaw_rate, throttle); - } - - virtual void commandAngleRatesZ(float roll_rate, float pitch_rate, float yaw_rate, float z) override - { - if (target_height_ != -z) { - thrust_controller_.setPoint(-z, .05f, .005f, 0.09f); - target_height_ = -z; + virtual void commandRollPitchYawZ(float roll, float pitch, float yaw, float z) override + { + if (target_height_ != -z) { + // these PID values were calculated experimentally using AltHoldCommand n MavLinkTest, this provides the best + // control over thrust to achieve minimal over/under shoot in a reasonable amount of time, but it has not + // been tested on a real drone outside jMavSim, so it may need recalibrating... + thrust_controller_.setPoint(-z, .05f, .005f, 0.09f); + target_height_ = -z; + } + checkValidVehicle(); + auto state = mav_vehicle_->getVehicleState(); + float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); + mav_vehicle_->moveByAttitude(roll, pitch, yaw, 0, 0, 0, thrust); + } + virtual void commandRollPitchYawrateZ(float roll, float pitch, float yaw_rate, float z) override + { + if (target_height_ != -z) { + thrust_controller_.setPoint(-z, .05f, .005f, 0.09f); + target_height_ = -z; + } + checkValidVehicle(); + auto state = mav_vehicle_->getVehicleState(); + float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); + mav_vehicle_->moveByAttitude(roll, pitch, 0, 0, 0, yaw_rate, thrust); } - checkValidVehicle(); - auto state = mav_vehicle_->getVehicleState(); - float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); - mav_vehicle_->moveByAttitude(0, 0, 0, roll_rate, pitch_rate, yaw_rate, thrust); - } - virtual void commandAngleRatesThrottle(float roll_rate, float pitch_rate, float yaw_rate, float throttle) override - { - checkValidVehicle(); - mav_vehicle_->moveByAttitude(0, 0, 0, roll_rate, pitch_rate, yaw_rate, throttle); - } + virtual void commandRollPitchYawThrottle(float roll, float pitch, float yaw, float throttle) override + { + checkValidVehicle(); + mav_vehicle_->moveByAttitude(roll, pitch, yaw, 0, 0, 0, throttle); + } - virtual void commandVelocity(float vx, float vy, float vz, const YawMode& yaw_mode) override - { - checkValidVehicle(); - float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; - mav_vehicle_->moveByLocalVelocity(vx, vy, vz, !yaw_mode.is_rate, yaw); - } + virtual void commandRollPitchYawrateThrottle(float roll, float pitch, float yaw_rate, float throttle) override + { + checkValidVehicle(); + mav_vehicle_->moveByAttitude(roll, pitch, 0, 0, 0, yaw_rate, throttle); + } - virtual void commandVelocityZ(float vx, float vy, float z, const YawMode& yaw_mode) override - { - checkValidVehicle(); - float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; - mav_vehicle_->moveByLocalVelocityWithAltHold(vx, vy, z, !yaw_mode.is_rate, yaw); - } + virtual void commandAngleRatesZ(float roll_rate, float pitch_rate, float yaw_rate, float z) override + { + if (target_height_ != -z) { + thrust_controller_.setPoint(-z, .05f, .005f, 0.09f); + target_height_ = -z; + } + checkValidVehicle(); + auto state = mav_vehicle_->getVehicleState(); + float thrust = 0.21f + thrust_controller_.control(-state.local_est.pos.z); + mav_vehicle_->moveByAttitude(0, 0, 0, roll_rate, pitch_rate, yaw_rate, thrust); + } - virtual void commandPosition(float x, float y, float z, const YawMode& yaw_mode) override - { - checkValidVehicle(); - float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; - mav_vehicle_->moveToLocalPosition(x, y, z, !yaw_mode.is_rate, yaw); - } + virtual void commandAngleRatesThrottle(float roll_rate, float pitch_rate, float yaw_rate, float throttle) override + { + checkValidVehicle(); + mav_vehicle_->moveByAttitude(0, 0, 0, roll_rate, pitch_rate, yaw_rate, throttle); + } - //TODO: decouple MultirotorApiBase, VehicalParams and SafetyEval - virtual const MultirotorApiParams& getMultirotorApiParams() const override - { - //defaults are good for PX4 generic quadcopter. - static const MultirotorApiParams vehicle_params_; - return vehicle_params_; - } + virtual void commandVelocity(float vx, float vy, float vz, const YawMode& yaw_mode) override + { + checkValidVehicle(); + float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; + mav_vehicle_->moveByLocalVelocity(vx, vy, vz, !yaw_mode.is_rate, yaw); + } - virtual void beforeTask() override - { - startOffboardMode(); - } + virtual void commandVelocityZ(float vx, float vy, float z, const YawMode& yaw_mode) override + { + checkValidVehicle(); + float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; + mav_vehicle_->moveByLocalVelocityWithAltHold(vx, vy, z, !yaw_mode.is_rate, yaw); + } - virtual void afterTask() override - { - endOffboardMode(); - } + virtual void commandPosition(float x, float y, float z, const YawMode& yaw_mode) override + { + checkValidVehicle(); + float yaw = yaw_mode.yaw_or_rate * M_PIf / 180; + mav_vehicle_->moveToLocalPosition(x, y, z, !yaw_mode.is_rate, yaw); + } -public: + //TODO: decouple MultirotorApiBase, VehicalParams and SafetyEval + virtual const MultirotorApiParams& getMultirotorApiParams() const override + { + //defaults are good for PX4 generic quadcopter. + static const MultirotorApiParams vehicle_params_; + return vehicle_params_; + } - class MavLinkLogViewerLog : public mavlinkcom::MavLinkLog - { - public: - MavLinkLogViewerLog(std::shared_ptr proxy) + virtual void beforeTask() override { - proxy_ = proxy; + startOffboardMode(); } - ~MavLinkLogViewerLog() + virtual void afterTask() override { - proxy_ = nullptr; + endOffboardMode(); } - void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override + public: + class MavLinkLogViewerLog : public mavlinkcom::MavLinkLog { - if (proxy_ != nullptr) { - unused(timestamp); - mavlinkcom::MavLinkMessage copy; - ::memcpy(©, &msg, sizeof(mavlinkcom::MavLinkMessage)); - try { - proxy_->sendMessage(copy); - } - catch (std::exception&) { - failures++; - if (failures == 100) { - // hmmm, doesn't like the proxy, bad socket perhaps, so stop trying... - proxy_ = nullptr; + public: + MavLinkLogViewerLog(std::shared_ptr proxy) + { + proxy_ = proxy; + } + + ~MavLinkLogViewerLog() + { + proxy_ = nullptr; + } + + void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override + { + if (proxy_ != nullptr) { + unused(timestamp); + mavlinkcom::MavLinkMessage copy; + ::memcpy(©, &msg, sizeof(mavlinkcom::MavLinkMessage)); + try { + proxy_->sendMessage(copy); + } + catch (std::exception&) { + failures++; + if (failures == 100) { + // hmmm, doesn't like the proxy, bad socket perhaps, so stop trying... + proxy_ = nullptr; + } } } } - } - private: - std::shared_ptr proxy_; - int failures = 0; - }; + private: + std::shared_ptr proxy_; + int failures = 0; + }; - -protected: //methods - virtual void connect() - { - if (!connecting_) { - connecting_ = true; - if (this->connect_thread_.joinable()) { - this->connect_thread_.join(); + protected: //methods + virtual void connect() + { + if (!connecting_) { + connecting_ = true; + if (this->connect_thread_.joinable()) { + this->connect_thread_.join(); + } + this->connect_thread_ = std::thread(&MavLinkMultirotorApi::connect_thread, this); } - this->connect_thread_ = std::thread(&MavLinkMultirotorApi::connect_thread, this); } - } - virtual void disconnect() - { - addStatusMessage("Disconnecting mavlink vehicle"); - connected_ = false; - connecting_ = false; + virtual void disconnect() + { + addStatusMessage("Disconnecting mavlink vehicle"); + connected_ = false; + connecting_ = false; - if (is_armed_) { - // close the telemetry log. - is_armed_ = false; - onDisarmed(); - } + if (is_armed_) { + // close the telemetry log. + is_armed_ = false; + onDisarmed(); + } - if (connection_ != nullptr) { - if (is_hil_mode_set_ && mav_vehicle_ != nullptr) { - setNormalMode(); + if (connection_ != nullptr) { + if (is_hil_mode_set_ && mav_vehicle_ != nullptr) { + setNormalMode(); + } + + connection_->stopLoggingSendMessage(); + connection_->stopLoggingReceiveMessage(); + connection_->close(); } - connection_->stopLoggingSendMessage(); - connection_->stopLoggingReceiveMessage(); - connection_->close(); - } + if (hil_node_ != nullptr) { + hil_node_->close(); + } - if (hil_node_ != nullptr) { - hil_node_->close(); - } + if (mav_vehicle_ != nullptr) { + auto c = mav_vehicle_->getConnection(); + if (c != nullptr) { + c->stopLoggingSendMessage(); + c->stopLoggingReceiveMessage(); + } + mav_vehicle_->close(); + mav_vehicle_ = nullptr; + } + + if (video_server_ != nullptr) + video_server_->close(); - if (mav_vehicle_ != nullptr) { - auto c = mav_vehicle_->getConnection(); - if (c != nullptr) { - c->stopLoggingSendMessage(); - c->stopLoggingReceiveMessage(); + if (logviewer_proxy_ != nullptr) { + logviewer_proxy_->close(); + logviewer_proxy_ = nullptr; + } + + if (logviewer_out_proxy_ != nullptr) { + logviewer_out_proxy_->close(); + logviewer_out_proxy_ = nullptr; } - mav_vehicle_->close(); - mav_vehicle_ = nullptr; - } - if (video_server_ != nullptr) - video_server_->close(); + if (qgc_proxy_ != nullptr) { + qgc_proxy_->close(); + qgc_proxy_ = nullptr; + } - if (logviewer_proxy_ != nullptr) { - logviewer_proxy_->close(); - logviewer_proxy_ = nullptr; + resetState(); } - if (logviewer_out_proxy_ != nullptr) { - logviewer_out_proxy_->close(); - logviewer_out_proxy_ = nullptr; + void connect_thread() + { + addStatusMessage("Waiting for mavlink vehicle..."); + connecting_ = true; + createMavConnection(connection_info_); + if (mav_vehicle_ != nullptr) { + connectToLogViewer(); + connectToQGC(); + } + + if (connecting_) { + // only set connected if we haven't already been told to disconnect. + connecting_ = false; + connected_ = true; + } } - if (qgc_proxy_ != nullptr) { - qgc_proxy_->close(); - qgc_proxy_ = nullptr; - } - - resetState(); - } + virtual void close() + { + disconnect(); + } - void connect_thread() - { - addStatusMessage("Waiting for mavlink vehicle..."); - connecting_ = true; - createMavConnection(connection_info_); - if (mav_vehicle_ != nullptr) { - connectToLogViewer(); - connectToQGC(); + void closeAllConnection() + { + close(); } - if (connecting_) { - // only set connected if we haven't already been told to disconnect. - connecting_ = false; - connected_ = true; + private: //methods + void openAllConnections() + { + Utils::log("Opening mavlink connection"); + close(); //just in case if connections were open + resetState(); //reset all variables we might have changed during last session + connect(); } - } - virtual void close() - { - disconnect(); - } + void getMocapPose(Vector3r& position, Quaternionr& orientation) const + { + position.x() = MocapPoseMessage.x; + position.y() = MocapPoseMessage.y; + position.z() = MocapPoseMessage.z; + orientation.w() = MocapPoseMessage.q[0]; + orientation.x() = MocapPoseMessage.q[1]; + orientation.y() = MocapPoseMessage.q[2]; + orientation.z() = MocapPoseMessage.q[3]; + } - void closeAllConnection() - { - close(); - } + //TODO: this method used to send collision to external sim. Do we still need this? + void sendCollision(float normalX, float normalY, float normalZ) + { + checkValidVehicle(); + + mavlinkcom::MavLinkCollision collision{}; + collision.src = 1; //provider of data is MavLink system in id field + collision.id = mav_vehicle_->getLocalSystemId(); + collision.action = static_cast(mavlinkcom::MAV_COLLISION_ACTION::MAV_COLLISION_ACTION_REPORT); + collision.threat_level = static_cast(mavlinkcom::MAV_COLLISION_THREAT_LEVEL::MAV_COLLISION_THREAT_LEVEL_NONE); + // we are abusing these fields, passing the angle of the object we hit, so that jMAVSim knows how to bounce off. + collision.time_to_minimum_delta = normalX; + collision.altitude_minimum_delta = normalY; + collision.horizontal_minimum_delta = normalZ; + mav_vehicle_->sendMessage(collision); + } + + //TODO: do we still need this method? + bool hasVideoRequest() + { + mavlinkcom::MavLinkVideoServer::MavLinkVideoRequest image_req; + return video_server_->hasVideoRequest(image_req); + } + //TODO: do we still need this method? + void sendImage(unsigned char data[], uint32_t length, uint16_t width, uint16_t height) + { + const int MAVLINK_DATA_STREAM_IMG_PNG = 6; + video_server_->sendFrame(data, length, width, height, MAVLINK_DATA_STREAM_IMG_PNG, 0); + } -private: //methods + //put PX4 in normal mode (i.e. non-simulation mode) + void setNormalMode() + { + if (is_hil_mode_set_ && connection_ != nullptr && mav_vehicle_ != nullptr) { - void openAllConnections() - { - Utils::log("Opening mavlink connection"); - close(); //just in case if connections were open - resetState(); //reset all variables we might have changed during last session - connect(); - } + // remove MAV_MODE_FLAG_HIL_ENABLED flag from current mode + std::lock_guard guard(set_mode_mutex_); + int mode = mav_vehicle_->getVehicleState().mode; + mode &= ~static_cast(mavlinkcom::MAV_MODE_FLAG::MAV_MODE_FLAG_HIL_ENABLED); - void getMocapPose(Vector3r& position, Quaternionr& orientation) const - { - position.x() = MocapPoseMessage.x; position.y() = MocapPoseMessage.y; position.z() = MocapPoseMessage.z; - orientation.w() = MocapPoseMessage.q[0]; orientation.x() = MocapPoseMessage.q[1]; - orientation.y() = MocapPoseMessage.q[2]; orientation.z() = MocapPoseMessage.q[3]; - } + mavlinkcom::MavCmdDoSetMode cmd; + cmd.command = static_cast(mavlinkcom::MAV_CMD::MAV_CMD_DO_SET_MODE); + cmd.Mode = static_cast(mode); + mav_vehicle_->sendCommand(cmd); - //TODO: this method used to send collision to external sim. Do we still need this? - void sendCollision(float normalX, float normalY, float normalZ) - { - checkValidVehicle(); - - mavlinkcom::MavLinkCollision collision{}; - collision.src = 1; //provider of data is MavLink system in id field - collision.id = mav_vehicle_->getLocalSystemId(); - collision.action = static_cast(mavlinkcom::MAV_COLLISION_ACTION::MAV_COLLISION_ACTION_REPORT); - collision.threat_level = static_cast(mavlinkcom::MAV_COLLISION_THREAT_LEVEL::MAV_COLLISION_THREAT_LEVEL_NONE); - // we are abusing these fields, passing the angle of the object we hit, so that jMAVSim knows how to bounce off. - collision.time_to_minimum_delta = normalX; - collision.altitude_minimum_delta = normalY; - collision.horizontal_minimum_delta = normalZ; - mav_vehicle_->sendMessage(collision); - } - - //TODO: do we still need this method? - bool hasVideoRequest() - { - mavlinkcom::MavLinkVideoServer::MavLinkVideoRequest image_req; - return video_server_->hasVideoRequest(image_req); - } + is_hil_mode_set_ = false; + } + } - //TODO: do we still need this method? - void sendImage(unsigned char data[], uint32_t length, uint16_t width, uint16_t height) - { - const int MAVLINK_DATA_STREAM_IMG_PNG = 6; - video_server_->sendFrame(data, length, width, height, MAVLINK_DATA_STREAM_IMG_PNG, 0); - } + //put PX4 in simulation mode + void setHILMode() + { + if (!is_simulation_mode_) + throw std::logic_error("Attempt to set device in HIL mode while not in simulation mode"); - //put PX4 in normal mode (i.e. non-simulation mode) - void setNormalMode() - { - if (is_hil_mode_set_ && connection_ != nullptr && mav_vehicle_ != nullptr) { + checkValidVehicle(); - // remove MAV_MODE_FLAG_HIL_ENABLED flag from current mode + // add MAV_MODE_FLAG_HIL_ENABLED flag to current mode std::lock_guard guard(set_mode_mutex_); int mode = mav_vehicle_->getVehicleState().mode; - mode &= ~static_cast(mavlinkcom::MAV_MODE_FLAG::MAV_MODE_FLAG_HIL_ENABLED); + mode |= static_cast(mavlinkcom::MAV_MODE_FLAG::MAV_MODE_FLAG_HIL_ENABLED); mavlinkcom::MavCmdDoSetMode cmd; cmd.command = static_cast(mavlinkcom::MAV_CMD::MAV_CMD_DO_SET_MODE); cmd.Mode = static_cast(mode); mav_vehicle_->sendCommand(cmd); - is_hil_mode_set_ = false; + is_hil_mode_set_ = true; } - } - - //put PX4 in simulation mode - void setHILMode() - { - if (!is_simulation_mode_) - throw std::logic_error("Attempt to set device in HIL mode while not in simulation mode"); - - checkValidVehicle(); - - // add MAV_MODE_FLAG_HIL_ENABLED flag to current mode - std::lock_guard guard(set_mode_mutex_); - int mode = mav_vehicle_->getVehicleState().mode; - mode |= static_cast(mavlinkcom::MAV_MODE_FLAG::MAV_MODE_FLAG_HIL_ENABLED); - - mavlinkcom::MavCmdDoSetMode cmd; - cmd.command = static_cast(mavlinkcom::MAV_CMD::MAV_CMD_DO_SET_MODE); - cmd.Mode = static_cast(mode); - mav_vehicle_->sendCommand(cmd); - - is_hil_mode_set_ = true; - } - - bool startOffboardMode() - { - checkValidVehicle(); - try { - mav_vehicle_->requestControl(); + bool startOffboardMode() + { + checkValidVehicle(); + try { + mav_vehicle_->requestControl(); + } + catch (std::exception& ex) { + ensureSafeMode(); + addStatusMessage(std::string("Request control failed: ") + ex.what()); + return false; + } + return true; } - catch (std::exception& ex) { + + void endOffboardMode() + { + // bugbug: I removed this releaseControl because it makes back-to-back move operations less smooth. + // The side effect of this is that with some drones (e.g. PX4 based) the drone itself will timeout + // when you stop sending move commands and the behavior on timeout is then determined by the drone itself. + // mav_vehicle_->releaseControl(); ensureSafeMode(); - addStatusMessage(std::string("Request control failed: ") + ex.what()); - return false; } - return true; - } - void endOffboardMode() - { - // bugbug: I removed this releaseControl because it makes back-to-back move operations less smooth. - // The side effect of this is that with some drones (e.g. PX4 based) the drone itself will timeout - // when you stop sending move commands and the behavior on timeout is then determined by the drone itself. - // mav_vehicle_->releaseControl(); - ensureSafeMode(); - } - - void ensureSafeMode() - { - if (mav_vehicle_ != nullptr) { - const mavlinkcom::VehicleState& state = mav_vehicle_->getVehicleState(); - if (state.controls.landed || !state.controls.armed) { - return; + void ensureSafeMode() + { + if (mav_vehicle_ != nullptr) { + const mavlinkcom::VehicleState& state = mav_vehicle_->getVehicleState(); + if (state.controls.landed || !state.controls.armed) { + return; + } } } - } - void checkValidVehicle() - { - if (mav_vehicle_ == nullptr || connection_ == nullptr || !connection_->isOpen() || !connected_) { - throw std::logic_error("Cannot perform operation when no vehicle is connected or vehicle is not responding"); + void checkValidVehicle() + { + if (mav_vehicle_ == nullptr || connection_ == nullptr || !connection_->isOpen() || !connected_) { + throw std::logic_error("Cannot perform operation when no vehicle is connected or vehicle is not responding"); + } } - } - //status update methods should call this first! - void updateState() const - { - StatusLock lock(this); - if (mav_vehicle_ != nullptr) { - int version = mav_vehicle_->getVehicleStateVersion(); - if (version != state_version_) { - current_state_ = mav_vehicle_->getVehicleState(); - state_version_ = version; + //status update methods should call this first! + void updateState() const + { + StatusLock lock(this); + if (mav_vehicle_ != nullptr) { + int version = mav_vehicle_->getVehicleStateVersion(); + if (version != state_version_) { + current_state_ = mav_vehicle_->getVehicleState(); + state_version_ = version; + } } } - } - virtual void normalizeRotorControls() - { - //if rotor controls are in not in 0-1 range then they are in -1 to 1 range in which case - //we normalize them to 0 to 1 for PX4 - if (!is_controls_0_1_) { - // change -1 to 1 to 0 to 1. - for (size_t i = 0; i < Utils::length(rotor_controls_); ++i) { - rotor_controls_[i] = (rotor_controls_[i] + 1.0f) / 2.0f; + virtual void normalizeRotorControls() + { + //if rotor controls are in not in 0-1 range then they are in -1 to 1 range in which case + //we normalize them to 0 to 1 for PX4 + if (!is_controls_0_1_) { + // change -1 to 1 to 0 to 1. + for (size_t i = 0; i < Utils::length(rotor_controls_); ++i) { + rotor_controls_[i] = (rotor_controls_[i] + 1.0f) / 2.0f; + } } - } - else { - //this applies to PX4 and may work differently on other firmwares. - //We use 0.2 as idle rotors which leaves out range of 0.8 - for (size_t i = 0; i < Utils::length(rotor_controls_); ++i) { - rotor_controls_[i] = Utils::clip(0.8f * rotor_controls_[i] + 0.20f, 0.0f, 1.0f); + else { + //this applies to PX4 and may work differently on other firmwares. + //We use 0.2 as idle rotors which leaves out range of 0.8 + for (size_t i = 0; i < Utils::length(rotor_controls_); ++i) { + rotor_controls_[i] = Utils::clip(0.8f * rotor_controls_[i] + 0.20f, 0.0f, 1.0f); + } } } - } - bool sendTestMessage(std::shared_ptr node) - { - try { - // try and send a test message. - mavlinkcom::MavLinkHeartbeat test; - test.autopilot = static_cast(mavlinkcom::MAV_AUTOPILOT::MAV_AUTOPILOT_PX4); - test.type = static_cast(mavlinkcom::MAV_TYPE::MAV_TYPE_GCS); - test.base_mode = 0; - test.custom_mode = 0; - test.mavlink_version = 3; - node->sendMessage(test); - test.system_status = 0; - return true; - } - catch (std::exception&) { - return false; + bool sendTestMessage(std::shared_ptr node) + { + try { + // try and send a test message. + mavlinkcom::MavLinkHeartbeat test; + test.autopilot = static_cast(mavlinkcom::MAV_AUTOPILOT::MAV_AUTOPILOT_PX4); + test.type = static_cast(mavlinkcom::MAV_TYPE::MAV_TYPE_GCS); + test.base_mode = 0; + test.custom_mode = 0; + test.mavlink_version = 3; + node->sendMessage(test); + test.system_status = 0; + return true; + } + catch (std::exception&) { + return false; + } } - } - bool connectToLogViewer() - { - //set up logviewer proxy - if (connection_info_.logviewer_ip_address.size() > 0) { - std::shared_ptr connection; - createProxy("LogViewer", connection_info_.logviewer_ip_address, connection_info_.logviewer_ip_port, connection_info_.local_host_ip, - logviewer_proxy_, connection); - if (!sendTestMessage(logviewer_proxy_)) { - // error talking to log viewer, so don't keep trying, and close the connection also. - logviewer_proxy_->getConnection()->close(); - logviewer_proxy_ = nullptr; - } + bool connectToLogViewer() + { + //set up logviewer proxy + if (connection_info_.logviewer_ip_address.size() > 0) { + std::shared_ptr connection; + createProxy("LogViewer", connection_info_.logviewer_ip_address, connection_info_.logviewer_ip_port, connection_info_.local_host_ip, logviewer_proxy_, connection); + if (!sendTestMessage(logviewer_proxy_)) { + // error talking to log viewer, so don't keep trying, and close the connection also. + logviewer_proxy_->getConnection()->close(); + logviewer_proxy_ = nullptr; + } - std::shared_ptr out_connection; - createProxy("LogViewerOut", connection_info_.logviewer_ip_address, connection_info_.logviewer_ip_sport, connection_info_.local_host_ip, - logviewer_out_proxy_, out_connection); - if (!sendTestMessage(logviewer_out_proxy_)) { - // error talking to log viewer, so don't keep trying, and close the connection also. - logviewer_out_proxy_->getConnection()->close(); - logviewer_out_proxy_ = nullptr; - } - else if (mav_vehicle_ != nullptr) { - auto proxylog = std::make_shared(logviewer_out_proxy_); - mav_vehicle_->getConnection()->startLoggingSendMessage(proxylog); - mav_vehicle_->getConnection()->startLoggingReceiveMessage(proxylog); - if (connection_ != nullptr) { - connection_->startLoggingSendMessage(proxylog); - connection_->startLoggingReceiveMessage(proxylog); + std::shared_ptr out_connection; + createProxy("LogViewerOut", connection_info_.logviewer_ip_address, connection_info_.logviewer_ip_sport, connection_info_.local_host_ip, logviewer_out_proxy_, out_connection); + if (!sendTestMessage(logviewer_out_proxy_)) { + // error talking to log viewer, so don't keep trying, and close the connection also. + logviewer_out_proxy_->getConnection()->close(); + logviewer_out_proxy_ = nullptr; + } + else if (mav_vehicle_ != nullptr) { + auto proxylog = std::make_shared(logviewer_out_proxy_); + mav_vehicle_->getConnection()->startLoggingSendMessage(proxylog); + mav_vehicle_->getConnection()->startLoggingReceiveMessage(proxylog); + if (connection_ != nullptr) { + connection_->startLoggingSendMessage(proxylog); + connection_->startLoggingReceiveMessage(proxylog); + } } } + return logviewer_proxy_ != nullptr; } - return logviewer_proxy_ != nullptr; - } - bool connectToQGC() - { - if (connection_info_.qgc_ip_address.size() > 0) { - std::shared_ptr connection; - createProxy("QGC", connection_info_.qgc_ip_address, connection_info_.qgc_ip_port, connection_info_.local_host_ip, qgc_proxy_, connection); - if (!sendTestMessage(qgc_proxy_)) { - // error talking to QGC, so don't keep trying, and close the connection also. - qgc_proxy_->getConnection()->close(); - qgc_proxy_ = nullptr; - } - else { - connection->subscribe([=](std::shared_ptr connection_val, const mavlinkcom::MavLinkMessage& msg) { - unused(connection_val); - processQgcMessages(msg); + bool connectToQGC() + { + if (connection_info_.qgc_ip_address.size() > 0) { + std::shared_ptr connection; + createProxy("QGC", connection_info_.qgc_ip_address, connection_info_.qgc_ip_port, connection_info_.local_host_ip, qgc_proxy_, connection); + if (!sendTestMessage(qgc_proxy_)) { + // error talking to QGC, so don't keep trying, and close the connection also. + qgc_proxy_->getConnection()->close(); + qgc_proxy_ = nullptr; + } + else { + connection->subscribe([=](std::shared_ptr connection_val, const mavlinkcom::MavLinkMessage& msg) { + unused(connection_val); + processQgcMessages(msg); }); + } } + return qgc_proxy_ != nullptr; } - return qgc_proxy_ != nullptr; - } - - void createProxy(std::string name, std::string ip, int port, string local_host_ip, - std::shared_ptr& node, std::shared_ptr& connection) - { - if (connection_ == nullptr) - throw std::domain_error("MavLinkMultirotorApi requires connection object to be set before createProxy call"); + void createProxy(std::string name, std::string ip, int port, string local_host_ip, + std::shared_ptr& node, std::shared_ptr& connection) + { + if (connection_ == nullptr) + throw std::domain_error("MavLinkMultirotorApi requires connection object to be set before createProxy call"); - connection = mavlinkcom::MavLinkConnection::connectRemoteUdp("Proxy to: " + name + " at " + ip + ":" + std::to_string(port), local_host_ip, ip, port); + connection = mavlinkcom::MavLinkConnection::connectRemoteUdp("Proxy to: " + name + " at " + ip + ":" + std::to_string(port), local_host_ip, ip, port); - // it is ok to reuse the simulator sysid and compid here because this node is only used to send a few messages directly to this endpoint - // and all other messages are funneled through from PX4 via the Join method below. - node = std::make_shared(connection_info_.sim_sysid, connection_info_.sim_compid); - node->connect(connection); + // it is ok to reuse the simulator sysid and compid here because this node is only used to send a few messages directly to this endpoint + // and all other messages are funneled through from PX4 via the Join method below. + node = std::make_shared(connection_info_.sim_sysid, connection_info_.sim_compid); + node->connect(connection); - // now join the main connection to this one, this causes all PX4 messages to be sent to the proxy and all messages from the proxy will be - // send directly to the PX4 (using whatever sysid/compid comes from that remote node). - connection_->join(connection); + // now join the main connection to this one, this causes all PX4 messages to be sent to the proxy and all messages from the proxy will be + // send directly to the PX4 (using whatever sysid/compid comes from that remote node). + connection_->join(connection); - auto mavcon = mav_vehicle_->getConnection(); - if (mavcon != connection_) { - mavcon->join(connection); + auto mavcon = mav_vehicle_->getConnection(); + if (mavcon != connection_) { + mavcon->join(connection); + } } - } - static std::string findPX4() - { - auto result = mavlinkcom::MavLinkConnection::findSerialPorts(0, 0); - for (auto iter = result.begin(); iter != result.end(); iter++) { - mavlinkcom::SerialPortInfo info = *iter; - if (( - (info.vid == pixhawkVendorId) && - (info.pid == pixhawkFMUV4ProductId || info.pid == pixhawkFMUV2ProductId || info.pid == pixhawkFMUV2OldBootloaderProductId || info.pid == pixhawkFMUV5ProductId) - ) || - ( - (info.displayName.find(L"PX4_") != std::string::npos) - )) { - // printf("Auto Selecting COM port: %S\n", info.displayName.c_str()); - - std::string portName_str; - - for (wchar_t ch : info.portName) { - portName_str.push_back(static_cast(ch)); + static std::string findPX4() + { + auto result = mavlinkcom::MavLinkConnection::findSerialPorts(0, 0); + for (auto iter = result.begin(); iter != result.end(); iter++) { + mavlinkcom::SerialPortInfo info = *iter; + if (( + (info.vid == pixhawkVendorId) && + (info.pid == pixhawkFMUV4ProductId || info.pid == pixhawkFMUV2ProductId || info.pid == pixhawkFMUV2OldBootloaderProductId || info.pid == pixhawkFMUV5ProductId)) || + ((info.displayName.find(L"PX4_") != std::string::npos))) { + // printf("Auto Selecting COM port: %S\n", info.displayName.c_str()); + + std::string portName_str; + + for (wchar_t ch : info.portName) { + portName_str.push_back(static_cast(ch)); + } + return portName_str; } - return portName_str; } + return ""; } - return ""; - } - void createMavConnection(const AirSimSettings::MavLinkConnectionInfo& connection_info) - { - if (connection_info.use_serial) { - createMavSerialConnection(connection_info.serial_port, connection_info.baud_rate); - } - else { - createMavEthernetConnection(connection_info); + void createMavConnection(const AirSimSettings::MavLinkConnectionInfo& connection_info) + { + if (connection_info.use_serial) { + createMavSerialConnection(connection_info.serial_port, connection_info.baud_rate); + } + else { + createMavEthernetConnection(connection_info); + } + + //Uncomment below for sending images over MavLink + //connectToVideoServer(); } - //Uncomment below for sending images over MavLink - //connectToVideoServer(); - } + void createMavEthernetConnection(const AirSimSettings::MavLinkConnectionInfo& connection_info) + { + close(); - void createMavEthernetConnection(const AirSimSettings::MavLinkConnectionInfo& connection_info) - { - close(); + connecting_ = true; + is_controls_0_1_ = true; + std::string remoteIpAddr; + Utils::setValue(rotor_controls_, 0.0f); - connecting_ = true; - is_controls_0_1_ = true; - std::string remoteIpAddr; - Utils::setValue(rotor_controls_, 0.0f); + if (connection_info.use_tcp) { + if (connection_info.tcp_port == 0) { + throw std::invalid_argument("TcpPort setting has an invalid value."); + } - if (connection_info.use_tcp) { - if (connection_info.tcp_port == 0) { - throw std::invalid_argument("TcpPort setting has an invalid value."); + auto msg = Utils::stringf("Waiting for TCP connection on port %d, local IP %s", connection_info.tcp_port, connection_info_.local_host_ip.c_str()); + addStatusMessage(msg); + try { + connection_ = std::make_shared(); + remoteIpAddr = connection_->acceptTcp("hil", connection_info_.local_host_ip, connection_info.tcp_port); + } + catch (std::exception& e) { + addStatusMessage("Accepting TCP socket failed, is another instance running?"); + addStatusMessage(e.what()); + return; + } } + else if (connection_info.udp_address.size() > 0) { + if (connection_info.udp_port == 0) { + throw std::invalid_argument("UdpPort setting has an invalid value."); + } - auto msg = Utils::stringf("Waiting for TCP connection on port %d, local IP %s", connection_info.tcp_port, connection_info_.local_host_ip.c_str()); - addStatusMessage(msg); - try { - connection_ = std::make_shared(); - remoteIpAddr = connection_->acceptTcp("hil", connection_info_.local_host_ip, connection_info.tcp_port); - } - catch (std::exception& e) { - addStatusMessage("Accepting TCP socket failed, is another instance running?"); - addStatusMessage(e.what()); - return; + connection_ = mavlinkcom::MavLinkConnection::connectRemoteUdp("hil", connection_info_.local_host_ip, connection_info.udp_address, connection_info.udp_port); } - } - else if (connection_info.udp_address.size() > 0) { - if (connection_info.udp_port == 0) { - throw std::invalid_argument("UdpPort setting has an invalid value."); + else { + throw std::invalid_argument("Please provide valid connection info for your drone."); } - connection_ = mavlinkcom::MavLinkConnection::connectRemoteUdp("hil", connection_info_.local_host_ip, connection_info.udp_address, connection_info.udp_port); - } - else { - throw std::invalid_argument("Please provide valid connection info for your drone."); - } - - // start listening to the SITL connection. - connection_->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { - unused(connection); - processMavMessages(msg); + // start listening to the SITL connection. + connection_->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { + unused(connection); + processMavMessages(msg); }); - hil_node_ = std::make_shared(connection_info_.sim_sysid, connection_info_.sim_compid); - hil_node_->connect(connection_); + hil_node_ = std::make_shared(connection_info_.sim_sysid, connection_info_.sim_compid); + hil_node_->connect(connection_); - if (connection_info.use_tcp) { - addStatusMessage(std::string("Connected to SITL over TCP.")); - } - else { - addStatusMessage(std::string("Connected to SITL over UDP.")); - } - - mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); - - if (connection_info_.control_ip_address != "") { - if (connection_info_.control_port_local == 0) { - throw std::invalid_argument("LocalControlPort setting has an invalid value."); + if (connection_info.use_tcp) { + addStatusMessage(std::string("Connected to SITL over TCP.")); } - if (!connection_info.use_tcp || connection_info_.control_ip_address != "remote") { - remoteIpAddr = connection_info_.control_ip_address; - } - if (remoteIpAddr == "local" || remoteIpAddr == "localhost") { - remoteIpAddr = "127.0.0.1"; + else { + addStatusMessage(std::string("Connected to SITL over UDP.")); } - // The PX4 SITL mode app cannot receive commands to control the drone over the same HIL mavlink connection. - // The HIL mavlink connection can only handle HIL_SENSOR messages. This separate channel is needed for - // everything else. - addStatusMessage(Utils::stringf("Connecting to PX4 Control UDP port %d, local IP %s, remote IP %s ...", - connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), remoteIpAddr.c_str())); + mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); - // if we try and connect the UDP port too quickly it doesn't work, bug in PX4 ? - for (int retries = 60; retries >= 0 && connecting_; retries--) { - try { - std::shared_ptr gcsConnection; - if (remoteIpAddr == "127.0.0.1") { - gcsConnection = mavlinkcom::MavLinkConnection::connectLocalUdp("gcs", - connection_info_.local_host_ip, - connection_info_.control_port_local); + if (connection_info_.control_ip_address != "") { + if (connection_info_.control_port_local == 0) { + throw std::invalid_argument("LocalControlPort setting has an invalid value."); + } + if (!connection_info.use_tcp || connection_info_.control_ip_address != "remote") { + remoteIpAddr = connection_info_.control_ip_address; + } + if (remoteIpAddr == "local" || remoteIpAddr == "localhost") { + remoteIpAddr = "127.0.0.1"; + } + + // The PX4 SITL mode app cannot receive commands to control the drone over the same HIL mavlink connection. + // The HIL mavlink connection can only handle HIL_SENSOR messages. This separate channel is needed for + // everything else. + addStatusMessage(Utils::stringf("Connecting to PX4 Control UDP port %d, local IP %s, remote IP %s ...", + connection_info_.control_port_local, + connection_info_.local_host_ip.c_str(), + remoteIpAddr.c_str())); + + // if we try and connect the UDP port too quickly it doesn't work, bug in PX4 ? + for (int retries = 60; retries >= 0 && connecting_; retries--) { + try { + std::shared_ptr gcsConnection; + if (remoteIpAddr == "127.0.0.1") { + gcsConnection = mavlinkcom::MavLinkConnection::connectLocalUdp("gcs", + connection_info_.local_host_ip, + connection_info_.control_port_local); + } + else { + gcsConnection = mavlinkcom::MavLinkConnection::connectRemoteUdp("gcs", + connection_info_.local_host_ip, + remoteIpAddr, + connection_info_.control_port_remote); + } + mav_vehicle_->connect(gcsConnection); + // need to try and send something to make sure the connection is good. + mav_vehicle_->setMessageInterval(mavlinkcom::MavLinkHomePosition::kMessageId, 1); + break; } - else { - gcsConnection = mavlinkcom::MavLinkConnection::connectRemoteUdp("gcs", - connection_info_.local_host_ip, - remoteIpAddr, - connection_info_.control_port_remote); + catch (std::exception&) { + std::this_thread::sleep_for(std::chrono::seconds(1)); } - mav_vehicle_->connect(gcsConnection); - // need to try and send something to make sure the connection is good. - mav_vehicle_->setMessageInterval(mavlinkcom::MavLinkHomePosition::kMessageId, 1); - break; } - catch (std::exception&) { - std::this_thread::sleep_for(std::chrono::seconds(1)); + + if (mav_vehicle_ == nullptr) { + // play was stopped! + return; } - } - if (mav_vehicle_ == nullptr) { - // play was stopped! - return; + if (mav_vehicle_->getConnection() != nullptr) { + addStatusMessage(std::string("Ground control connected over UDP.")); + } + else { + addStatusMessage(std::string("Timeout trying to connect ground control over UDP.")); + return; + } } - - if (mav_vehicle_->getConnection() != nullptr) { - addStatusMessage(std::string("Ground control connected over UDP.")); + try { + connectVehicle(); } - else { - addStatusMessage(std::string("Timeout trying to connect ground control over UDP.")); - return; + catch (std::exception& e) { + addStatusMessage("Error connecting vehicle:"); + addStatusMessage(e.what()); } - } - try { - connectVehicle(); - } - catch (std::exception& e) { - addStatusMessage("Error connecting vehicle:"); - addStatusMessage(e.what()); } - } - void processControlMessages(const mavlinkcom::MavLinkMessage& msg) - { - // Utils::log(Utils::stringf("Control msg %d", msg.msgid)); - // PX4 usually sends the following on the control channel. - // If nothing is arriving here it means our control channel UDP connection isn't working. - // MAVLINK_MSG_ID_HIGHRES_IMU - // MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET - // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW - // MAVLINK_MSG_ID_GPS_RAW_INT - // MAVLINK_MSG_ID_TIMESYNC - // MAVLINK_MSG_ID_ALTITUDE - // MAVLINK_MSG_ID_VFR_HUD - // MAVLINK_MSG_ID_ESTIMATOR_STATUS - // MAVLINK_MSG_ID_EXTENDED_SYS_STATE - // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN - // MAVLINK_MSG_ID_PING - // MAVLINK_MSG_ID_SYS_STATUS - // MAVLINK_MSG_ID_SYSTEM_TIME - // MAVLINK_MSG_ID_LINK_NODE_STATUS - // MAVLINK_MSG_ID_AUTOPILOT_VERSION - // MAVLINK_MSG_ID_COMMAND_ACK - // MAVLINK_MSG_ID_STATUSTEXT - // MAVLINK_MSG_ID_PARAM_VALUE - processMavMessages(msg); - } - - void connectVehicle() - { - // listen to this UDP mavlink connection also - auto mavcon = mav_vehicle_->getConnection(); - if (mavcon != nullptr && mavcon != connection_) { - mavcon->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { - unused(connection); - processControlMessages(msg); - }); - } - else { - mav_vehicle_->connect(connection_); + void processControlMessages(const mavlinkcom::MavLinkMessage& msg) + { + // Utils::log(Utils::stringf("Control msg %d", msg.msgid)); + // PX4 usually sends the following on the control channel. + // If nothing is arriving here it means our control channel UDP connection isn't working. + // MAVLINK_MSG_ID_HIGHRES_IMU + // MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET + // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW + // MAVLINK_MSG_ID_GPS_RAW_INT + // MAVLINK_MSG_ID_TIMESYNC + // MAVLINK_MSG_ID_ALTITUDE + // MAVLINK_MSG_ID_VFR_HUD + // MAVLINK_MSG_ID_ESTIMATOR_STATUS + // MAVLINK_MSG_ID_EXTENDED_SYS_STATE + // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN + // MAVLINK_MSG_ID_PING + // MAVLINK_MSG_ID_SYS_STATUS + // MAVLINK_MSG_ID_SYSTEM_TIME + // MAVLINK_MSG_ID_LINK_NODE_STATUS + // MAVLINK_MSG_ID_AUTOPILOT_VERSION + // MAVLINK_MSG_ID_COMMAND_ACK + // MAVLINK_MSG_ID_STATUSTEXT + // MAVLINK_MSG_ID_PARAM_VALUE + processMavMessages(msg); } - connected_ = true; + void connectVehicle() + { + // listen to this UDP mavlink connection also + auto mavcon = mav_vehicle_->getConnection(); + if (mavcon != nullptr && mavcon != connection_) { + mavcon->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { + unused(connection); + processControlMessages(msg); + }); + } + else { + mav_vehicle_->connect(connection_); + } + + connected_ = true; - // Also request home position messages - mav_vehicle_->setMessageInterval(mavlinkcom::MavLinkHomePosition::kMessageId, 1); + // Also request home position messages + mav_vehicle_->setMessageInterval(mavlinkcom::MavLinkHomePosition::kMessageId, 1); - // now we can start our heartbeats. - mav_vehicle_->startHeartbeat(); + // now we can start our heartbeats. + mav_vehicle_->startHeartbeat(); - // wait for px4 to connect so we can safely send any configured parameters - while (!send_params_ && connected_) { - std::this_thread::sleep_for(std::chrono::seconds(1)); - } + // wait for px4 to connect so we can safely send any configured parameters + while (!send_params_ && connected_) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + } - if (connected_) { - sendParams(); - send_params_ = false; + if (connected_) { + sendParams(); + send_params_ = false; + } } - } - void createMavSerialConnection(const std::string& port_name, int baud_rate) - { - close(); + void createMavSerialConnection(const std::string& port_name, int baud_rate) + { + close(); - connecting_ = true; - bool reported = false; - std::string port_name_auto = port_name; - while (port_name_auto == "" || port_name_auto == "*") { - port_name_auto = findPX4(); - if (port_name_auto == "") { - if (!reported) { - reported = true; - addStatusMessage("Could not detect a connected PX4 flight controller on any USB ports."); - addStatusMessage("You can specify USB port in settings.json."); + connecting_ = true; + bool reported = false; + std::string port_name_auto = port_name; + while (port_name_auto == "" || port_name_auto == "*") { + port_name_auto = findPX4(); + if (port_name_auto == "") { + if (!reported) { + reported = true; + addStatusMessage("Could not detect a connected PX4 flight controller on any USB ports."); + addStatusMessage("You can specify USB port in settings.json."); + } + std::this_thread::sleep_for(std::chrono::seconds(1)); } - std::this_thread::sleep_for(std::chrono::seconds(1)); } - } - if (port_name_auto == "") { - addStatusMessage("USB port for PX4 flight controller is empty. Please set it in settings.json."); - return; - } + if (port_name_auto == "") { + addStatusMessage("USB port for PX4 flight controller is empty. Please set it in settings.json."); + return; + } - if (baud_rate == 0) { - addStatusMessage("Baud rate specified in settings.json is 0 which is invalid"); - return; - } + if (baud_rate == 0) { + addStatusMessage("Baud rate specified in settings.json is 0 which is invalid"); + return; + } - addStatusMessage(Utils::stringf("Connecting to PX4 over serial port: %s, baud rate %d ....", port_name_auto.c_str(), baud_rate)); - reported = false; + addStatusMessage(Utils::stringf("Connecting to PX4 over serial port: %s, baud rate %d ....", port_name_auto.c_str(), baud_rate)); + reported = false; - while (connecting_) { - try { - connection_ = mavlinkcom::MavLinkConnection::connectSerial("hil", port_name_auto, baud_rate); - connection_->ignoreMessage(mavlinkcom::MavLinkAttPosMocap::kMessageId); //TODO: find better way to communicate debug pose instead of using fake Mo-cap messages - hil_node_ = std::make_shared(connection_info_.sim_sysid, connection_info_.sim_compid); - hil_node_->connect(connection_); - addStatusMessage(Utils::stringf("Connected to PX4 over serial port: %s", port_name_auto.c_str())); - - // start listening to the HITL connection. - connection_->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { - unused(connection); - processMavMessages(msg); + while (connecting_) { + try { + connection_ = mavlinkcom::MavLinkConnection::connectSerial("hil", port_name_auto, baud_rate); + connection_->ignoreMessage(mavlinkcom::MavLinkAttPosMocap::kMessageId); //TODO: find better way to communicate debug pose instead of using fake Mo-cap messages + hil_node_ = std::make_shared(connection_info_.sim_sysid, connection_info_.sim_compid); + hil_node_->connect(connection_); + addStatusMessage(Utils::stringf("Connected to PX4 over serial port: %s", port_name_auto.c_str())); + + // start listening to the HITL connection. + connection_->subscribe([=](std::shared_ptr connection, const mavlinkcom::MavLinkMessage& msg) { + unused(connection); + processMavMessages(msg); }); - mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); + mav_vehicle_ = std::make_shared(connection_info_.vehicle_sysid, connection_info_.vehicle_compid); - connectVehicle(); - return; - } - catch (std::exception& e) { - if (!reported) { - reported = true; - addStatusMessage("Error connecting to mavlink vehicle."); - addStatusMessage(e.what()); - addStatusMessage("Please check your USB port in settings.json."); + connectVehicle(); + return; + } + catch (std::exception& e) { + if (!reported) { + reported = true; + addStatusMessage("Error connecting to mavlink vehicle."); + addStatusMessage(e.what()); + addStatusMessage("Please check your USB port in settings.json."); + } + std::this_thread::sleep_for(std::chrono::seconds(1)); } - std::this_thread::sleep_for(std::chrono::seconds(1)); } } - } - mavlinkcom::MavLinkHilSensor getLastSensorMessage() - { - std::lock_guard guard(last_message_mutex_); - return last_sensor_message_; - } + mavlinkcom::MavLinkHilSensor getLastSensorMessage() + { + std::lock_guard guard(last_message_mutex_); + return last_sensor_message_; + } - mavlinkcom::MavLinkDistanceSensor getLastDistanceMessage() - { - std::lock_guard guard(last_message_mutex_); - return last_distance_message_; - } + mavlinkcom::MavLinkDistanceSensor getLastDistanceMessage() + { + std::lock_guard guard(last_message_mutex_); + return last_distance_message_; + } - mavlinkcom::MavLinkHilGps getLastGpsMessage() - { - std::lock_guard guard(last_message_mutex_); - return last_gps_message_; - } + mavlinkcom::MavLinkHilGps getLastGpsMessage() + { + std::lock_guard guard(last_message_mutex_); + return last_gps_message_; + } - void sendParams() - { - // send any mavlink parameters from settings.json through to the connected vehicle. - if (mav_vehicle_ != nullptr && connection_info_.params.size() > 0) { - try { - for (auto iter : connection_info_.params) { - auto key = iter.first; - auto value = iter.second; - mavlinkcom::MavLinkParameter p; - p.name = key; - p.value = value; - bool result = false; - mav_vehicle_->setParameter(p).wait(1000, &result); - if (!result) { - Utils::log(Utils::stringf("Failed to set mavlink parameter '%s'", key.c_str())); - } + void sendParams() + { + // send any mavlink parameters from settings.json through to the connected vehicle. + if (mav_vehicle_ != nullptr && connection_info_.params.size() > 0) { + try { + for (auto iter : connection_info_.params) { + auto key = iter.first; + auto value = iter.second; + mavlinkcom::MavLinkParameter p; + p.name = key; + p.value = value; + bool result = false; + mav_vehicle_->setParameter(p).wait(1000, &result); + if (!result) { + Utils::log(Utils::stringf("Failed to set mavlink parameter '%s'", key.c_str())); + } + } + } + catch (std::exception& ex) { + addStatusMessage("Exception sending parameters to vehicle"); + addStatusMessage(ex.what()); } - } - catch (std::exception& ex) { - addStatusMessage("Exception sending parameters to vehicle"); - addStatusMessage(ex.what()); } } - } - void setArmed(bool armed) - { - if (is_armed_) { - if (!armed) { - onDisarmed(); + void setArmed(bool armed) + { + if (is_armed_) { + if (!armed) { + onDisarmed(); + } } - } - else { - if (armed) { - onArmed(); + else { + if (armed) { + onArmed(); + } } - } - is_armed_ = armed; - if (!armed) { - //reset motor controls - for (size_t i = 0; i < Utils::length(rotor_controls_); ++i) { - rotor_controls_[i] = 0; + is_armed_ = armed; + if (!armed) { + //reset motor controls + for (size_t i = 0; i < Utils::length(rotor_controls_); ++i) { + rotor_controls_[i] = 0; + } } } - } - void processQgcMessages(const mavlinkcom::MavLinkMessage& msg) - { - if (msg.msgid == MocapPoseMessage.msgid) { - std::lock_guard guard(mocap_pose_mutex_); - MocapPoseMessage.decode(msg); - getMocapPose(mocap_pose_.position, mocap_pose_.orientation); - } - //else ignore message - } - - void addStatusMessage(const std::string& message) - { - if (message.size() != 0) { - Utils::log(message); - std::lock_guard guard_status(status_text_mutex_); - //if queue became too large, clear it first - if (status_messages_.size() > status_messages_MaxSize) - Utils::clear(status_messages_, status_messages_MaxSize - status_messages_.size()); - status_messages_.push(message); + void processQgcMessages(const mavlinkcom::MavLinkMessage& msg) + { + if (msg.msgid == MocapPoseMessage.msgid) { + std::lock_guard guard(mocap_pose_mutex_); + MocapPoseMessage.decode(msg); + getMocapPose(mocap_pose_.position, mocap_pose_.orientation); + } + //else ignore message } - } - void handleLockStep() - { - received_actuator_controls_ = true; - // if the timestamps match then it means we are in lockstep mode. - if (!lock_step_enabled_) { - // && (HilActuatorControlsMessage.flags & 0x1)) // todo: enable this check when this flag is widely available... - if (last_hil_sensor_time_ == HilActuatorControlsMessage.time_usec) { - addStatusMessage("Enabling lockstep mode"); - lock_step_enabled_ = true; + void addStatusMessage(const std::string& message) + { + if (message.size() != 0) { + Utils::log(message); + std::lock_guard guard_status(status_text_mutex_); + //if queue became too large, clear it first + if (status_messages_.size() > status_messages_MaxSize) + Utils::clear(status_messages_, status_messages_MaxSize - status_messages_.size()); + status_messages_.push(message); } } - else + + void handleLockStep() { - auto now = clock()->nowNanos() / 1000; - auto delay = static_cast(now - last_update_time_); + received_actuator_controls_ = true; + // if the timestamps match then it means we are in lockstep mode. + if (!lock_step_enabled_) { + // && (HilActuatorControlsMessage.flags & 0x1)) // todo: enable this check when this flag is widely available... + if (last_hil_sensor_time_ == HilActuatorControlsMessage.time_usec) { + addStatusMessage("Enabling lockstep mode"); + lock_step_enabled_ = true; + } + } + else { + auto now = clock()->nowNanos() / 1000; + auto delay = static_cast(now - last_update_time_); - std::lock_guard guard(telemetry_mutex_); - actuator_delay_ += delay; - } - if (world_ != nullptr) { - world_->pause(false); + std::lock_guard guard(telemetry_mutex_); + actuator_delay_ += delay; + } + if (world_ != nullptr) { + world_->pause(false); + } } - } - - void processMavMessages(const mavlinkcom::MavLinkMessage& msg) - { - if (msg.msgid == HeartbeatMessage.msgid) { - std::lock_guard guard_heartbeat(heartbeat_mutex_); - - HeartbeatMessage.decode(msg); - bool armed = (HeartbeatMessage.base_mode & static_cast(mavlinkcom::MAV_MODE_FLAG::MAV_MODE_FLAG_SAFETY_ARMED)) > 0; - setArmed(armed); - if (!got_first_heartbeat_) { - Utils::log("received first heartbeat"); - - got_first_heartbeat_ = true; - if (HeartbeatMessage.autopilot == static_cast(mavlinkcom::MAV_AUTOPILOT::MAV_AUTOPILOT_PX4) && - HeartbeatMessage.type == static_cast(mavlinkcom::MAV_TYPE::MAV_TYPE_FIXED_WING)) { - // PX4 will scale fixed wing servo outputs to -1 to 1 - // and it scales multi rotor servo output to 0 to 1. - is_controls_0_1_ = false; + void processMavMessages(const mavlinkcom::MavLinkMessage& msg) + { + if (msg.msgid == HeartbeatMessage.msgid) { + std::lock_guard guard_heartbeat(heartbeat_mutex_); + + HeartbeatMessage.decode(msg); + + bool armed = (HeartbeatMessage.base_mode & static_cast(mavlinkcom::MAV_MODE_FLAG::MAV_MODE_FLAG_SAFETY_ARMED)) > 0; + setArmed(armed); + if (!got_first_heartbeat_) { + Utils::log("received first heartbeat"); + + got_first_heartbeat_ = true; + if (HeartbeatMessage.autopilot == static_cast(mavlinkcom::MAV_AUTOPILOT::MAV_AUTOPILOT_PX4) && + HeartbeatMessage.type == static_cast(mavlinkcom::MAV_TYPE::MAV_TYPE_FIXED_WING)) { + // PX4 will scale fixed wing servo outputs to -1 to 1 + // and it scales multi rotor servo output to 0 to 1. + is_controls_0_1_ = false; + } + } + else if (is_simulation_mode_ && !is_hil_mode_set_) { + setHILMode(); } } - else if (is_simulation_mode_ && !is_hil_mode_set_) { - setHILMode(); + else if (msg.msgid == StatusTextMessage.msgid) { + StatusTextMessage.decode(msg); + //lock is established by below method + addStatusMessage(std::string(StatusTextMessage.text)); + } + else if (msg.msgid == CommandLongMessage.msgid) { + CommandLongMessage.decode(msg); + if (CommandLongMessage.command == static_cast(mavlinkcom::MAV_CMD::MAV_CMD_SET_MESSAGE_INTERVAL)) { + int msg_id = static_cast(CommandLongMessage.param1 + 0.5); + if (msg_id == 115) { //HIL_STATE_QUATERNION + hil_state_freq_ = static_cast(CommandLongMessage.param2 + 0.5); + } + } } - } - else if (msg.msgid == StatusTextMessage.msgid) { - StatusTextMessage.decode(msg); - //lock is established by below method - addStatusMessage(std::string(StatusTextMessage.text)); - } - else if (msg.msgid == CommandLongMessage.msgid) { - CommandLongMessage.decode(msg); - if (CommandLongMessage.command == static_cast(mavlinkcom::MAV_CMD::MAV_CMD_SET_MESSAGE_INTERVAL)) { - int msg_id = static_cast(CommandLongMessage.param1 + 0.5); - if (msg_id == 115) { //HIL_STATE_QUATERNION - hil_state_freq_ = static_cast(CommandLongMessage.param2 + 0.5); + else if (msg.msgid == HilControlsMessage.msgid) { + if (!actuators_message_supported_) { + std::lock_guard guard_controls(hil_controls_mutex_); + + HilControlsMessage.decode(msg); + rotor_controls_[0] = HilControlsMessage.roll_ailerons; + rotor_controls_[1] = HilControlsMessage.pitch_elevator; + rotor_controls_[2] = HilControlsMessage.yaw_rudder; + rotor_controls_[3] = HilControlsMessage.throttle; + rotor_controls_[4] = HilControlsMessage.aux1; + rotor_controls_[5] = HilControlsMessage.aux2; + rotor_controls_[6] = HilControlsMessage.aux3; + rotor_controls_[7] = HilControlsMessage.aux4; + + normalizeRotorControls(); + handleLockStep(); } } - } - else if (msg.msgid == HilControlsMessage.msgid) { - if (!actuators_message_supported_) { - std::lock_guard guard_controls(hil_controls_mutex_); + else if (msg.msgid == HilActuatorControlsMessage.msgid) { + actuators_message_supported_ = true; - HilControlsMessage.decode(msg); - rotor_controls_[0] = HilControlsMessage.roll_ailerons; - rotor_controls_[1] = HilControlsMessage.pitch_elevator; - rotor_controls_[2] = HilControlsMessage.yaw_rudder; - rotor_controls_[3] = HilControlsMessage.throttle; - rotor_controls_[4] = HilControlsMessage.aux1; - rotor_controls_[5] = HilControlsMessage.aux2; - rotor_controls_[6] = HilControlsMessage.aux3; - rotor_controls_[7] = HilControlsMessage.aux4; + std::lock_guard guard_actuator(hil_controls_mutex_); //use same mutex as HIL_CONTROl + + HilActuatorControlsMessage.decode(msg); + bool isarmed = (HilActuatorControlsMessage.mode & 128) != 0; + for (auto i = 0; i < 8; ++i) { + if (isarmed) { + rotor_controls_[i] = HilActuatorControlsMessage.controls[i]; + } + else { + rotor_controls_[i] = 0; + } + } + if (isarmed) { + normalizeRotorControls(); + } - normalizeRotorControls(); handleLockStep(); } - } - else if (msg.msgid == HilActuatorControlsMessage.msgid) { - actuators_message_supported_ = true; - - std::lock_guard guard_actuator(hil_controls_mutex_); //use same mutex as HIL_CONTROl - - HilActuatorControlsMessage.decode(msg); - bool isarmed = (HilActuatorControlsMessage.mode & 128) != 0; - for (auto i = 0; i < 8; ++i) { - if (isarmed) { - rotor_controls_[i] = HilActuatorControlsMessage.controls[i]; + else if (msg.msgid == MavLinkGpsRawInt.msgid) { + MavLinkGpsRawInt.decode(msg); + auto fix_type = static_cast(MavLinkGpsRawInt.fix_type); + auto locked = (fix_type != mavlinkcom::GPS_FIX_TYPE::GPS_FIX_TYPE_NO_GPS && + fix_type != mavlinkcom::GPS_FIX_TYPE::GPS_FIX_TYPE_NO_FIX); + if (locked && !has_gps_lock_) { + addStatusMessage("Got GPS lock"); + has_gps_lock_ = true; } - else { - rotor_controls_[i] = 0; + if (!has_home_ && current_state_.home.is_set) { + addStatusMessage("Got GPS Home Location"); + has_home_ = true; } + send_params_ = true; } - if (isarmed) { - normalizeRotorControls(); + else if (msg.msgid == mavlinkcom::MavLinkLocalPositionNed::kMessageId) { + // we are getting position information... so we can use this to check the stability of the z coordinate before takeoff. + if (current_state_.controls.landed) { + monitorGroundAltitude(); + } } - - handleLockStep(); - } - else if (msg.msgid == MavLinkGpsRawInt.msgid) { - MavLinkGpsRawInt.decode(msg); - auto fix_type = static_cast(MavLinkGpsRawInt.fix_type); - auto locked = (fix_type != mavlinkcom::GPS_FIX_TYPE::GPS_FIX_TYPE_NO_GPS && - fix_type != mavlinkcom::GPS_FIX_TYPE::GPS_FIX_TYPE_NO_FIX); - if (locked && !has_gps_lock_) { - addStatusMessage("Got GPS lock"); - has_gps_lock_ = true; + else if (msg.msgid == mavlinkcom::MavLinkExtendedSysState::kMessageId) { + // check landed state. + getLandedState(); + send_params_ = true; } - if (!has_home_ && current_state_.home.is_set) { - addStatusMessage("Got GPS Home Location"); - has_home_ = true; + else if (msg.msgid == mavlinkcom::MavLinkHomePosition::kMessageId) { + mavlinkcom::MavLinkHomePosition home; + home.decode(msg); + // this is a good time to send the params + send_params_ = true; } - send_params_ = true; - } - else if (msg.msgid == mavlinkcom::MavLinkLocalPositionNed::kMessageId) { - // we are getting position information... so we can use this to check the stability of the z coordinate before takeoff. - if (current_state_.controls.landed) { - monitorGroundAltitude(); + else if (msg.msgid == mavlinkcom::MavLinkSysStatus::kMessageId) { + // this is a good time to send the params + send_params_ = true; + } + else if (msg.msgid == mavlinkcom::MavLinkAutopilotVersion::kMessageId) { + // this is a good time to send the params + send_params_ = true; + } + else { + // creates too much log output, only do this when debugging this issue specifically. + // Utils::log(Utils::stringf("Ignoring msg %d from %d,%d ", msg.msgid, msg.compid, msg.sysid)); } } - else if (msg.msgid == mavlinkcom::MavLinkExtendedSysState::kMessageId) { - // check landed state. - getLandedState(); - send_params_ = true; - } - else if (msg.msgid == mavlinkcom::MavLinkHomePosition::kMessageId) { - mavlinkcom::MavLinkHomePosition home; - home.decode(msg); - // this is a good time to send the params - send_params_ = true; - } - else if (msg.msgid == mavlinkcom::MavLinkSysStatus::kMessageId) { - // this is a good time to send the params - send_params_ = true; - } - else if (msg.msgid == mavlinkcom::MavLinkAutopilotVersion::kMessageId) { - // this is a good time to send the params - send_params_ = true; - } - else { - // creates too much log output, only do this when debugging this issue specifically. - // Utils::log(Utils::stringf("Ignoring msg %d from %d,%d ", msg.msgid, msg.compid, msg.sysid)); - } - } - void sendHILSensor(const Vector3r& acceleration, const Vector3r& gyro, const Vector3r& mag, float abs_pressure, float pressure_alt) - { - if (!is_simulation_mode_) - throw std::logic_error("Attempt to send simulated sensor messages while not in simulation mode"); - - mavlinkcom::MavLinkHilSensor hil_sensor; - hil_sensor.time_usec = last_hil_sensor_time_ = getSimTime(); + void sendHILSensor(const Vector3r& acceleration, const Vector3r& gyro, const Vector3r& mag, float abs_pressure, float pressure_alt) + { + if (!is_simulation_mode_) + throw std::logic_error("Attempt to send simulated sensor messages while not in simulation mode"); - hil_sensor.xacc = acceleration.x(); - hil_sensor.yacc = acceleration.y(); - hil_sensor.zacc = acceleration.z(); - hil_sensor.fields_updated = 0b111; // Set accel bit fields + mavlinkcom::MavLinkHilSensor hil_sensor; + hil_sensor.time_usec = last_hil_sensor_time_ = getSimTime(); - hil_sensor.xgyro = gyro.x(); - hil_sensor.ygyro = gyro.y(); - hil_sensor.zgyro = gyro.z(); + hil_sensor.xacc = acceleration.x(); + hil_sensor.yacc = acceleration.y(); + hil_sensor.zacc = acceleration.z(); + hil_sensor.fields_updated = 0b111; // Set accel bit fields - hil_sensor.fields_updated |= 0b111000; // Set gyro bit fields + hil_sensor.xgyro = gyro.x(); + hil_sensor.ygyro = gyro.y(); + hil_sensor.zgyro = gyro.z(); - hil_sensor.xmag = mag.x(); - hil_sensor.ymag = mag.y(); - hil_sensor.zmag = mag.z(); + hil_sensor.fields_updated |= 0b111000; // Set gyro bit fields - hil_sensor.fields_updated |= 0b111000000; // Set mag bit fields + hil_sensor.xmag = mag.x(); + hil_sensor.ymag = mag.y(); + hil_sensor.zmag = mag.z(); - hil_sensor.abs_pressure = abs_pressure; - hil_sensor.pressure_alt = pressure_alt; + hil_sensor.fields_updated |= 0b111000000; // Set mag bit fields - hil_sensor.fields_updated |= 0b1101000000000; // Set baro bit fields + hil_sensor.abs_pressure = abs_pressure; + hil_sensor.pressure_alt = pressure_alt; - //TODO: enable temperature? diff_pressure - if (was_reset_) { - hil_sensor.fields_updated = static_cast(1 << 31); - } + hil_sensor.fields_updated |= 0b1101000000000; // Set baro bit fields - if (hil_node_ != nullptr) { - hil_node_->sendMessage(hil_sensor); - received_actuator_controls_ = false; - if (lock_step_enabled_ && world_ != nullptr) { - world_->pauseForTime(0.1); // 100 millisecond delay max waiting for actuator controls. + //TODO: enable temperature? diff_pressure + if (was_reset_) { + hil_sensor.fields_updated = static_cast(1 << 31); } - } - - std::lock_guard guard(last_message_mutex_); - last_sensor_message_ = hil_sensor; - } - void sendSystemTime() - { - // SYSTEM TIME from host - auto tu = getSimTime(); - uint32_t ms = (uint32_t)(tu / 1000); - if (ms != last_sys_time_) { - last_sys_time_ = ms; - mavlinkcom::MavLinkSystemTime msg_system_time; - msg_system_time.time_unix_usec = tu; - msg_system_time.time_boot_ms = last_sys_time_; if (hil_node_ != nullptr) { - hil_node_->sendMessage(msg_system_time); + hil_node_->sendMessage(hil_sensor); + received_actuator_controls_ = false; + if (lock_step_enabled_ && world_ != nullptr) { + world_->pauseForTime(0.1); // 100 millisecond delay max waiting for actuator controls. + } } - } - } - void sendDistanceSensor(float min_distance, float max_distance, float current_distance, - uint8_t sensor_type, uint8_t sensor_id, const Quaternionr& orientation) - { - if (!is_simulation_mode_) - throw std::logic_error("Attempt to send simulated distance sensor messages while not in simulation mode"); + std::lock_guard guard(last_message_mutex_); + last_sensor_message_ = hil_sensor; + } - mavlinkcom::MavLinkDistanceSensor distance_sensor; - distance_sensor.time_boot_ms = static_cast(getSimTime() / 1000); - distance_sensor.min_distance = static_cast(min_distance); - distance_sensor.max_distance = static_cast(max_distance); - distance_sensor.current_distance = static_cast(current_distance); - distance_sensor.type = sensor_type; - distance_sensor.id = sensor_id; + void sendSystemTime() + { + // SYSTEM TIME from host + auto tu = getSimTime(); + uint32_t ms = (uint32_t)(tu / 1000); + if (ms != last_sys_time_) { + last_sys_time_ = ms; + mavlinkcom::MavLinkSystemTime msg_system_time; + msg_system_time.time_unix_usec = tu; + msg_system_time.time_boot_ms = last_sys_time_; + if (hil_node_ != nullptr) { + hil_node_->sendMessage(msg_system_time); + } + } + } - // Use custom orientation - distance_sensor.orientation = 100; // MAV_SENSOR_ROTATION_CUSTOM - distance_sensor.quaternion[0] = orientation.w(); - distance_sensor.quaternion[1] = orientation.x(); - distance_sensor.quaternion[2] = orientation.y(); - distance_sensor.quaternion[3] = orientation.z(); + void sendDistanceSensor(float min_distance, float max_distance, float current_distance, + uint8_t sensor_type, uint8_t sensor_id, const Quaternionr& orientation) + { + if (!is_simulation_mode_) + throw std::logic_error("Attempt to send simulated distance sensor messages while not in simulation mode"); + + mavlinkcom::MavLinkDistanceSensor distance_sensor; + distance_sensor.time_boot_ms = static_cast(getSimTime() / 1000); + distance_sensor.min_distance = static_cast(min_distance); + distance_sensor.max_distance = static_cast(max_distance); + distance_sensor.current_distance = static_cast(current_distance); + distance_sensor.type = sensor_type; + distance_sensor.id = sensor_id; + + // Use custom orientation + distance_sensor.orientation = 100; // MAV_SENSOR_ROTATION_CUSTOM + distance_sensor.quaternion[0] = orientation.w(); + distance_sensor.quaternion[1] = orientation.x(); + distance_sensor.quaternion[2] = orientation.y(); + distance_sensor.quaternion[3] = orientation.z(); + + //TODO: use covariance parameter? - //TODO: use covariance parameter? + if (hil_node_ != nullptr) { + hil_node_->sendMessage(distance_sensor); + } - if (hil_node_ != nullptr) { - hil_node_->sendMessage(distance_sensor); + std::lock_guard guard(last_message_mutex_); + last_distance_message_ = distance_sensor; } - std::lock_guard guard(last_message_mutex_); - last_distance_message_ = distance_sensor; - } - - void sendHILGps(const GeoPoint& geo_point, const Vector3r& velocity, float velocity_xy, float cog, - float eph, float epv, int fix_type, unsigned int satellites_visible) - { - unused(satellites_visible); + void sendHILGps(const GeoPoint& geo_point, const Vector3r& velocity, float velocity_xy, float cog, + float eph, float epv, int fix_type, unsigned int satellites_visible) + { + unused(satellites_visible); + + if (!is_simulation_mode_) + throw std::logic_error("Attempt to send simulated GPS messages while not in simulation mode"); + + mavlinkcom::MavLinkHilGps hil_gps; + hil_gps.time_usec = getSimTime(); + hil_gps.lat = static_cast(geo_point.latitude * 1E7); + hil_gps.lon = static_cast(geo_point.longitude * 1E7); + hil_gps.alt = static_cast(geo_point.altitude * 1000); + hil_gps.vn = static_cast(velocity.x() * 100); + hil_gps.ve = static_cast(velocity.y() * 100); + hil_gps.vd = static_cast(velocity.z() * 100); + hil_gps.eph = static_cast(eph * 100); + hil_gps.epv = static_cast(epv * 100); + hil_gps.fix_type = static_cast(fix_type); + hil_gps.vel = static_cast(velocity_xy * 100); + hil_gps.cog = static_cast(cog * 100); + hil_gps.satellites_visible = static_cast(15); - if (!is_simulation_mode_) - throw std::logic_error("Attempt to send simulated GPS messages while not in simulation mode"); + if (hil_node_ != nullptr) { + hil_node_->sendMessage(hil_gps); + } - mavlinkcom::MavLinkHilGps hil_gps; - hil_gps.time_usec = getSimTime(); - hil_gps.lat = static_cast(geo_point.latitude * 1E7); - hil_gps.lon = static_cast(geo_point.longitude * 1E7); - hil_gps.alt = static_cast(geo_point.altitude * 1000); - hil_gps.vn = static_cast(velocity.x() * 100); - hil_gps.ve = static_cast(velocity.y() * 100); - hil_gps.vd = static_cast(velocity.z() * 100); - hil_gps.eph = static_cast(eph * 100); - hil_gps.epv = static_cast(epv * 100); - hil_gps.fix_type = static_cast(fix_type); - hil_gps.vel = static_cast(velocity_xy * 100); - hil_gps.cog = static_cast(cog * 100); - hil_gps.satellites_visible = static_cast(15); + if (hil_gps.lat < 0.1f && hil_gps.lat > -0.1f) { + //Utils::DebugBreak(); + Utils::log("hil_gps.lat was too close to 0", Utils::kLogLevelError); + } - if (hil_node_ != nullptr) { - hil_node_->sendMessage(hil_gps); + std::lock_guard guard(last_message_mutex_); + last_gps_message_ = hil_gps; } - if (hil_gps.lat < 0.1f && hil_gps.lat > -0.1f) { - //Utils::DebugBreak(); - Utils::log("hil_gps.lat was too close to 0", Utils::kLogLevelError); + void resetState() + { + //reset state + is_hil_mode_set_ = false; + is_controls_0_1_ = true; + hil_state_freq_ = -1; + actuators_message_supported_ = false; + state_version_ = 0; + current_state_ = mavlinkcom::VehicleState(); + target_height_ = 0; + got_first_heartbeat_ = false; + is_armed_ = false; + has_home_ = false; + sim_time_us_ = 0; + last_sys_time_ = 0; + last_gps_time_ = 0; + last_update_time_ = 0; + last_hil_sensor_time_ = 0; + update_count_ = 0; + hil_sensor_count_ = 0; + lock_step_resets_ = 0; + actuator_delay_ = 0; + is_api_control_enabled_ = false; + thrust_controller_ = PidController(); + Utils::setValue(rotor_controls_, 0.0f); + was_reset_ = false; + received_actuator_controls_ = false; + lock_step_enabled_ = false; + has_gps_lock_ = false; + send_params_ = false; + mocap_pose_ = Pose::nanPose(); + ground_variance_ = 1; + ground_filter_.initialize(25, 0.1f); + cancelLastTask(); } - std::lock_guard guard(last_message_mutex_); - last_gps_message_ = hil_gps; - } - - void resetState() - { - //reset state - is_hil_mode_set_ = false; - is_controls_0_1_ = true; - hil_state_freq_ = -1; - actuators_message_supported_ = false; - state_version_ = 0; - current_state_ = mavlinkcom::VehicleState(); - target_height_ = 0; - got_first_heartbeat_ = false; - is_armed_ = false; - has_home_ = false; - sim_time_us_ = 0; - last_sys_time_ = 0; - last_gps_time_ = 0; - last_update_time_ = 0; - last_hil_sensor_time_ = 0; - update_count_ = 0; - hil_sensor_count_ = 0; - lock_step_resets_ = 0; - actuator_delay_ = 0; - is_api_control_enabled_ = false; - thrust_controller_ = PidController(); - Utils::setValue(rotor_controls_, 0.0f); - was_reset_ = false; - received_actuator_controls_ = false; - lock_step_enabled_ = false; - has_gps_lock_ = false; - send_params_ = false; - mocap_pose_ = Pose::nanPose(); - ground_variance_ = 1; - ground_filter_.initialize(25, 0.1f); - cancelLastTask(); - } - - void monitorGroundAltitude() - { - // used to ensure stable altitude before takeoff. - auto position = getPosition(); - auto result = ground_filter_.filter(position.z()); - auto variance = std::get<1>(result); - if (variance >= 0) { // filter returns -1 if we don't have enough data yet. - ground_variance_ = variance; - } - } - - -protected: //variables - - //TODO: below was made protected from private to support Ardupilot - //implementation but we need to review this and avoid having protected variables - static const int RotorControlsCount = 8; - - const SensorCollection* sensors_; - mutable std::mutex hil_controls_mutex_; - AirSimSettings::MavLinkConnectionInfo connection_info_; - float rotor_controls_[RotorControlsCount]; - bool is_simulation_mode_; - - -private: //variables - static const int pixhawkVendorId = 9900; ///< Vendor ID for Pixhawk board (V2 and V1) and PX4 Flow - static const int pixhawkFMUV4ProductId = 18; ///< Product ID for Pixhawk V2 board - static const int pixhawkFMUV2ProductId = 17; ///< Product ID for Pixhawk V2 board - static const int pixhawkFMUV5ProductId = 50; ///< Product ID for Pixhawk V5 board - static const int pixhawkFMUV2OldBootloaderProductId = 22; ///< Product ID for Bootloader on older Pixhawk V2 boards - static const int pixhawkFMUV1ProductId = 16; ///< Product ID for PX4 FMU V1 board - static const int messageReceivedTimeout = 10; ///< Seconds - - std::shared_ptr logviewer_proxy_, logviewer_out_proxy_, qgc_proxy_; - - size_t status_messages_MaxSize = 5000; - - std::shared_ptr hil_node_; - std::shared_ptr connection_; - std::shared_ptr video_server_; - std::shared_ptr mav_vehicle_control_; - - mavlinkcom::MavLinkAttPosMocap MocapPoseMessage; - mavlinkcom::MavLinkHeartbeat HeartbeatMessage; - mavlinkcom::MavLinkSetMode SetModeMessage; - mavlinkcom::MavLinkStatustext StatusTextMessage; - mavlinkcom::MavLinkHilControls HilControlsMessage; - mavlinkcom::MavLinkHilActuatorControls HilActuatorControlsMessage; - mavlinkcom::MavLinkGpsRawInt MavLinkGpsRawInt; - mavlinkcom::MavLinkCommandLong CommandLongMessage; - mavlinkcom::MavLinkLocalPositionNed MavLinkLocalPositionNed; - - mavlinkcom::MavLinkHilSensor last_sensor_message_; - mavlinkcom::MavLinkDistanceSensor last_distance_message_; - mavlinkcom::MavLinkHilGps last_gps_message_; - - std::mutex mocap_pose_mutex_, heartbeat_mutex_, set_mode_mutex_, status_text_mutex_, last_message_mutex_, telemetry_mutex_; - - //variables required for VehicleApiBase implementation - bool got_first_heartbeat_ = false, is_hil_mode_set_ = false, is_armed_ = false; - bool is_controls_0_1_; //Are motor controls specified in 0..1 or -1..1? - bool send_params_ = false; - std::queue status_messages_; - int hil_state_freq_; - bool actuators_message_supported_ = false; - bool was_reset_ = false; - bool has_home_ = false; - bool is_ready_ = false; - bool has_gps_lock_ = false; - bool lock_step_enabled_ = false; - bool received_actuator_controls_ = false; - std::string is_ready_message_; - Pose mocap_pose_; - std::thread connect_thread_; - bool connecting_ = false; - bool connected_ = false; - common_utils::SmoothingFilter ground_filter_; - double ground_variance_ = 1; - const double GroundTolerance = 0.1; - - // variables for throttling HIL_SENSOR and SYSTEM_TIME messages - uint32_t last_sys_time_ = 0; - unsigned long long sim_time_us_ = 0; - uint64_t last_gps_time_ = 0; - uint64_t last_update_time_ = 0; - uint64_t last_hil_sensor_time_ = 0; - - // variables accumulated for MavLinkTelemetry messages. - uint64_t update_time_ = 0; - uint32_t update_count_ = 0; - uint32_t hil_sensor_count_ = 0; - uint32_t lock_step_resets_ = 0; - uint32_t actuator_delay_ = 0; - std::thread telemetry_thread_; - - //additional variables required for MultirotorApiBase implementation - //this is optional for methods that might not use vehicle commands - std::shared_ptr mav_vehicle_; - float target_height_; - bool is_api_control_enabled_; - PidController thrust_controller_; - common_utils::Timer hil_message_timer_; - common_utils::Timer gcs_message_timer_; - std::shared_ptr log_; - std::string log_file_name_; - World* world_; - - //every time we return status update, we need to check if we have new data - //this is why below two variables are marked as mutable - mutable int state_version_; - mutable mavlinkcom::VehicleState current_state_; -}; + void monitorGroundAltitude() + { + // used to ensure stable altitude before takeoff. + auto position = getPosition(); + auto result = ground_filter_.filter(position.z()); + auto variance = std::get<1>(result); + if (variance >= 0) { // filter returns -1 if we don't have enough data yet. + ground_variance_ = variance; + } + } + + protected: //variables + //TODO: below was made protected from private to support Ardupilot + //implementation but we need to review this and avoid having protected variables + static const int RotorControlsCount = 8; + + const SensorCollection* sensors_; + mutable std::mutex hil_controls_mutex_; + AirSimSettings::MavLinkConnectionInfo connection_info_; + float rotor_controls_[RotorControlsCount]; + bool is_simulation_mode_; + + private: //variables + static const int pixhawkVendorId = 9900; ///< Vendor ID for Pixhawk board (V2 and V1) and PX4 Flow + static const int pixhawkFMUV4ProductId = 18; ///< Product ID for Pixhawk V2 board + static const int pixhawkFMUV2ProductId = 17; ///< Product ID for Pixhawk V2 board + static const int pixhawkFMUV5ProductId = 50; ///< Product ID for Pixhawk V5 board + static const int pixhawkFMUV2OldBootloaderProductId = 22; ///< Product ID for Bootloader on older Pixhawk V2 boards + static const int pixhawkFMUV1ProductId = 16; ///< Product ID for PX4 FMU V1 board + static const int messageReceivedTimeout = 10; ///< Seconds + + std::shared_ptr logviewer_proxy_, logviewer_out_proxy_, qgc_proxy_; + + size_t status_messages_MaxSize = 5000; + + std::shared_ptr hil_node_; + std::shared_ptr connection_; + std::shared_ptr video_server_; + std::shared_ptr mav_vehicle_control_; + + mavlinkcom::MavLinkAttPosMocap MocapPoseMessage; + mavlinkcom::MavLinkHeartbeat HeartbeatMessage; + mavlinkcom::MavLinkSetMode SetModeMessage; + mavlinkcom::MavLinkStatustext StatusTextMessage; + mavlinkcom::MavLinkHilControls HilControlsMessage; + mavlinkcom::MavLinkHilActuatorControls HilActuatorControlsMessage; + mavlinkcom::MavLinkGpsRawInt MavLinkGpsRawInt; + mavlinkcom::MavLinkCommandLong CommandLongMessage; + mavlinkcom::MavLinkLocalPositionNed MavLinkLocalPositionNed; + + mavlinkcom::MavLinkHilSensor last_sensor_message_; + mavlinkcom::MavLinkDistanceSensor last_distance_message_; + mavlinkcom::MavLinkHilGps last_gps_message_; + + std::mutex mocap_pose_mutex_, heartbeat_mutex_, set_mode_mutex_, status_text_mutex_, last_message_mutex_, telemetry_mutex_; + + //variables required for VehicleApiBase implementation + bool got_first_heartbeat_ = false, is_hil_mode_set_ = false, is_armed_ = false; + bool is_controls_0_1_; //Are motor controls specified in 0..1 or -1..1? + bool send_params_ = false; + std::queue status_messages_; + int hil_state_freq_; + bool actuators_message_supported_ = false; + bool was_reset_ = false; + bool has_home_ = false; + bool is_ready_ = false; + bool has_gps_lock_ = false; + bool lock_step_enabled_ = false; + bool received_actuator_controls_ = false; + std::string is_ready_message_; + Pose mocap_pose_; + std::thread connect_thread_; + bool connecting_ = false; + bool connected_ = false; + common_utils::SmoothingFilter ground_filter_; + double ground_variance_ = 1; + const double GroundTolerance = 0.1; + + // variables for throttling HIL_SENSOR and SYSTEM_TIME messages + uint32_t last_sys_time_ = 0; + unsigned long long sim_time_us_ = 0; + uint64_t last_gps_time_ = 0; + uint64_t last_update_time_ = 0; + uint64_t last_hil_sensor_time_ = 0; + + // variables accumulated for MavLinkTelemetry messages. + uint64_t update_time_ = 0; + uint32_t update_count_ = 0; + uint32_t hil_sensor_count_ = 0; + uint32_t lock_step_resets_ = 0; + uint32_t actuator_delay_ = 0; + std::thread telemetry_thread_; + + //additional variables required for MultirotorApiBase implementation + //this is optional for methods that might not use vehicle commands + std::shared_ptr mav_vehicle_; + float target_height_; + bool is_api_control_enabled_; + PidController thrust_controller_; + common_utils::Timer hil_message_timer_; + common_utils::Timer gcs_message_timer_; + std::shared_ptr log_; + std::string log_file_name_; + World* world_; + + //every time we return status update, we need to check if we have new data + //this is why below two variables are marked as mutable + mutable int state_version_; + mutable mavlinkcom::VehicleState current_state_; + }; } } //namespace #endif From 6c747c79d28c39f088a4e56c97f522b8a52cfe16 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Thu, 29 Apr 2021 23:42:20 -0700 Subject: [PATCH 34/37] cr fixes --- MavLinkCom/src/MavLinkMessageBase.cpp | 6 ++-- PythonClient/multirotor/high.py | 52 --------------------------- PythonClient/multirotor/takeoff.py | 34 +++++++++++++++++- 3 files changed, 35 insertions(+), 57 deletions(-) delete mode 100644 PythonClient/multirotor/high.py diff --git a/MavLinkCom/src/MavLinkMessageBase.cpp b/MavLinkCom/src/MavLinkMessageBase.cpp index 8abd846a29..0dbbc143c0 100644 --- a/MavLinkCom/src/MavLinkMessageBase.cpp +++ b/MavLinkCom/src/MavLinkMessageBase.cpp @@ -53,13 +53,11 @@ int MavLinkMessage::update_checksum() } if (len != msglen) { + // mavlink2 supports trimming the payload of trailing zeros so the messages + // are variable length as a result. if (mavlink1) { throw std::runtime_error(Utils::stringf("Message length %d doesn't match expected length%d\n", len, msglen)); } - else { - // mavlink2 supports trimming the payload of trailing zeros so the messages - // are variable length as a result. - } } len = mavlink1 ? msglen : _mav_trim_payload(payload, msglen); this->len = len; diff --git a/PythonClient/multirotor/high.py b/PythonClient/multirotor/high.py deleted file mode 100644 index afdcadff91..0000000000 --- a/PythonClient/multirotor/high.py +++ /dev/null @@ -1,52 +0,0 @@ -import setup_path -import airsim - -import sys -import time - -print("""This script is designed to fly on the streets of the Neighborhood environment -and assumes the unreal position of the drone is [160, -1500, 120].""") - -client = airsim.MultirotorClient() -client.confirmConnection() -client.enableApiControl(True) - -print("arming the drone...") -client.armDisarm(True) - -state = client.getMultirotorState() -if state.landed_state == airsim.LandedState.Landed: - print("taking off...") - client.takeoffAsync().join() -else: - client.hoverAsync().join() - -time.sleep(1) - -state = client.getMultirotorState() -if state.landed_state == airsim.LandedState.Landed: - print("take off failed...") - sys.exit(1) - -# AirSim uses NED coordinates so negative axis is up. -# z of -50 is 50 meters above the original launch point. -z = -50 -print("make sure we are hovering at 50 meters...") -client.moveToZAsync(z, 1).join() - -# see https://github.com/Microsoft/AirSim/wiki/moveOnPath-demo - -# this method is async and we are not waiting for the result since we are passing timeout_sec=0. - -time.sleep(1) - -# come down quickly -z = -7 -client.moveToZAsync(z, 5).join() - -print("landing...") -client.landAsync().join() -print("disarming...") -client.armDisarm(False) -client.enableApiControl(False) -print("done.") diff --git a/PythonClient/multirotor/takeoff.py b/PythonClient/multirotor/takeoff.py index 035f065442..3d16063a4a 100644 --- a/PythonClient/multirotor/takeoff.py +++ b/PythonClient/multirotor/takeoff.py @@ -1,5 +1,15 @@ -import setup_path +import setup_path import airsim +import sys +import time + +# For high speed ascent and descent on PX4 you may need to set these properties: +# param set MPC_Z_VEL_MAX_UP 5 +# param set MPC_Z_VEL_MAX_DN 5 + +z = 5 +if len(sys.argv) > 1: + z = float(sys.argv[1]) client = airsim.MultirotorClient() client.confirmConnection() @@ -14,3 +24,25 @@ else: print("already flying...") client.hoverAsync().join() + +print("make sure we are hovering at {} meters...".format(z)) + +if z > 5: + # AirSim uses NED coordinates so negative axis is up. + # z of -50 is 50 meters above the original launch point. + client.moveToZAsync(-z, 5).join() + client.hoverAsync().join() + time.sleep(5) + +if z > 10: + print("come down quickly to 10 meters...") + z = 10 + client.moveToZAsync(-z, 3).join() + client.hoverAsync().join() + +print("landing...") +client.landAsync().join() +print("disarming...") +client.armDisarm(False) +client.enableApiControl(False) +print("done.") From e434f417df5fcf6d84fb49294adb28de97ef2aa0 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Mon, 3 May 2021 13:16:00 -0700 Subject: [PATCH 35/37] Add info on lockstep and steppable clock. Test with steppable clocka and fix some bugs. --- AirLib/include/common/AirSimSettings.hpp | 2236 +++++++++-------- .../mavlink/MavLinkMultirotorApi.hpp | 34 +- docs/px4_lockstep.md | 40 + docs/px4_setup.md | 4 + docs/px4_sitl.md | 3 + docs/px4_sitl_wsl2.md | 6 +- 6 files changed, 1190 insertions(+), 1133 deletions(-) create mode 100644 docs/px4_lockstep.md diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index 4d685cbe14..fd9126248d 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -4,1311 +4,1313 @@ #ifndef airsim_core_AirSimSettings_hpp #define airsim_core_AirSimSettings_hpp -#include -#include -#include -#include -#include -#include "Settings.hpp" #include "CommonStructs.hpp" -#include "common_utils/Utils.hpp" #include "ImageCaptureBase.hpp" +#include "Settings.hpp" +#include "common_utils/Utils.hpp" #include "sensors/SensorBase.hpp" +#include +#include +#include +#include +#include -namespace msr { namespace airlib { - -struct AirSimSettings +namespace msr +{ +namespace airlib { -private: - typedef common_utils::Utils Utils; - typedef ImageCaptureBase::ImageType ImageType; - -public: //types - static constexpr int kSubwindowCount = 3; //must be >= 3 for now - static constexpr char const * kVehicleTypePX4 = "px4multirotor"; - static constexpr char const * kVehicleTypeArduCopterSolo = "arducoptersolo"; - static constexpr char const * kVehicleTypeSimpleFlight = "simpleflight"; - static constexpr char const * kVehicleTypeArduCopter = "arducopter"; - static constexpr char const * kVehicleTypePhysXCar = "physxcar"; - static constexpr char const * kVehicleTypeArduRover = "ardurover"; - static constexpr char const * kVehicleTypeComputerVision = "computervision"; - - static constexpr char const * kVehicleInertialFrame = "VehicleInertialFrame"; - static constexpr char const * kSensorLocalFrame = "SensorLocalFrame"; - - static constexpr char const * kSimModeTypeMultirotor = "Multirotor"; - static constexpr char const * kSimModeTypeCar = "Car"; - static constexpr char const * kSimModeTypeComputerVision = "ComputerVision"; - - struct SubwindowSetting + + struct AirSimSettings { - int window_index; - ImageType image_type; - bool visible; - std::string camera_name; - std::string vehicle_name; + private: + typedef common_utils::Utils Utils; + typedef ImageCaptureBase::ImageType ImageType; - SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, - bool visible_val = false, const std::string& camera_name_val = "", const std::string& vehicle_name_val = "") - : window_index(window_index_val), image_type(image_type_val), - visible(visible_val), camera_name(camera_name_val), vehicle_name(vehicle_name_val) - { - } - }; + public: //types + static constexpr int kSubwindowCount = 3; //must be >= 3 for now + static constexpr char const* kVehicleTypePX4 = "px4multirotor"; + static constexpr char const* kVehicleTypeArduCopterSolo = "arducoptersolo"; + static constexpr char const* kVehicleTypeSimpleFlight = "simpleflight"; + static constexpr char const* kVehicleTypeArduCopter = "arducopter"; + static constexpr char const* kVehicleTypePhysXCar = "physxcar"; + static constexpr char const* kVehicleTypeArduRover = "ardurover"; + static constexpr char const* kVehicleTypeComputerVision = "computervision"; - struct RecordingSetting - { - bool record_on_move = false; - float record_interval = 0.05f; - std::string folder = ""; - bool enabled = false; + static constexpr char const* kVehicleInertialFrame = "VehicleInertialFrame"; + static constexpr char const* kSensorLocalFrame = "SensorLocalFrame"; - std::map > requests; + static constexpr char const* kSimModeTypeMultirotor = "Multirotor"; + static constexpr char const* kSimModeTypeCar = "Car"; + static constexpr char const* kSimModeTypeComputerVision = "ComputerVision"; - RecordingSetting() + struct SubwindowSetting { - } + int window_index; + ImageType image_type; + bool visible; + std::string camera_name; + std::string vehicle_name; + + SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, + bool visible_val = false, const std::string& camera_name_val = "", const std::string& vehicle_name_val = "") + : window_index(window_index_val), image_type(image_type_val), visible(visible_val), camera_name(camera_name_val), vehicle_name(vehicle_name_val) + { + } + }; - RecordingSetting(bool record_on_move_val, float record_interval_val, const std::string& folder_val, bool enabled_val) - : record_on_move(record_on_move_val), record_interval(record_interval_val), folder(folder_val), - enabled(enabled_val) + struct RecordingSetting { - } - }; + bool record_on_move = false; + float record_interval = 0.05f; + std::string folder = ""; + bool enabled = false; - struct PawnPath - { - std::string pawn_bp; - std::string slippery_mat; - std::string non_slippery_mat; - - PawnPath(const std::string& pawn_bp_val = "", - const std::string& slippery_mat_val = "/AirSim/VehicleAdv/PhysicsMaterials/Slippery.Slippery", - const std::string& non_slippery_mat_val = "/AirSim/VehicleAdv/PhysicsMaterials/NonSlippery.NonSlippery") - : pawn_bp(pawn_bp_val), slippery_mat(slippery_mat_val), non_slippery_mat(non_slippery_mat_val) - { - } - }; + std::map> requests; - struct RCSettings - { - int remote_control_id = -1; - bool allow_api_when_disconnected = false; - }; + RecordingSetting() + { + } - struct Rotation - { - float yaw = 0; - float pitch = 0; - float roll = 0; + RecordingSetting(bool record_on_move_val, float record_interval_val, const std::string& folder_val, bool enabled_val) + : record_on_move(record_on_move_val), record_interval(record_interval_val), folder(folder_val), enabled(enabled_val) + { + } + }; - Rotation() + struct PawnPath { - } + std::string pawn_bp; + std::string slippery_mat; + std::string non_slippery_mat; + + PawnPath(const std::string& pawn_bp_val = "", + const std::string& slippery_mat_val = "/AirSim/VehicleAdv/PhysicsMaterials/Slippery.Slippery", + const std::string& non_slippery_mat_val = "/AirSim/VehicleAdv/PhysicsMaterials/NonSlippery.NonSlippery") + : pawn_bp(pawn_bp_val), slippery_mat(slippery_mat_val), non_slippery_mat(non_slippery_mat_val) + { + } + }; - Rotation(float yaw_val, float pitch_val, float roll_val) - : yaw(yaw_val), pitch(pitch_val), roll(roll_val) + struct RCSettings { - } + int remote_control_id = -1; + bool allow_api_when_disconnected = false; + }; - static Rotation nanRotation() + struct Rotation { - static const Rotation val(Utils::nan(), Utils::nan(), Utils::nan()); - return val; - } - }; + float yaw = 0; + float pitch = 0; + float roll = 0; + Rotation() + { + } - struct GimbalSetting - { - float stabilization = 0; - //bool is_world_frame = false; - Rotation rotation = Rotation::nanRotation(); - }; + Rotation(float yaw_val, float pitch_val, float roll_val) + : yaw(yaw_val), pitch(pitch_val), roll(roll_val) + { + } - struct CaptureSetting - { - //below settings_json are obtained by using Unreal console command (press ~): - // ShowFlag.VisualizeHDR 1. - //to replicate camera settings_json to SceneCapture2D - //TODO: should we use UAirBlueprintLib::GetDisplayGamma()? - static constexpr float kSceneTargetGamma = 1.4f; - - int image_type = 0; - - unsigned int width = 256, height = 144; //960 X 540 - float fov_degrees = Utils::nan(); //90.0f - int auto_exposure_method = -1; //histogram - float auto_exposure_speed = Utils::nan(); // 100.0f; - float auto_exposure_bias = Utils::nan(); // 0; - float auto_exposure_max_brightness = Utils::nan(); // 0.64f; - float auto_exposure_min_brightness = Utils::nan(); // 0.03f; - float auto_exposure_low_percent = Utils::nan(); // 80.0f; - float auto_exposure_high_percent = Utils::nan(); // 98.3f; - float auto_exposure_histogram_log_min = Utils::nan(); // -8; - float auto_exposure_histogram_log_max = Utils::nan(); // 4; - float motion_blur_amount = Utils::nan(); - float target_gamma = Utils::nan(); //1.0f; //This would be reset to kSceneTargetGamma for scene as default - int projection_mode = 0; // ECameraProjectionMode::Perspective - float ortho_width = Utils::nan(); - }; + static Rotation nanRotation() + { + static const Rotation val(Utils::nan(), Utils::nan(), Utils::nan()); + return val; + } + }; - struct NoiseSetting - { - int ImageType = 0; + struct GimbalSetting + { + float stabilization = 0; + //bool is_world_frame = false; + Rotation rotation = Rotation::nanRotation(); + }; - bool Enabled = false; + struct CaptureSetting + { + //below settings_json are obtained by using Unreal console command (press ~): + // ShowFlag.VisualizeHDR 1. + //to replicate camera settings_json to SceneCapture2D + //TODO: should we use UAirBlueprintLib::GetDisplayGamma()? + static constexpr float kSceneTargetGamma = 1.4f; + + int image_type = 0; + + unsigned int width = 256, height = 144; //960 X 540 + float fov_degrees = Utils::nan(); //90.0f + int auto_exposure_method = -1; //histogram + float auto_exposure_speed = Utils::nan(); // 100.0f; + float auto_exposure_bias = Utils::nan(); // 0; + float auto_exposure_max_brightness = Utils::nan(); // 0.64f; + float auto_exposure_min_brightness = Utils::nan(); // 0.03f; + float auto_exposure_low_percent = Utils::nan(); // 80.0f; + float auto_exposure_high_percent = Utils::nan(); // 98.3f; + float auto_exposure_histogram_log_min = Utils::nan(); // -8; + float auto_exposure_histogram_log_max = Utils::nan(); // 4; + float motion_blur_amount = Utils::nan(); + float target_gamma = Utils::nan(); //1.0f; //This would be reset to kSceneTargetGamma for scene as default + int projection_mode = 0; // ECameraProjectionMode::Perspective + float ortho_width = Utils::nan(); + }; - float RandContrib = 0.2f; - float RandSpeed = 100000.0f; - float RandSize = 500.0f; - float RandDensity = 2.0f; + struct NoiseSetting + { + int ImageType = 0; - float HorzWaveContrib = 0.03f; - float HorzWaveStrength = 0.08f; - float HorzWaveVertSize = 1.0f; - float HorzWaveScreenSize = 1.0f; + bool Enabled = false; - float HorzNoiseLinesContrib = 1.0f; - float HorzNoiseLinesDensityY = 0.01f; - float HorzNoiseLinesDensityXY = 0.5f; + float RandContrib = 0.2f; + float RandSpeed = 100000.0f; + float RandSize = 500.0f; + float RandDensity = 2.0f; - float HorzDistortionContrib = 1.0f; - float HorzDistortionStrength = 0.002f; - }; + float HorzWaveContrib = 0.03f; + float HorzWaveStrength = 0.08f; + float HorzWaveVertSize = 1.0f; + float HorzWaveScreenSize = 1.0f; - struct CameraSetting - { - //nan means keep the default values set in components - Vector3r position = VectorMath::nanVector(); - Rotation rotation = Rotation::nanRotation(); + float HorzNoiseLinesContrib = 1.0f; + float HorzNoiseLinesDensityY = 0.01f; + float HorzNoiseLinesDensityXY = 0.5f; - GimbalSetting gimbal; - std::map capture_settings; - std::map noise_settings; + float HorzDistortionContrib = 1.0f; + float HorzDistortionStrength = 0.002f; + }; - CameraSetting() + struct CameraSetting { - initializeCaptureSettings(capture_settings); - initializeNoiseSettings(noise_settings); - } - }; + //nan means keep the default values set in components + Vector3r position = VectorMath::nanVector(); + Rotation rotation = Rotation::nanRotation(); + + GimbalSetting gimbal; + std::map capture_settings; + std::map noise_settings; + + CameraSetting() + { + initializeCaptureSettings(capture_settings); + initializeNoiseSettings(noise_settings); + } + }; - struct CameraDirectorSetting - { - Vector3r position = VectorMath::nanVector(); - Rotation rotation = Rotation::nanRotation(); - float follow_distance = Utils::nan(); - }; + struct CameraDirectorSetting + { + Vector3r position = VectorMath::nanVector(); + Rotation rotation = Rotation::nanRotation(); + float follow_distance = Utils::nan(); + }; - struct SensorSetting - { - SensorBase::SensorType sensor_type; - std::string sensor_name; - bool enabled = true; - Settings settings; // imported json data that needs to be parsed by specific sensors. - }; + struct SensorSetting + { + SensorBase::SensorType sensor_type; + std::string sensor_name; + bool enabled = true; + Settings settings; // imported json data that needs to be parsed by specific sensors. + }; - struct BarometerSetting : SensorSetting - { - }; + struct BarometerSetting : SensorSetting + { + }; - struct ImuSetting : SensorSetting - { - }; + struct ImuSetting : SensorSetting + { + }; - struct GpsSetting : SensorSetting - { - }; + struct GpsSetting : SensorSetting + { + }; - struct MagnetometerSetting : SensorSetting - { - }; + struct MagnetometerSetting : SensorSetting + { + }; - struct DistanceSetting : SensorSetting - { - }; + struct DistanceSetting : SensorSetting + { + }; - struct LidarSetting : SensorSetting - { - }; + struct LidarSetting : SensorSetting + { + }; - struct VehicleSetting - { - //required - std::string vehicle_name; - std::string vehicle_type; - - //optional - std::string default_vehicle_state; - std::string pawn_path; - bool allow_api_always = true; - bool auto_create = true; - bool enable_collision_passthrough = false; - bool enable_trace = false; - bool enable_collisions = true; - bool is_fpv_vehicle = false; - - //nan means use player start - Vector3r position = VectorMath::nanVector(); //in global NED - Rotation rotation = Rotation::nanRotation(); - - std::map cameras; - std::map> sensors; - - RCSettings rc; - }; + struct VehicleSetting + { + //required + std::string vehicle_name; + std::string vehicle_type; + + //optional + std::string default_vehicle_state; + std::string pawn_path; + bool allow_api_always = true; + bool auto_create = true; + bool enable_collision_passthrough = false; + bool enable_trace = false; + bool enable_collisions = true; + bool is_fpv_vehicle = false; + + //nan means use player start + Vector3r position = VectorMath::nanVector(); //in global NED + Rotation rotation = Rotation::nanRotation(); + + std::map cameras; + std::map> sensors; + + RCSettings rc; + }; - struct MavLinkConnectionInfo - { - /* Default values are requires so uninitialized instance doesn't have random values */ - - bool use_serial = true; // false means use UDP or TCP instead - - //Used to connect via HITL: needed only if use_serial = true - std::string serial_port = "*"; - int baud_rate = 115200; - - // Used to connect to drone over UDP: needed only if use_serial = false and use_tcp == false - std::string udp_address = "127.0.0.1"; - int udp_port = 14560; - - // Used to accept connections from drone over TCP: needed only if use_tcp = true - bool use_tcp = false; - int tcp_port = 4560; - - // The PX4 SITL app requires receiving drone commands over a different mavlink channel called - // the "ground control station" (or GCS) channel. - std::string control_ip_address = "127.0.0.1"; - int control_port_local = 14540; - int control_port_remote = 14580; - - // The log viewer can be on a different machine, so you can configure it's ip address and port here. - int logviewer_ip_port = 14388; - int logviewer_ip_sport = 14389; // for logging all messages we send to the vehicle. - std::string logviewer_ip_address = ""; - - // The QGroundControl app can be on a different machine, and AirSim can act as a proxy to forward - // the mavlink stream over to that machine if you configure it's ip address and port here. - int qgc_ip_port = 0; - std::string qgc_ip_address = ""; - - // mavlink vehicle identifiers - uint8_t sim_sysid = 142; - int sim_compid = 42; - uint8_t offboard_sysid = 134; - int offboard_compid = 1; - uint8_t vehicle_sysid = 135; - int vehicle_compid = 1; - - // if you want to select a specific local network adapter so you can reach certain remote machines (e.g. wifi versus ethernet) - // then you will want to change the LocalHostIp accordingly. This default only works when log viewer and QGC are also on the - // same machine. Whatever network you choose it has to be the same one for external - std::string local_host_ip = "127.0.0.1"; - - std::string model = "Generic"; - - std::map params; - std::string logs; - }; + struct MavLinkConnectionInfo + { + /* Default values are requires so uninitialized instance doesn't have random values */ + + bool use_serial = true; // false means use UDP or TCP instead + + //Used to connect via HITL: needed only if use_serial = true + std::string serial_port = "*"; + int baud_rate = 115200; + + // Used to connect to drone over UDP: needed only if use_serial = false and use_tcp == false + std::string udp_address = "127.0.0.1"; + int udp_port = 14560; + + // Used to accept connections from drone over TCP: needed only if use_tcp = true + bool lock_step = true; + bool use_tcp = false; + int tcp_port = 4560; + + // The PX4 SITL app requires receiving drone commands over a different mavlink channel called + // the "ground control station" (or GCS) channel. + std::string control_ip_address = "127.0.0.1"; + int control_port_local = 14540; + int control_port_remote = 14580; + + // The log viewer can be on a different machine, so you can configure it's ip address and port here. + int logviewer_ip_port = 14388; + int logviewer_ip_sport = 14389; // for logging all messages we send to the vehicle. + std::string logviewer_ip_address = ""; + + // The QGroundControl app can be on a different machine, and AirSim can act as a proxy to forward + // the mavlink stream over to that machine if you configure it's ip address and port here. + int qgc_ip_port = 0; + std::string qgc_ip_address = ""; + + // mavlink vehicle identifiers + uint8_t sim_sysid = 142; + int sim_compid = 42; + uint8_t offboard_sysid = 134; + int offboard_compid = 1; + uint8_t vehicle_sysid = 135; + int vehicle_compid = 1; + + // if you want to select a specific local network adapter so you can reach certain remote machines (e.g. wifi versus ethernet) + // then you will want to change the LocalHostIp accordingly. This default only works when log viewer and QGC are also on the + // same machine. Whatever network you choose it has to be the same one for external + std::string local_host_ip = "127.0.0.1"; + + std::string model = "Generic"; + + std::map params; + std::string logs; + }; - struct MavLinkVehicleSetting : public VehicleSetting - { - MavLinkConnectionInfo connection_info; - }; + struct MavLinkVehicleSetting : public VehicleSetting + { + MavLinkConnectionInfo connection_info; + }; - struct SegmentationSetting - { - enum class InitMethodType { - None, CommonObjectsRandomIDs + struct SegmentationSetting + { + enum class InitMethodType + { + None, + CommonObjectsRandomIDs + }; + + enum class MeshNamingMethodType + { + OwnerName, + StaticMeshName + }; + + InitMethodType init_method = InitMethodType::CommonObjectsRandomIDs; + bool override_existing = false; + MeshNamingMethodType mesh_naming_method = MeshNamingMethodType::OwnerName; }; - enum class MeshNamingMethodType { - OwnerName, StaticMeshName + struct TimeOfDaySetting + { + bool enabled = false; + std::string start_datetime = ""; //format: %Y-%m-%d %H:%M:%S + bool is_start_datetime_dst = false; + float celestial_clock_speed = 1; + float update_interval_secs = 60; + bool move_sun = true; }; - InitMethodType init_method = InitMethodType::CommonObjectsRandomIDs; - bool override_existing = false; - MeshNamingMethodType mesh_naming_method = MeshNamingMethodType::OwnerName; - }; + private: //fields + float settings_version_actual; + float settings_version_minimum = 1.2f; + + public: //fields + std::string simmode_name = ""; + std::string level_name = ""; + + std::vector subwindow_settings; + RecordingSetting recording_setting; + SegmentationSetting segmentation_setting; + TimeOfDaySetting tod_setting; + + std::vector warning_messages; + std::vector error_messages; + + bool is_record_ui_visible = false; + int initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME + bool enable_rpc = true; + std::string api_server_address = ""; + int api_port = RpcLibPort; + std::string physics_engine_name = ""; + + std::string clock_type = ""; + float clock_speed = 1.0f; + bool engine_sound = false; + bool log_messages_visible = true; + HomeGeoPoint origin_geopoint{ GeoPoint(47.641468, -122.140165, 122) }; //The geo-coordinate assigned to Unreal coordinate 0,0,0 + std::map pawn_paths; //path for pawn blueprint + std::map> vehicles; + CameraSetting camera_defaults; + CameraDirectorSetting camera_director; + float speed_unit_factor = 1.0f; + std::string speed_unit_label = "m\\s"; + std::map> sensor_defaults; + Vector3r wind = Vector3r::Zero(); + + std::string settings_text_ = ""; + + public: //methods + static AirSimSettings& singleton() + { + static AirSimSettings instance; + return instance; + } - struct TimeOfDaySetting - { - bool enabled = false; - std::string start_datetime = ""; //format: %Y-%m-%d %H:%M:%S - bool is_start_datetime_dst = false; - float celestial_clock_speed = 1; - float update_interval_secs = 60; - bool move_sun = true; - }; + AirSimSettings() + { + initializeSubwindowSettings(subwindow_settings); + initializePawnPaths(pawn_paths); + } -private: //fields - float settings_version_actual; - float settings_version_minimum = 1.2f; - -public: //fields - std::string simmode_name = ""; - std::string level_name = ""; - - std::vector subwindow_settings; - RecordingSetting recording_setting; - SegmentationSetting segmentation_setting; - TimeOfDaySetting tod_setting; - - std::vector warning_messages; - std::vector error_messages; - - bool is_record_ui_visible = false; - int initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME - bool enable_rpc = true; - std::string api_server_address = ""; - int api_port = RpcLibPort; - std::string physics_engine_name = ""; - - std::string clock_type = ""; - float clock_speed = 1.0f; - bool engine_sound = false; - bool log_messages_visible = true; - HomeGeoPoint origin_geopoint{ GeoPoint(47.641468, -122.140165, 122) }; //The geo-coordinate assigned to Unreal coordinate 0,0,0 - std::map pawn_paths; //path for pawn blueprint - std::map> vehicles; - CameraSetting camera_defaults; - CameraDirectorSetting camera_director; - float speed_unit_factor = 1.0f; - std::string speed_unit_label = "m\\s"; - std::map> sensor_defaults; - Vector3r wind = Vector3r::Zero(); - - std::string settings_text_ = ""; - -public: //methods - static AirSimSettings& singleton() - { - static AirSimSettings instance; - return instance; - } + //returns number of warnings + void load(std::function simmode_getter) + { + warning_messages.clear(); + error_messages.clear(); + const Settings& settings_json = Settings::singleton(); + checkSettingsVersion(settings_json); + + loadCoreSimModeSettings(settings_json, simmode_getter); + loadLevelSettings(settings_json); + loadDefaultCameraSetting(settings_json, camera_defaults); + loadCameraDirectorSetting(settings_json, camera_director, simmode_name); + loadSubWindowsSettings(settings_json, subwindow_settings); + loadViewModeSettings(settings_json); + loadSegmentationSetting(settings_json, segmentation_setting); + loadPawnPaths(settings_json, pawn_paths); + loadOtherSettings(settings_json); + loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults); + loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults); + + //this should be done last because it depends on vehicles (and/or their type) we have + loadRecordingSetting(settings_json); + loadClockSettings(settings_json); + } - AirSimSettings() - { - initializeSubwindowSettings(subwindow_settings); - initializePawnPaths(pawn_paths); - } + static void initializeSettings(const std::string& json_settings_text) + { + singleton().settings_text_ = json_settings_text; + Settings& settings_json = Settings::loadJSonString(json_settings_text); + if (!settings_json.isLoadSuccess()) + throw std::invalid_argument("Cannot parse JSON settings_json string."); + } - //returns number of warnings - void load(std::function simmode_getter) - { - warning_messages.clear(); - error_messages.clear(); - const Settings& settings_json = Settings::singleton(); - checkSettingsVersion(settings_json); - - loadCoreSimModeSettings(settings_json, simmode_getter); - loadLevelSettings(settings_json); - loadDefaultCameraSetting(settings_json, camera_defaults); - loadCameraDirectorSetting(settings_json, camera_director, simmode_name); - loadSubWindowsSettings(settings_json, subwindow_settings); - loadViewModeSettings(settings_json); - loadSegmentationSetting(settings_json, segmentation_setting); - loadPawnPaths(settings_json, pawn_paths); - loadOtherSettings(settings_json); - loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults); - loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults); - - //this should be done last because it depends on vehicles (and/or their type) we have - loadRecordingSetting(settings_json); - loadClockSettings(settings_json); - } - - static void initializeSettings(const std::string& json_settings_text) - { - singleton().settings_text_ = json_settings_text; - Settings& settings_json = Settings::loadJSonString(json_settings_text); - if (! settings_json.isLoadSuccess()) - throw std::invalid_argument("Cannot parse JSON settings_json string."); - } + static void createDefaultSettingsFile() + { + initializeSettings("{}"); - static void createDefaultSettingsFile() - { - initializeSettings("{}"); + Settings& settings_json = Settings::singleton(); + //write some settings_json in new file otherwise the string "null" is written if all settings_json are empty + settings_json.setString("SeeDocsAt", "https://github.com/Microsoft/AirSim/blob/master/docs/settings.md"); + settings_json.setDouble("SettingsVersion", 1.2); - Settings& settings_json = Settings::singleton(); - //write some settings_json in new file otherwise the string "null" is written if all settings_json are empty - settings_json.setString("SeeDocsAt", "https://github.com/Microsoft/AirSim/blob/master/docs/settings.md"); - settings_json.setDouble("SettingsVersion", 1.2); + std::string settings_filename = Settings::getUserDirectoryFullPath("settings.json"); + //TODO: there is a crash in Linux due to settings_json.saveJSonString(). Remove this workaround after we only support Unreal 4.17 + //https://answers.unrealengine.com/questions/664905/unreal-crashes-on-two-lines-of-extremely-simple-st.html + settings_json.saveJSonFile(settings_filename); + } - std::string settings_filename = Settings::getUserDirectoryFullPath("settings.json"); - //TODO: there is a crash in Linux due to settings_json.saveJSonString(). Remove this workaround after we only support Unreal 4.17 - //https://answers.unrealengine.com/questions/664905/unreal-crashes-on-two-lines-of-extremely-simple-st.html - settings_json.saveJSonFile(settings_filename); - } + // This is for the case when a new vehicle is made on the fly, at runtime + void addVehicleSetting(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = "") + { + auto vehicle_setting = std::unique_ptr(new VehicleSetting()); - // This is for the case when a new vehicle is made on the fly, at runtime - void addVehicleSetting(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path="") - { - auto vehicle_setting = std::unique_ptr(new VehicleSetting()); + vehicle_setting->vehicle_name = vehicle_name; + vehicle_setting->vehicle_type = vehicle_type; + vehicle_setting->position = pose.position; + vehicle_setting->pawn_path = pawn_path; - vehicle_setting->vehicle_name = vehicle_name; - vehicle_setting->vehicle_type = vehicle_type; - vehicle_setting->position = pose.position; - vehicle_setting->pawn_path = pawn_path; + VectorMath::toEulerianAngle(pose.orientation, vehicle_setting->rotation.pitch, vehicle_setting->rotation.roll, vehicle_setting->rotation.yaw); - VectorMath::toEulerianAngle(pose.orientation, vehicle_setting->rotation.pitch, - vehicle_setting->rotation.roll, vehicle_setting->rotation.yaw); + vehicles[vehicle_name] = std::move(vehicle_setting); + } - vehicles[vehicle_name] = std::move(vehicle_setting); - } + const VehicleSetting* getVehicleSetting(const std::string& vehicle_name) const + { + auto it = vehicles.find(vehicle_name); + if (it == vehicles.end()) + // pre-existing flying pawns in Unreal Engine don't have name 'SimpleFlight' + it = vehicles.find("SimpleFlight"); + return it->second.get(); + } - const VehicleSetting* getVehicleSetting(const std::string& vehicle_name) const - { - auto it = vehicles.find(vehicle_name); - if (it == vehicles.end()) - // pre-existing flying pawns in Unreal Engine don't have name 'SimpleFlight' - it = vehicles.find("SimpleFlight"); - return it->second.get(); - } - - static Vector3r createVectorSetting(const Settings& settings_json, const Vector3r& default_vec) - { - return Vector3r(settings_json.getFloat("X", default_vec.x()), - settings_json.getFloat("Y", default_vec.y()), - settings_json.getFloat("Z", default_vec.z())); - } - static Rotation createRotationSetting(const Settings& settings_json, const Rotation& default_rot) - { - return Rotation(settings_json.getFloat("Yaw", default_rot.yaw), - settings_json.getFloat("Pitch", default_rot.pitch), - settings_json.getFloat("Roll", default_rot.roll)); - } + static Vector3r createVectorSetting(const Settings& settings_json, const Vector3r& default_vec) + { + return Vector3r(settings_json.getFloat("X", default_vec.x()), + settings_json.getFloat("Y", default_vec.y()), + settings_json.getFloat("Z", default_vec.z())); + } + static Rotation createRotationSetting(const Settings& settings_json, const Rotation& default_rot) + { + return Rotation(settings_json.getFloat("Yaw", default_rot.yaw), + settings_json.getFloat("Pitch", default_rot.pitch), + settings_json.getFloat("Roll", default_rot.roll)); + } -private: - void checkSettingsVersion(const Settings& settings_json) - { - bool has_default_settings = hasDefaultSettings(settings_json, settings_version_actual); - bool upgrade_required = settings_version_actual < settings_version_minimum; - if (upgrade_required) { - bool auto_upgrade = false; - - //if we have default setting file not modified by user then we will - //just auto-upgrade it - if (has_default_settings) { - auto_upgrade = true; - } - else { - //check if auto-upgrade is possible - if (settings_version_actual == 1) { - const std::vector all_changed_keys = { - "AdditionalCameras", "CaptureSettings", "NoiseSettings", - "UsageScenario", "SimpleFlight", "PX4" - }; - std::stringstream detected_keys_ss; - for (const auto& changed_key : all_changed_keys) { - if (settings_json.hasKey(changed_key)) - detected_keys_ss << changed_key << ","; - } - std::string detected_keys = detected_keys_ss.str(); - if (detected_keys.length()) { - std::string error_message = - "You are using newer version of AirSim with older version of settings.json. " - "You can either delete your settings.json and restart AirSim or use the upgrade " - "instructions at https://git.io/vjefh. \n\n" - "Following keys in your settings.json needs updating: " - ; - - error_messages.push_back(error_message + detected_keys); + private: + void checkSettingsVersion(const Settings& settings_json) + { + bool has_default_settings = hasDefaultSettings(settings_json, settings_version_actual); + bool upgrade_required = settings_version_actual < settings_version_minimum; + if (upgrade_required) { + bool auto_upgrade = false; + + //if we have default setting file not modified by user then we will + //just auto-upgrade it + if (has_default_settings) { + auto_upgrade = true; + } + else { + //check if auto-upgrade is possible + if (settings_version_actual == 1) { + const std::vector all_changed_keys = { + "AdditionalCameras", "CaptureSettings", "NoiseSettings", "UsageScenario", "SimpleFlight", "PX4" + }; + std::stringstream detected_keys_ss; + for (const auto& changed_key : all_changed_keys) { + if (settings_json.hasKey(changed_key)) + detected_keys_ss << changed_key << ","; + } + std::string detected_keys = detected_keys_ss.str(); + if (detected_keys.length()) { + std::string error_message = + "You are using newer version of AirSim with older version of settings.json. " + "You can either delete your settings.json and restart AirSim or use the upgrade " + "instructions at https://git.io/vjefh. \n\n" + "Following keys in your settings.json needs updating: "; + + error_messages.push_back(error_message + detected_keys); + } + else + auto_upgrade = true; } else auto_upgrade = true; } - else - auto_upgrade = true; - } - if (auto_upgrade) { - warning_messages.push_back( - "You are using newer version of AirSim with older version of settings.json. " - "You should delete your settings.json file and restart AirSim."); + if (auto_upgrade) { + warning_messages.push_back( + "You are using newer version of AirSim with older version of settings.json. " + "You should delete your settings.json file and restart AirSim."); + } } + //else no action necessary } - //else no action necessary - } - bool hasDefaultSettings(const Settings& settings_json, float& version) - { - //if empty settings file - bool has_default = settings_json.size() == 0; + bool hasDefaultSettings(const Settings& settings_json, float& version) + { + //if empty settings file + bool has_default = settings_json.size() == 0; - bool has_docs = settings_json.getString("SeeDocsAt", "") != "" - || settings_json.getString("see_docs_at", "") != ""; - //we had spelling mistake so we are currently supporting SettingsVersion or SettingdVersion :( - version = settings_json.getFloat("SettingsVersion", settings_json.getFloat("SettingdVersion", 0)); + bool has_docs = settings_json.getString("SeeDocsAt", "") != "" || settings_json.getString("see_docs_at", "") != ""; + //we had spelling mistake so we are currently supporting SettingsVersion or SettingdVersion :( + version = settings_json.getFloat("SettingsVersion", settings_json.getFloat("SettingdVersion", 0)); - //If we have pre-V1 settings and only element is docs link - has_default |= settings_json.size() == 1 && has_docs; + //If we have pre-V1 settings and only element is docs link + has_default |= settings_json.size() == 1 && has_docs; - //if we have V1 settings and only elements are docs link and version - has_default |= settings_json.size() == 2 && has_docs && version > 0; + //if we have V1 settings and only elements are docs link and version + has_default |= settings_json.size() == 2 && has_docs && version > 0; - return has_default; - } + return has_default; + } - void loadCoreSimModeSettings(const Settings& settings_json, std::function simmode_getter) - { - //get the simmode from user if not specified - simmode_name = settings_json.getString("SimMode", ""); - if (simmode_name == "") { - if (simmode_getter) - simmode_name = simmode_getter(); - else - throw std::invalid_argument("simmode_name is not expected empty in SimModeBase"); + void loadCoreSimModeSettings(const Settings& settings_json, std::function simmode_getter) + { + //get the simmode from user if not specified + simmode_name = settings_json.getString("SimMode", ""); + if (simmode_name == "") { + if (simmode_getter) + simmode_name = simmode_getter(); + else + throw std::invalid_argument("simmode_name is not expected empty in SimModeBase"); + } + + physics_engine_name = settings_json.getString("PhysicsEngineName", ""); + if (physics_engine_name == "") { + if (simmode_name == kSimModeTypeMultirotor) + physics_engine_name = "FastPhysicsEngine"; + else + physics_engine_name = "PhysX"; //this value is only informational for now + } } - physics_engine_name = settings_json.getString("PhysicsEngineName", ""); - if (physics_engine_name == "") { - if (simmode_name == kSimModeTypeMultirotor) - physics_engine_name = "FastPhysicsEngine"; - else - physics_engine_name = "PhysX"; //this value is only informational for now + void loadLevelSettings(const Settings& settings_json) + { + level_name = settings_json.getString("Default Environment", ""); } - } - - void loadLevelSettings(const Settings& settings_json) - { - level_name = settings_json.getString("Default Environment", ""); - } - void loadViewModeSettings(const Settings& settings_json) - { - std::string view_mode_string = settings_json.getString("ViewMode", ""); + void loadViewModeSettings(const Settings& settings_json) + { + std::string view_mode_string = settings_json.getString("ViewMode", ""); + + if (view_mode_string == "") { + if (simmode_name == kSimModeTypeMultirotor) + view_mode_string = "FlyWithMe"; + else if (simmode_name == kSimModeTypeComputerVision) + view_mode_string = "Fpv"; + else + view_mode_string = "SpringArmChase"; + } - if (view_mode_string == "") { - if (simmode_name == kSimModeTypeMultirotor) - view_mode_string = "FlyWithMe"; - else if (simmode_name == kSimModeTypeComputerVision) - view_mode_string = "Fpv"; + if (view_mode_string == "Fpv") + initial_view_mode = 0; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FPV; + else if (view_mode_string == "GroundObserver") + initial_view_mode = 1; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_GROUND_OBSERVER; + else if (view_mode_string == "FlyWithMe") + initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME; + else if (view_mode_string == "Manual") + initial_view_mode = 3; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_MANUAL; + else if (view_mode_string == "SpringArmChase") + initial_view_mode = 4; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_SPRINGARM_CHASE; + else if (view_mode_string == "Backup") + initial_view_mode = 5; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_BACKUP; + else if (view_mode_string == "NoDisplay") + initial_view_mode = 6; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_NODISPLAY; + else if (view_mode_string == "Front") + initial_view_mode = 7; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_FRONT; else - view_mode_string = "SpringArmChase"; + error_messages.push_back("ViewMode setting is not recognized: " + view_mode_string); } - if (view_mode_string == "Fpv") - initial_view_mode = 0; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FPV; - else if (view_mode_string == "GroundObserver") - initial_view_mode = 1; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_GROUND_OBSERVER; - else if (view_mode_string == "FlyWithMe") - initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME; - else if (view_mode_string == "Manual") - initial_view_mode = 3; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_MANUAL; - else if (view_mode_string == "SpringArmChase") - initial_view_mode = 4; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_SPRINGARM_CHASE; - else if (view_mode_string == "Backup") - initial_view_mode = 5; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_BACKUP; - else if (view_mode_string == "NoDisplay") - initial_view_mode = 6; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_NODISPLAY; - else if (view_mode_string == "Front") - initial_view_mode = 7; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_FRONT; - else - error_messages.push_back("ViewMode setting is not recognized: " + view_mode_string); - } - - static void loadRCSetting(const std::string& simmode_name, const Settings& settings_json, RCSettings& rc_setting) - { - Settings rc_json; - if (settings_json.getChild("RC", rc_json)) { - rc_setting.remote_control_id = rc_json.getInt("RemoteControlID", - simmode_name == kSimModeTypeMultirotor ? 0 : -1); - rc_setting.allow_api_when_disconnected = rc_json.getBool("AllowAPIWhenDisconnected", - rc_setting.allow_api_when_disconnected); + static void loadRCSetting(const std::string& simmode_name, const Settings& settings_json, RCSettings& rc_setting) + { + Settings rc_json; + if (settings_json.getChild("RC", rc_json)) { + rc_setting.remote_control_id = rc_json.getInt("RemoteControlID", + simmode_name == kSimModeTypeMultirotor ? 0 : -1); + rc_setting.allow_api_when_disconnected = rc_json.getBool("AllowAPIWhenDisconnected", + rc_setting.allow_api_when_disconnected); + } } - } - static std::string getCameraName(const Settings& settings_json) - { - return settings_json.getString("CameraName", - //TODO: below exist only due to legacy reason and can be replaced by "" in future - std::to_string(settings_json.getInt("CameraID", 0))); - } + static std::string getCameraName(const Settings& settings_json) + { + return settings_json.getString("CameraName", + //TODO: below exist only due to legacy reason and can be replaced by "" in future + std::to_string(settings_json.getInt("CameraID", 0))); + } - void loadDefaultRecordingSettings() - { - recording_setting.requests.clear(); - // Add Scene image for each vehicle - for (const auto& vehicle : vehicles) { - recording_setting.requests[vehicle.first].push_back(ImageCaptureBase::ImageRequest( - "", ImageType::Scene, false, true)); + void loadDefaultRecordingSettings() + { + recording_setting.requests.clear(); + // Add Scene image for each vehicle + for (const auto& vehicle : vehicles) { + recording_setting.requests[vehicle.first].push_back(ImageCaptureBase::ImageRequest( + "", ImageType::Scene, false, true)); + } } - } - void loadRecordingSetting(const Settings& settings_json) - { - loadDefaultRecordingSettings(); - - Settings recording_json; - if (settings_json.getChild("Recording", recording_json)) { - recording_setting.record_on_move = recording_json.getBool("RecordOnMove", recording_setting.record_on_move); - recording_setting.record_interval = recording_json.getFloat("RecordInterval", recording_setting.record_interval); - recording_setting.folder = recording_json.getString("Folder", recording_setting.folder); - recording_setting.enabled = recording_json.getBool("Enabled", recording_setting.enabled); - - Settings req_cameras_settings; - if (recording_json.getChild("Cameras", req_cameras_settings)) { - // If 'Cameras' field is present, clear defaults - recording_setting.requests.clear(); - // Get name of the default vehicle to be used if "VehicleName" isn't specified - // Map contains a default vehicle if vehicles haven't been specified - std::string default_vehicle_name = vehicles.begin()->first; - - for (size_t child_index = 0; child_index < req_cameras_settings.size(); ++child_index) { - Settings req_camera_settings; - - if (req_cameras_settings.getChild(child_index, req_camera_settings)) { - std::string camera_name = getCameraName(req_camera_settings); - ImageType image_type = Utils::toEnum( - req_camera_settings.getInt("ImageType", 0)); - bool compress = req_camera_settings.getBool("Compress", true); - bool pixels_as_float = req_camera_settings.getBool("PixelsAsFloat", false); - std::string vehicle_name = req_camera_settings.getString("VehicleName", default_vehicle_name); - - recording_setting.requests[vehicle_name].push_back(ImageCaptureBase::ImageRequest( - camera_name, image_type, pixels_as_float, compress)); + void loadRecordingSetting(const Settings& settings_json) + { + loadDefaultRecordingSettings(); + + Settings recording_json; + if (settings_json.getChild("Recording", recording_json)) { + recording_setting.record_on_move = recording_json.getBool("RecordOnMove", recording_setting.record_on_move); + recording_setting.record_interval = recording_json.getFloat("RecordInterval", recording_setting.record_interval); + recording_setting.folder = recording_json.getString("Folder", recording_setting.folder); + recording_setting.enabled = recording_json.getBool("Enabled", recording_setting.enabled); + + Settings req_cameras_settings; + if (recording_json.getChild("Cameras", req_cameras_settings)) { + // If 'Cameras' field is present, clear defaults + recording_setting.requests.clear(); + // Get name of the default vehicle to be used if "VehicleName" isn't specified + // Map contains a default vehicle if vehicles haven't been specified + std::string default_vehicle_name = vehicles.begin()->first; + + for (size_t child_index = 0; child_index < req_cameras_settings.size(); ++child_index) { + Settings req_camera_settings; + + if (req_cameras_settings.getChild(child_index, req_camera_settings)) { + std::string camera_name = getCameraName(req_camera_settings); + ImageType image_type = Utils::toEnum( + req_camera_settings.getInt("ImageType", 0)); + bool compress = req_camera_settings.getBool("Compress", true); + bool pixels_as_float = req_camera_settings.getBool("PixelsAsFloat", false); + std::string vehicle_name = req_camera_settings.getString("VehicleName", default_vehicle_name); + + recording_setting.requests[vehicle_name].push_back(ImageCaptureBase::ImageRequest( + camera_name, image_type, pixels_as_float, compress)); + } } } } } - } - static void initializeCaptureSettings(std::map& capture_settings) - { - capture_settings.clear(); - for (int i = -1; i < Utils::toNumeric(ImageType::Count); ++i) { - capture_settings[i] = CaptureSetting(); + static void initializeCaptureSettings(std::map& capture_settings) + { + capture_settings.clear(); + for (int i = -1; i < Utils::toNumeric(ImageType::Count); ++i) { + capture_settings[i] = CaptureSetting(); + } + capture_settings.at(Utils::toNumeric(ImageType::Scene)).target_gamma = CaptureSetting::kSceneTargetGamma; } - capture_settings.at(Utils::toNumeric(ImageType::Scene)).target_gamma = CaptureSetting::kSceneTargetGamma; - } - static void loadCaptureSettings(const Settings& settings_json, std::map& capture_settings) - { - initializeCaptureSettings(capture_settings); - - Settings json_parent; - if (settings_json.getChild("CaptureSettings", json_parent)) { - for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) { - Settings json_settings_child; - if (json_parent.getChild(child_index, json_settings_child)) { - CaptureSetting capture_setting; - createCaptureSettings(json_settings_child, capture_setting); - capture_settings[capture_setting.image_type] = capture_setting; + static void loadCaptureSettings(const Settings& settings_json, std::map& capture_settings) + { + initializeCaptureSettings(capture_settings); + + Settings json_parent; + if (settings_json.getChild("CaptureSettings", json_parent)) { + for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) { + Settings json_settings_child; + if (json_parent.getChild(child_index, json_settings_child)) { + CaptureSetting capture_setting; + createCaptureSettings(json_settings_child, capture_setting); + capture_settings[capture_setting.image_type] = capture_setting; + } } } } - } - static std::unique_ptr createMavLinkVehicleSetting(const Settings& settings_json) - { - //these settings_json are expected in same section, not in another child - std::unique_ptr vehicle_setting_p = std::unique_ptr(new MavLinkVehicleSetting()); - MavLinkVehicleSetting* vehicle_setting = static_cast(vehicle_setting_p.get()); + static std::unique_ptr createMavLinkVehicleSetting(const Settings& settings_json) + { + //these settings_json are expected in same section, not in another child + std::unique_ptr vehicle_setting_p = std::unique_ptr(new MavLinkVehicleSetting()); + MavLinkVehicleSetting* vehicle_setting = static_cast(vehicle_setting_p.get()); - //TODO: we should be selecting remote if available else keyboard - //currently keyboard is not supported so use rc as default - vehicle_setting->rc.remote_control_id = 0; + //TODO: we should be selecting remote if available else keyboard + //currently keyboard is not supported so use rc as default + vehicle_setting->rc.remote_control_id = 0; - MavLinkConnectionInfo &connection_info = vehicle_setting->connection_info; - connection_info.sim_sysid = static_cast(settings_json.getInt("SimSysID", connection_info.sim_sysid)); - connection_info.sim_compid = settings_json.getInt("SimCompID", connection_info.sim_compid); + MavLinkConnectionInfo& connection_info = vehicle_setting->connection_info; + connection_info.sim_sysid = static_cast(settings_json.getInt("SimSysID", connection_info.sim_sysid)); + connection_info.sim_compid = settings_json.getInt("SimCompID", connection_info.sim_compid); - connection_info.vehicle_sysid = static_cast(settings_json.getInt("VehicleSysID", connection_info.vehicle_sysid)); - connection_info.vehicle_compid = settings_json.getInt("VehicleCompID", connection_info.vehicle_compid); + connection_info.vehicle_sysid = static_cast(settings_json.getInt("VehicleSysID", connection_info.vehicle_sysid)); + connection_info.vehicle_compid = settings_json.getInt("VehicleCompID", connection_info.vehicle_compid); - connection_info.offboard_sysid = static_cast(settings_json.getInt("OffboardSysID", connection_info.offboard_sysid)); - connection_info.offboard_compid = settings_json.getInt("OffboardCompID", connection_info.offboard_compid); + connection_info.offboard_sysid = static_cast(settings_json.getInt("OffboardSysID", connection_info.offboard_sysid)); + connection_info.offboard_compid = settings_json.getInt("OffboardCompID", connection_info.offboard_compid); - connection_info.logviewer_ip_address = settings_json.getString("LogViewerHostIp", connection_info.logviewer_ip_address); - connection_info.logviewer_ip_port = settings_json.getInt("LogViewerPort", connection_info.logviewer_ip_port); - connection_info.logviewer_ip_sport = settings_json.getInt("LogViewerSendPort", connection_info.logviewer_ip_sport); + connection_info.logviewer_ip_address = settings_json.getString("LogViewerHostIp", connection_info.logviewer_ip_address); + connection_info.logviewer_ip_port = settings_json.getInt("LogViewerPort", connection_info.logviewer_ip_port); + connection_info.logviewer_ip_sport = settings_json.getInt("LogViewerSendPort", connection_info.logviewer_ip_sport); - connection_info.qgc_ip_address = settings_json.getString("QgcHostIp", connection_info.qgc_ip_address); - connection_info.qgc_ip_port = settings_json.getInt("QgcPort", connection_info.qgc_ip_port); + connection_info.qgc_ip_address = settings_json.getString("QgcHostIp", connection_info.qgc_ip_address); + connection_info.qgc_ip_port = settings_json.getInt("QgcPort", connection_info.qgc_ip_port); - connection_info.control_ip_address = settings_json.getString("ControlIp", connection_info.control_ip_address); - connection_info.control_port_local = settings_json.getInt("ControlPort", connection_info.control_port_local); // legacy - connection_info.control_port_local = settings_json.getInt("ControlPortLocal", connection_info.control_port_local); - connection_info.control_port_remote = settings_json.getInt("ControlPortRemote", connection_info.control_port_remote); + connection_info.control_ip_address = settings_json.getString("ControlIp", connection_info.control_ip_address); + connection_info.control_port_local = settings_json.getInt("ControlPort", connection_info.control_port_local); // legacy + connection_info.control_port_local = settings_json.getInt("ControlPortLocal", connection_info.control_port_local); + connection_info.control_port_remote = settings_json.getInt("ControlPortRemote", connection_info.control_port_remote); - std::string sitlip = settings_json.getString("SitlIp", connection_info.control_ip_address); - if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0) { - // backwards compat - connection_info.control_ip_address = sitlip; - } - if (settings_json.hasKey("SitlPort")) { - // backwards compat - connection_info.control_port_local = settings_json.getInt("SitlPort", connection_info.control_port_local); - } + std::string sitlip = settings_json.getString("SitlIp", connection_info.control_ip_address); + if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0) { + // backwards compat + connection_info.control_ip_address = sitlip; + } + if (settings_json.hasKey("SitlPort")) { + // backwards compat + connection_info.control_port_local = settings_json.getInt("SitlPort", connection_info.control_port_local); + } - connection_info.local_host_ip = settings_json.getString("LocalHostIp", connection_info.local_host_ip); - - connection_info.use_serial = settings_json.getBool("UseSerial", connection_info.use_serial); - connection_info.udp_address = settings_json.getString("UdpIp", connection_info.udp_address); - connection_info.udp_port = settings_json.getInt("UdpPort", connection_info.udp_port); - connection_info.use_tcp = settings_json.getBool("UseTcp", connection_info.use_tcp); - connection_info.tcp_port = settings_json.getInt("TcpPort", connection_info.tcp_port); - connection_info.serial_port = settings_json.getString("SerialPort", connection_info.serial_port); - connection_info.baud_rate = settings_json.getInt("SerialBaudRate", connection_info.baud_rate); - connection_info.model = settings_json.getString("Model", connection_info.model); - connection_info.logs = settings_json.getString("Logs", connection_info.logs); - - Settings params; - if (settings_json.getChild("Parameters", params)) { - std::vector keys; - params.getChildNames(keys); - for (auto key: keys) { - connection_info.params[key] = params.getFloat(key, 0); + connection_info.local_host_ip = settings_json.getString("LocalHostIp", connection_info.local_host_ip); + + connection_info.use_serial = settings_json.getBool("UseSerial", connection_info.use_serial); + connection_info.udp_address = settings_json.getString("UdpIp", connection_info.udp_address); + connection_info.udp_port = settings_json.getInt("UdpPort", connection_info.udp_port); + connection_info.use_tcp = settings_json.getBool("UseTcp", connection_info.use_tcp); + connection_info.lock_step = settings_json.getBool("LockStep", connection_info.lock_step); + connection_info.tcp_port = settings_json.getInt("TcpPort", connection_info.tcp_port); + connection_info.serial_port = settings_json.getString("SerialPort", connection_info.serial_port); + connection_info.baud_rate = settings_json.getInt("SerialBaudRate", connection_info.baud_rate); + connection_info.model = settings_json.getString("Model", connection_info.model); + connection_info.logs = settings_json.getString("Logs", connection_info.logs); + + Settings params; + if (settings_json.getChild("Parameters", params)) { + std::vector keys; + params.getChildNames(keys); + for (auto key : keys) { + connection_info.params[key] = params.getFloat(key, 0); + } } + + return vehicle_setting_p; } - return vehicle_setting_p; - } + static std::unique_ptr createVehicleSetting(const std::string& simmode_name, const Settings& settings_json, + const std::string vehicle_name, + std::map>& sensor_defaults) + { + auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", "")); - static std::unique_ptr createVehicleSetting(const std::string& simmode_name, const Settings& settings_json, - const std::string vehicle_name, - std::map>& sensor_defaults) - { - auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", "")); - - std::unique_ptr vehicle_setting; - if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypeArduCopterSolo - || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeArduRover) - vehicle_setting = createMavLinkVehicleSetting(settings_json); - //for everything else we don't need derived class yet - else { - vehicle_setting = std::unique_ptr(new VehicleSetting()); - if (vehicle_type == kVehicleTypeSimpleFlight) { - //TODO: we should be selecting remote if available else keyboard - //currently keyboard is not supported so use rc as default - vehicle_setting->rc.remote_control_id = 0; + std::unique_ptr vehicle_setting; + if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypeArduCopterSolo || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeArduRover) + vehicle_setting = createMavLinkVehicleSetting(settings_json); + //for everything else we don't need derived class yet + else { + vehicle_setting = std::unique_ptr(new VehicleSetting()); + if (vehicle_type == kVehicleTypeSimpleFlight) { + //TODO: we should be selecting remote if available else keyboard + //currently keyboard is not supported so use rc as default + vehicle_setting->rc.remote_control_id = 0; + } } + vehicle_setting->vehicle_name = vehicle_name; + + //required settings_json + vehicle_setting->vehicle_type = vehicle_type; + + //optional settings_json + vehicle_setting->pawn_path = settings_json.getString("PawnPath", ""); + vehicle_setting->default_vehicle_state = settings_json.getString("DefaultVehicleState", ""); + vehicle_setting->allow_api_always = settings_json.getBool("AllowAPIAlways", + vehicle_setting->allow_api_always); + vehicle_setting->auto_create = settings_json.getBool("AutoCreate", + vehicle_setting->auto_create); + vehicle_setting->enable_collision_passthrough = settings_json.getBool("EnableCollisionPassthrogh", + vehicle_setting->enable_collision_passthrough); + vehicle_setting->enable_trace = settings_json.getBool("EnableTrace", + vehicle_setting->enable_trace); + vehicle_setting->enable_collisions = settings_json.getBool("EnableCollisions", + vehicle_setting->enable_collisions); + vehicle_setting->is_fpv_vehicle = settings_json.getBool("IsFpvVehicle", + vehicle_setting->is_fpv_vehicle); + + loadRCSetting(simmode_name, settings_json, vehicle_setting->rc); + + vehicle_setting->position = createVectorSetting(settings_json, vehicle_setting->position); + vehicle_setting->rotation = createRotationSetting(settings_json, vehicle_setting->rotation); + + loadCameraSettings(settings_json, vehicle_setting->cameras); + loadSensorSettings(settings_json, "Sensors", vehicle_setting->sensors, sensor_defaults); + + return vehicle_setting; } - vehicle_setting->vehicle_name = vehicle_name; - - //required settings_json - vehicle_setting->vehicle_type = vehicle_type; - - //optional settings_json - vehicle_setting->pawn_path = settings_json.getString("PawnPath", ""); - vehicle_setting->default_vehicle_state = settings_json.getString("DefaultVehicleState", ""); - vehicle_setting->allow_api_always = settings_json.getBool("AllowAPIAlways", - vehicle_setting->allow_api_always); - vehicle_setting->auto_create = settings_json.getBool("AutoCreate", - vehicle_setting->auto_create); - vehicle_setting->enable_collision_passthrough = settings_json.getBool("EnableCollisionPassthrogh", - vehicle_setting->enable_collision_passthrough); - vehicle_setting->enable_trace = settings_json.getBool("EnableTrace", - vehicle_setting->enable_trace); - vehicle_setting->enable_collisions = settings_json.getBool("EnableCollisions", - vehicle_setting->enable_collisions); - vehicle_setting->is_fpv_vehicle = settings_json.getBool("IsFpvVehicle", - vehicle_setting->is_fpv_vehicle); - - loadRCSetting(simmode_name, settings_json, vehicle_setting->rc); - - vehicle_setting->position = createVectorSetting(settings_json, vehicle_setting->position); - vehicle_setting->rotation = createRotationSetting(settings_json, vehicle_setting->rotation); - - loadCameraSettings(settings_json, vehicle_setting->cameras); - loadSensorSettings(settings_json, "Sensors", vehicle_setting->sensors, sensor_defaults); - - return vehicle_setting; - } - - static void initializeVehicleSettings(const std::string &simmode_name, std::map>& vehicles) - { - vehicles.clear(); - - //NOTE: Do not set defaults for vehicle type here. If you do then make sure - //to sync code in createVehicleSetting() as well. - if (simmode_name == kSimModeTypeMultirotor) { - // create simple flight as default multirotor - auto simple_flight_setting = std::unique_ptr(new VehicleSetting()); - simple_flight_setting->vehicle_name = "SimpleFlight"; - simple_flight_setting->vehicle_type = kVehicleTypeSimpleFlight; - // TODO: we should be selecting remote if available else keyboard - // currently keyboard is not supported so use rc as default - simple_flight_setting->rc.remote_control_id = 0; - vehicles[simple_flight_setting->vehicle_name] = std::move(simple_flight_setting); - } - else if (simmode_name == kSimModeTypeCar) { - // create PhysX as default car vehicle - auto physx_car_setting = std::unique_ptr(new VehicleSetting()); - physx_car_setting->vehicle_name = "PhysXCar"; - physx_car_setting->vehicle_type = kVehicleTypePhysXCar; - vehicles[physx_car_setting->vehicle_name] = std::move(physx_car_setting); - } - else if (simmode_name == kSimModeTypeComputerVision) { - // create default computer vision vehicle - auto cv_setting = std::unique_ptr(new VehicleSetting()); - cv_setting->vehicle_name = "ComputerVision"; - cv_setting->vehicle_type = kVehicleTypeComputerVision; - vehicles[cv_setting->vehicle_name] = std::move(cv_setting); - } - else { - throw std::invalid_argument(Utils::stringf( - "Unknown SimMode: %s, failed to set default vehicle settings", simmode_name.c_str()).c_str()); + + static void initializeVehicleSettings(const std::string& simmode_name, std::map>& vehicles) + { + vehicles.clear(); + + //NOTE: Do not set defaults for vehicle type here. If you do then make sure + //to sync code in createVehicleSetting() as well. + if (simmode_name == kSimModeTypeMultirotor) { + // create simple flight as default multirotor + auto simple_flight_setting = std::unique_ptr(new VehicleSetting()); + simple_flight_setting->vehicle_name = "SimpleFlight"; + simple_flight_setting->vehicle_type = kVehicleTypeSimpleFlight; + // TODO: we should be selecting remote if available else keyboard + // currently keyboard is not supported so use rc as default + simple_flight_setting->rc.remote_control_id = 0; + vehicles[simple_flight_setting->vehicle_name] = std::move(simple_flight_setting); + } + else if (simmode_name == kSimModeTypeCar) { + // create PhysX as default car vehicle + auto physx_car_setting = std::unique_ptr(new VehicleSetting()); + physx_car_setting->vehicle_name = "PhysXCar"; + physx_car_setting->vehicle_type = kVehicleTypePhysXCar; + vehicles[physx_car_setting->vehicle_name] = std::move(physx_car_setting); + } + else if (simmode_name == kSimModeTypeComputerVision) { + // create default computer vision vehicle + auto cv_setting = std::unique_ptr(new VehicleSetting()); + cv_setting->vehicle_name = "ComputerVision"; + cv_setting->vehicle_type = kVehicleTypeComputerVision; + vehicles[cv_setting->vehicle_name] = std::move(cv_setting); + } + else { + throw std::invalid_argument(Utils::stringf( + "Unknown SimMode: %s, failed to set default vehicle settings", simmode_name.c_str()) + .c_str()); + } } - } - static void loadVehicleSettings(const std::string& simmode_name, const Settings& settings_json, - std::map>& vehicles, - std::map>& sensor_defaults) - { - initializeVehicleSettings(simmode_name, vehicles); + static void loadVehicleSettings(const std::string& simmode_name, const Settings& settings_json, + std::map>& vehicles, + std::map>& sensor_defaults) + { + initializeVehicleSettings(simmode_name, vehicles); - msr::airlib::Settings vehicles_child; - if (settings_json.getChild("Vehicles", vehicles_child)) { - std::vector keys; - vehicles_child.getChildNames(keys); + msr::airlib::Settings vehicles_child; + if (settings_json.getChild("Vehicles", vehicles_child)) { + std::vector keys; + vehicles_child.getChildNames(keys); - //remove default vehicles, if values are specified in settings - if (keys.size()) - vehicles.clear(); + //remove default vehicles, if values are specified in settings + if (keys.size()) + vehicles.clear(); - for (const auto& key : keys) { - msr::airlib::Settings child; - vehicles_child.getChild(key, child); - vehicles[key] = createVehicleSetting(simmode_name, child, key, sensor_defaults); + for (const auto& key : keys) { + msr::airlib::Settings child; + vehicles_child.getChild(key, child); + vehicles[key] = createVehicleSetting(simmode_name, child, key, sensor_defaults); + } } } - } - static void initializePawnPaths(std::map& pawn_paths) - { - pawn_paths.clear(); - pawn_paths.emplace("BareboneCar", - PawnPath("Class'/AirSim/VehicleAdv/Vehicle/VehicleAdvPawn.VehicleAdvPawn_C'")); - pawn_paths.emplace("DefaultCar", - PawnPath("Class'/AirSim/VehicleAdv/SUV/SuvCarPawn.SuvCarPawn_C'")); - pawn_paths.emplace("DefaultQuadrotor", - PawnPath("Class'/AirSim/Blueprints/BP_FlyingPawn.BP_FlyingPawn_C'")); - pawn_paths.emplace("DefaultComputerVision", - PawnPath("Class'/AirSim/Blueprints/BP_ComputerVisionPawn.BP_ComputerVisionPawn_C'")); - - } - - static void loadPawnPaths(const Settings& settings_json, std::map& pawn_paths) - { - initializePawnPaths(pawn_paths); + static void initializePawnPaths(std::map& pawn_paths) + { + pawn_paths.clear(); + pawn_paths.emplace("BareboneCar", + PawnPath("Class'/AirSim/VehicleAdv/Vehicle/VehicleAdvPawn.VehicleAdvPawn_C'")); + pawn_paths.emplace("DefaultCar", + PawnPath("Class'/AirSim/VehicleAdv/SUV/SuvCarPawn.SuvCarPawn_C'")); + pawn_paths.emplace("DefaultQuadrotor", + PawnPath("Class'/AirSim/Blueprints/BP_FlyingPawn.BP_FlyingPawn_C'")); + pawn_paths.emplace("DefaultComputerVision", + PawnPath("Class'/AirSim/Blueprints/BP_ComputerVisionPawn.BP_ComputerVisionPawn_C'")); + } - msr::airlib::Settings pawn_paths_child; - if (settings_json.getChild("PawnPaths", pawn_paths_child)) { - std::vector keys; - pawn_paths_child.getChildNames(keys); + static void loadPawnPaths(const Settings& settings_json, std::map& pawn_paths) + { + initializePawnPaths(pawn_paths); + + msr::airlib::Settings pawn_paths_child; + if (settings_json.getChild("PawnPaths", pawn_paths_child)) { + std::vector keys; + pawn_paths_child.getChildNames(keys); - for (const auto& key : keys) { - msr::airlib::Settings child; - pawn_paths_child.getChild(key, child); - pawn_paths[key] = createPathPawn(child); + for (const auto& key : keys) { + msr::airlib::Settings child; + pawn_paths_child.getChild(key, child); + pawn_paths[key] = createPathPawn(child); + } } } - } - static PawnPath createPathPawn(const Settings& settings_json) - { - auto paths = PawnPath(); - paths.pawn_bp = settings_json.getString("PawnBP", ""); - auto slippery_mat = settings_json.getString("SlipperyMat", ""); - auto non_slippery_mat = settings_json.getString("NonSlipperyMat", ""); + static PawnPath createPathPawn(const Settings& settings_json) + { + auto paths = PawnPath(); + paths.pawn_bp = settings_json.getString("PawnBP", ""); + auto slippery_mat = settings_json.getString("SlipperyMat", ""); + auto non_slippery_mat = settings_json.getString("NonSlipperyMat", ""); - if (slippery_mat != "") - paths.slippery_mat = slippery_mat; - if (non_slippery_mat != "") - paths.non_slippery_mat = non_slippery_mat; + if (slippery_mat != "") + paths.slippery_mat = slippery_mat; + if (non_slippery_mat != "") + paths.non_slippery_mat = non_slippery_mat; - return paths; - } + return paths; + } - static void loadSegmentationSetting(const Settings& settings_json, SegmentationSetting& segmentation_setting) - { - Settings json_parent; - if (settings_json.getChild("SegmentationSettings", json_parent)) { - std::string init_method = Utils::toLower(json_parent.getString("InitMethod", "")); - if (init_method == "" || init_method == "commonobjectsrandomids") - segmentation_setting.init_method = SegmentationSetting::InitMethodType::CommonObjectsRandomIDs; - else if (init_method == "none") - segmentation_setting.init_method = SegmentationSetting::InitMethodType::None; - else - //TODO: below exception doesn't actually get raised right now because of issue in Unreal Engine? - throw std::invalid_argument(std::string("SegmentationSetting init_method has invalid value in settings_json ") + init_method); + static void loadSegmentationSetting(const Settings& settings_json, SegmentationSetting& segmentation_setting) + { + Settings json_parent; + if (settings_json.getChild("SegmentationSettings", json_parent)) { + std::string init_method = Utils::toLower(json_parent.getString("InitMethod", "")); + if (init_method == "" || init_method == "commonobjectsrandomids") + segmentation_setting.init_method = SegmentationSetting::InitMethodType::CommonObjectsRandomIDs; + else if (init_method == "none") + segmentation_setting.init_method = SegmentationSetting::InitMethodType::None; + else + //TODO: below exception doesn't actually get raised right now because of issue in Unreal Engine? + throw std::invalid_argument(std::string("SegmentationSetting init_method has invalid value in settings_json ") + init_method); - segmentation_setting.override_existing = json_parent.getBool("OverrideExisting", false); + segmentation_setting.override_existing = json_parent.getBool("OverrideExisting", false); - std::string mesh_naming_method = Utils::toLower(json_parent.getString("MeshNamingMethod", "")); - if (mesh_naming_method == "" || mesh_naming_method == "ownername") - segmentation_setting.mesh_naming_method = SegmentationSetting::MeshNamingMethodType::OwnerName; - else if (mesh_naming_method == "staticmeshname") - segmentation_setting.mesh_naming_method = SegmentationSetting::MeshNamingMethodType::StaticMeshName; - else - throw std::invalid_argument(std::string("SegmentationSetting MeshNamingMethod has invalid value in settings_json ") + mesh_naming_method); + std::string mesh_naming_method = Utils::toLower(json_parent.getString("MeshNamingMethod", "")); + if (mesh_naming_method == "" || mesh_naming_method == "ownername") + segmentation_setting.mesh_naming_method = SegmentationSetting::MeshNamingMethodType::OwnerName; + else if (mesh_naming_method == "staticmeshname") + segmentation_setting.mesh_naming_method = SegmentationSetting::MeshNamingMethodType::StaticMeshName; + else + throw std::invalid_argument(std::string("SegmentationSetting MeshNamingMethod has invalid value in settings_json ") + mesh_naming_method); + } } - } - static void initializeNoiseSettings(std::map& noise_settings) - { - const int image_count = Utils::toNumeric(ImageType::Count); - noise_settings.clear(); - for (int i = -1; i < image_count; ++i) - noise_settings[i] = NoiseSetting(); - } + static void initializeNoiseSettings(std::map& noise_settings) + { + const int image_count = Utils::toNumeric(ImageType::Count); + noise_settings.clear(); + for (int i = -1; i < image_count; ++i) + noise_settings[i] = NoiseSetting(); + } - static void loadNoiseSettings(const Settings& settings_json, std::map& noise_settings) - { - initializeNoiseSettings(noise_settings); - - Settings json_parent; - if (settings_json.getChild("NoiseSettings", json_parent)) { - for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) { - Settings json_settings_child; - if (json_parent.getChild(child_index, json_settings_child)) { - NoiseSetting noise_setting; - loadNoiseSetting(json_settings_child, noise_setting); - noise_settings[noise_setting.ImageType] = noise_setting; + static void loadNoiseSettings(const Settings& settings_json, std::map& noise_settings) + { + initializeNoiseSettings(noise_settings); + + Settings json_parent; + if (settings_json.getChild("NoiseSettings", json_parent)) { + for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) { + Settings json_settings_child; + if (json_parent.getChild(child_index, json_settings_child)) { + NoiseSetting noise_setting; + loadNoiseSetting(json_settings_child, noise_setting); + noise_settings[noise_setting.ImageType] = noise_setting; + } } } } - } - - static void loadNoiseSetting(const msr::airlib::Settings& settings_json, NoiseSetting& noise_setting) - { - noise_setting.Enabled = settings_json.getBool("Enabled", noise_setting.Enabled); - noise_setting.ImageType = settings_json.getInt("ImageType", noise_setting.ImageType); - - noise_setting.HorzWaveStrength = settings_json.getFloat("HorzWaveStrength", noise_setting.HorzWaveStrength); - noise_setting.RandSpeed = settings_json.getFloat("RandSpeed", noise_setting.RandSpeed); - noise_setting.RandSize = settings_json.getFloat("RandSize", noise_setting.RandSize); - noise_setting.RandDensity = settings_json.getFloat("RandDensity", noise_setting.RandDensity); - noise_setting.RandContrib = settings_json.getFloat("RandContrib", noise_setting.RandContrib); - noise_setting.HorzWaveContrib = settings_json.getFloat("HorzWaveContrib", noise_setting.HorzWaveContrib); - noise_setting.HorzWaveVertSize = settings_json.getFloat("HorzWaveVertSize", noise_setting.HorzWaveVertSize); - noise_setting.HorzWaveScreenSize = settings_json.getFloat("HorzWaveScreenSize", noise_setting.HorzWaveScreenSize); - noise_setting.HorzNoiseLinesContrib = settings_json.getFloat("HorzNoiseLinesContrib", noise_setting.HorzNoiseLinesContrib); - noise_setting.HorzNoiseLinesDensityY = settings_json.getFloat("HorzNoiseLinesDensityY", noise_setting.HorzNoiseLinesDensityY); - noise_setting.HorzNoiseLinesDensityXY = settings_json.getFloat("HorzNoiseLinesDensityXY", noise_setting.HorzNoiseLinesDensityXY); - noise_setting.HorzDistortionStrength = settings_json.getFloat("HorzDistortionStrength", noise_setting.HorzDistortionStrength); - noise_setting.HorzDistortionContrib = settings_json.getFloat("HorzDistortionContrib", noise_setting.HorzDistortionContrib); - } - - static GimbalSetting createGimbalSetting(const Settings& settings_json) - { - GimbalSetting gimbal; - //capture_setting.gimbal.is_world_frame = settings_json.getBool("IsWorldFrame", false); - gimbal.stabilization = settings_json.getFloat("Stabilization", false); - gimbal.rotation = createRotationSetting(settings_json, gimbal.rotation); - return gimbal; - } - - static CameraSetting createCameraSetting(const Settings& settings_json) - { - CameraSetting setting; - setting.position = createVectorSetting(settings_json, setting.position); - setting.rotation = createRotationSetting(settings_json, setting.rotation); + static void loadNoiseSetting(const msr::airlib::Settings& settings_json, NoiseSetting& noise_setting) + { + noise_setting.Enabled = settings_json.getBool("Enabled", noise_setting.Enabled); + noise_setting.ImageType = settings_json.getInt("ImageType", noise_setting.ImageType); + + noise_setting.HorzWaveStrength = settings_json.getFloat("HorzWaveStrength", noise_setting.HorzWaveStrength); + noise_setting.RandSpeed = settings_json.getFloat("RandSpeed", noise_setting.RandSpeed); + noise_setting.RandSize = settings_json.getFloat("RandSize", noise_setting.RandSize); + noise_setting.RandDensity = settings_json.getFloat("RandDensity", noise_setting.RandDensity); + noise_setting.RandContrib = settings_json.getFloat("RandContrib", noise_setting.RandContrib); + noise_setting.HorzWaveContrib = settings_json.getFloat("HorzWaveContrib", noise_setting.HorzWaveContrib); + noise_setting.HorzWaveVertSize = settings_json.getFloat("HorzWaveVertSize", noise_setting.HorzWaveVertSize); + noise_setting.HorzWaveScreenSize = settings_json.getFloat("HorzWaveScreenSize", noise_setting.HorzWaveScreenSize); + noise_setting.HorzNoiseLinesContrib = settings_json.getFloat("HorzNoiseLinesContrib", noise_setting.HorzNoiseLinesContrib); + noise_setting.HorzNoiseLinesDensityY = settings_json.getFloat("HorzNoiseLinesDensityY", noise_setting.HorzNoiseLinesDensityY); + noise_setting.HorzNoiseLinesDensityXY = settings_json.getFloat("HorzNoiseLinesDensityXY", noise_setting.HorzNoiseLinesDensityXY); + noise_setting.HorzDistortionStrength = settings_json.getFloat("HorzDistortionStrength", noise_setting.HorzDistortionStrength); + noise_setting.HorzDistortionContrib = settings_json.getFloat("HorzDistortionContrib", noise_setting.HorzDistortionContrib); + } - loadCaptureSettings(settings_json, setting.capture_settings); - loadNoiseSettings(settings_json, setting.noise_settings); - Settings json_gimbal; - if (settings_json.getChild("Gimbal", json_gimbal)) - setting.gimbal = createGimbalSetting(json_gimbal); + static GimbalSetting createGimbalSetting(const Settings& settings_json) + { + GimbalSetting gimbal; + //capture_setting.gimbal.is_world_frame = settings_json.getBool("IsWorldFrame", false); + gimbal.stabilization = settings_json.getFloat("Stabilization", false); + gimbal.rotation = createRotationSetting(settings_json, gimbal.rotation); + return gimbal; + } - return setting; - } + static CameraSetting createCameraSetting(const Settings& settings_json) + { + CameraSetting setting; - static void loadCameraSettings(const Settings& settings_json, std::map& cameras) - { - cameras.clear(); + setting.position = createVectorSetting(settings_json, setting.position); + setting.rotation = createRotationSetting(settings_json, setting.rotation); - Settings json_parent; - if (settings_json.getChild("Cameras", json_parent)) { - std::vector keys; - json_parent.getChildNames(keys); + loadCaptureSettings(settings_json, setting.capture_settings); + loadNoiseSettings(settings_json, setting.noise_settings); + Settings json_gimbal; + if (settings_json.getChild("Gimbal", json_gimbal)) + setting.gimbal = createGimbalSetting(json_gimbal); - for (const auto& key : keys) { - msr::airlib::Settings child; - json_parent.getChild(key, child); - cameras[key] = createCameraSetting(child); - } + return setting; } - } - static void createCaptureSettings(const msr::airlib::Settings& settings_json, CaptureSetting& capture_setting) - { - capture_setting.width = settings_json.getInt("Width", capture_setting.width); - capture_setting.height = settings_json.getInt("Height", capture_setting.height); - capture_setting.fov_degrees = settings_json.getFloat("FOV_Degrees", capture_setting.fov_degrees); - capture_setting.auto_exposure_speed = settings_json.getFloat("AutoExposureSpeed", capture_setting.auto_exposure_speed); - capture_setting.auto_exposure_bias = settings_json.getFloat("AutoExposureBias", capture_setting.auto_exposure_bias); - capture_setting.auto_exposure_max_brightness = settings_json.getFloat("AutoExposureMaxBrightness", capture_setting.auto_exposure_max_brightness); - capture_setting.auto_exposure_min_brightness = settings_json.getFloat("AutoExposureMinBrightness", capture_setting.auto_exposure_min_brightness); - capture_setting.motion_blur_amount = settings_json.getFloat("MotionBlurAmount", capture_setting.motion_blur_amount); - capture_setting.image_type = settings_json.getInt("ImageType", 0); - capture_setting.target_gamma = settings_json.getFloat("TargetGamma", - capture_setting.image_type == 0 ? CaptureSetting::kSceneTargetGamma : Utils::nan()); - - std::string projection_mode = Utils::toLower(settings_json.getString("ProjectionMode", "")); - if (projection_mode == "" || projection_mode == "perspective") - capture_setting.projection_mode = 0; // Perspective - else if (projection_mode == "orthographic") - capture_setting.projection_mode = 1; // Orthographic - else - throw std::invalid_argument(std::string("CaptureSettings projection_mode has invalid value in settings_json ") + projection_mode); - - capture_setting.ortho_width = settings_json.getFloat("OrthoWidth", capture_setting.ortho_width); - } - - static void loadSubWindowsSettings(const Settings& settings_json, std::vector& subwindow_settings) - { - //load default subwindows - initializeSubwindowSettings(subwindow_settings); - - Settings json_parent; - if (settings_json.getChild("SubWindows", json_parent)) { - for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) { - Settings json_settings_child; - if (json_parent.getChild(child_index, json_settings_child)) { - int window_index = json_settings_child.getInt("WindowID", 0); - SubwindowSetting& subwindow_setting = subwindow_settings.at(window_index); - subwindow_setting.window_index = window_index; - subwindow_setting.image_type = Utils::toEnum( - json_settings_child.getInt("ImageType", 0)); - subwindow_setting.visible = json_settings_child.getBool("Visible", false); - subwindow_setting.camera_name = getCameraName(json_settings_child); - subwindow_setting.vehicle_name = json_settings_child.getString("VehicleName", ""); + static void loadCameraSettings(const Settings& settings_json, std::map& cameras) + { + cameras.clear(); + + Settings json_parent; + if (settings_json.getChild("Cameras", json_parent)) { + std::vector keys; + json_parent.getChildNames(keys); + + for (const auto& key : keys) { + msr::airlib::Settings child; + json_parent.getChild(key, child); + cameras[key] = createCameraSetting(child); } } } - } - static void initializeSubwindowSettings(std::vector& subwindow_settings) - { - subwindow_settings.clear(); - subwindow_settings.push_back(SubwindowSetting(0, ImageType::DepthVis, false, "", "")); //depth - subwindow_settings.push_back(SubwindowSetting(1, ImageType::Segmentation, false, "", "")); //seg - subwindow_settings.push_back(SubwindowSetting(2, ImageType::Scene, false, "", "")); //vis - } + static void createCaptureSettings(const msr::airlib::Settings& settings_json, CaptureSetting& capture_setting) + { + capture_setting.width = settings_json.getInt("Width", capture_setting.width); + capture_setting.height = settings_json.getInt("Height", capture_setting.height); + capture_setting.fov_degrees = settings_json.getFloat("FOV_Degrees", capture_setting.fov_degrees); + capture_setting.auto_exposure_speed = settings_json.getFloat("AutoExposureSpeed", capture_setting.auto_exposure_speed); + capture_setting.auto_exposure_bias = settings_json.getFloat("AutoExposureBias", capture_setting.auto_exposure_bias); + capture_setting.auto_exposure_max_brightness = settings_json.getFloat("AutoExposureMaxBrightness", capture_setting.auto_exposure_max_brightness); + capture_setting.auto_exposure_min_brightness = settings_json.getFloat("AutoExposureMinBrightness", capture_setting.auto_exposure_min_brightness); + capture_setting.motion_blur_amount = settings_json.getFloat("MotionBlurAmount", capture_setting.motion_blur_amount); + capture_setting.image_type = settings_json.getInt("ImageType", 0); + capture_setting.target_gamma = settings_json.getFloat("TargetGamma", + capture_setting.image_type == 0 ? CaptureSetting::kSceneTargetGamma : Utils::nan()); + + std::string projection_mode = Utils::toLower(settings_json.getString("ProjectionMode", "")); + if (projection_mode == "" || projection_mode == "perspective") + capture_setting.projection_mode = 0; // Perspective + else if (projection_mode == "orthographic") + capture_setting.projection_mode = 1; // Orthographic + else + throw std::invalid_argument(std::string("CaptureSettings projection_mode has invalid value in settings_json ") + projection_mode); - void loadOtherSettings(const Settings& settings_json) - { - //by default we spawn server at local endpoint. Do not use 127.0.0.1 as default below - //because for docker container default is 0.0.0.0 and people get really confused why things - //don't work - api_server_address = settings_json.getString("LocalHostIp", ""); - api_port = settings_json.getInt("ApiServerPort", RpcLibPort); - is_record_ui_visible = settings_json.getBool("RecordUIVisible", true); - engine_sound = settings_json.getBool("EngineSound", false); - enable_rpc = settings_json.getBool("EnableRpc", enable_rpc); - speed_unit_factor = settings_json.getFloat("SpeedUnitFactor", 1.0f); - speed_unit_label = settings_json.getString("SpeedUnitLabel", "m\\s"); - log_messages_visible = settings_json.getBool("LogMessagesVisible", true); - - { //load origin geopoint - Settings origin_geopoint_json; - if (settings_json.getChild("OriginGeopoint", origin_geopoint_json)) { - GeoPoint origin = origin_geopoint.home_geo_point; - origin.latitude = origin_geopoint_json.getDouble("Latitude", origin.latitude); - origin.longitude = origin_geopoint_json.getDouble("Longitude", origin.longitude); - origin.altitude = origin_geopoint_json.getFloat("Altitude", origin.altitude); - origin_geopoint.initialize(origin); - } + capture_setting.ortho_width = settings_json.getFloat("OrthoWidth", capture_setting.ortho_width); } - { //time of day settings_json - Settings tod_settings_json; - if (settings_json.getChild("TimeOfDay", tod_settings_json)) { - tod_setting.enabled = tod_settings_json.getBool("Enabled", tod_setting.enabled); - tod_setting.start_datetime = tod_settings_json.getString("StartDateTime", tod_setting.start_datetime); - tod_setting.celestial_clock_speed = tod_settings_json.getFloat("CelestialClockSpeed", tod_setting.celestial_clock_speed); - tod_setting.is_start_datetime_dst = tod_settings_json.getBool("StartDateTimeDst", tod_setting.is_start_datetime_dst); - tod_setting.update_interval_secs = tod_settings_json.getFloat("UpdateIntervalSecs", tod_setting.update_interval_secs); - tod_setting.move_sun = tod_settings_json.getBool("MoveSun", tod_setting.move_sun); + static void loadSubWindowsSettings(const Settings& settings_json, std::vector& subwindow_settings) + { + //load default subwindows + initializeSubwindowSettings(subwindow_settings); + + Settings json_parent; + if (settings_json.getChild("SubWindows", json_parent)) { + for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) { + Settings json_settings_child; + if (json_parent.getChild(child_index, json_settings_child)) { + int window_index = json_settings_child.getInt("WindowID", 0); + SubwindowSetting& subwindow_setting = subwindow_settings.at(window_index); + subwindow_setting.window_index = window_index; + subwindow_setting.image_type = Utils::toEnum( + json_settings_child.getInt("ImageType", 0)); + subwindow_setting.visible = json_settings_child.getBool("Visible", false); + subwindow_setting.camera_name = getCameraName(json_settings_child); + subwindow_setting.vehicle_name = json_settings_child.getString("VehicleName", ""); + } + } } } + static void initializeSubwindowSettings(std::vector& subwindow_settings) { - // Wind Settings - Settings child_json; - if (settings_json.getChild("Wind", child_json)) { - wind = createVectorSetting(child_json, wind); - } + subwindow_settings.clear(); + subwindow_settings.push_back(SubwindowSetting(0, ImageType::DepthVis, false, "", "")); //depth + subwindow_settings.push_back(SubwindowSetting(1, ImageType::Segmentation, false, "", "")); //seg + subwindow_settings.push_back(SubwindowSetting(2, ImageType::Scene, false, "", "")); //vis } - } - static void loadDefaultCameraSetting(const Settings& settings_json, CameraSetting& camera_defaults) - { - Settings child_json; - if (settings_json.getChild("CameraDefaults", child_json)) { - camera_defaults = createCameraSetting(child_json); - } - } + void loadOtherSettings(const Settings& settings_json) + { + //by default we spawn server at local endpoint. Do not use 127.0.0.1 as default below + //because for docker container default is 0.0.0.0 and people get really confused why things + //don't work + api_server_address = settings_json.getString("LocalHostIp", ""); + api_port = settings_json.getInt("ApiServerPort", RpcLibPort); + is_record_ui_visible = settings_json.getBool("RecordUIVisible", true); + engine_sound = settings_json.getBool("EngineSound", false); + enable_rpc = settings_json.getBool("EnableRpc", enable_rpc); + speed_unit_factor = settings_json.getFloat("SpeedUnitFactor", 1.0f); + speed_unit_label = settings_json.getString("SpeedUnitLabel", "m\\s"); + log_messages_visible = settings_json.getBool("LogMessagesVisible", true); + + { //load origin geopoint + Settings origin_geopoint_json; + if (settings_json.getChild("OriginGeopoint", origin_geopoint_json)) { + GeoPoint origin = origin_geopoint.home_geo_point; + origin.latitude = origin_geopoint_json.getDouble("Latitude", origin.latitude); + origin.longitude = origin_geopoint_json.getDouble("Longitude", origin.longitude); + origin.altitude = origin_geopoint_json.getFloat("Altitude", origin.altitude); + origin_geopoint.initialize(origin); + } + } - static void loadCameraDirectorSetting(const Settings& settings_json, - CameraDirectorSetting& camera_director, const std::string& simmode_name) - { - camera_director = CameraDirectorSetting(); + { //time of day settings_json + Settings tod_settings_json; + if (settings_json.getChild("TimeOfDay", tod_settings_json)) { + tod_setting.enabled = tod_settings_json.getBool("Enabled", tod_setting.enabled); + tod_setting.start_datetime = tod_settings_json.getString("StartDateTime", tod_setting.start_datetime); + tod_setting.celestial_clock_speed = tod_settings_json.getFloat("CelestialClockSpeed", tod_setting.celestial_clock_speed); + tod_setting.is_start_datetime_dst = tod_settings_json.getBool("StartDateTimeDst", tod_setting.is_start_datetime_dst); + tod_setting.update_interval_secs = tod_settings_json.getFloat("UpdateIntervalSecs", tod_setting.update_interval_secs); + tod_setting.move_sun = tod_settings_json.getBool("MoveSun", tod_setting.move_sun); + } + } - Settings child_json; - if (settings_json.getChild("CameraDirector", child_json)) { - camera_director.position = createVectorSetting(settings_json, camera_director.position); - camera_director.rotation = createRotationSetting(settings_json, camera_director.rotation); - camera_director.follow_distance = child_json.getFloat("FollowDistance", camera_director.follow_distance); + { + // Wind Settings + Settings child_json; + if (settings_json.getChild("Wind", child_json)) { + wind = createVectorSetting(child_json, wind); + } + } } - if (std::isnan(camera_director.follow_distance)) { - if (simmode_name == kSimModeTypeCar) - camera_director.follow_distance = -8; - else - camera_director.follow_distance = -3; - } - if (std::isnan(camera_director.position.x())) - camera_director.position.x() = camera_director.follow_distance; - if (std::isnan(camera_director.position.y())) - camera_director.position.y() = 0; - if (std::isnan(camera_director.position.z())) { - if (simmode_name == kSimModeTypeCar) - camera_director.position.z() = -4; - else - camera_director.position.z() = -2; + static void loadDefaultCameraSetting(const Settings& settings_json, CameraSetting& camera_defaults) + { + Settings child_json; + if (settings_json.getChild("CameraDefaults", child_json)) { + camera_defaults = createCameraSetting(child_json); + } } - } - void loadClockSettings(const Settings& settings_json) - { - clock_type = settings_json.getString("ClockType", ""); + static void loadCameraDirectorSetting(const Settings& settings_json, + CameraDirectorSetting& camera_director, const std::string& simmode_name) + { + camera_director = CameraDirectorSetting(); - if (clock_type == "") { - //default value - clock_type = "ScalableClock"; + Settings child_json; + if (settings_json.getChild("CameraDirector", child_json)) { + camera_director.position = createVectorSetting(settings_json, camera_director.position); + camera_director.rotation = createRotationSetting(settings_json, camera_director.rotation); + camera_director.follow_distance = child_json.getFloat("FollowDistance", camera_director.follow_distance); + } - //override if multirotor simmode with simple_flight - if (simmode_name == kSimModeTypeMultirotor) { - //TODO: this won't work if simple_flight and PX4 is combined together! - - //for multirotors we select steppable fixed interval clock unless we have - //PX4 enabled vehicle - clock_type = "SteppableClock"; - for (auto const& vehicle : vehicles) { - if (vehicle.second->auto_create && - vehicle.second->vehicle_type == kVehicleTypePX4) { - clock_type = "ScalableClock"; - break; + if (std::isnan(camera_director.follow_distance)) { + if (simmode_name == kSimModeTypeCar) + camera_director.follow_distance = -8; + else + camera_director.follow_distance = -3; + } + if (std::isnan(camera_director.position.x())) + camera_director.position.x() = camera_director.follow_distance; + if (std::isnan(camera_director.position.y())) + camera_director.position.y() = 0; + if (std::isnan(camera_director.position.z())) { + if (simmode_name == kSimModeTypeCar) + camera_director.position.z() = -4; + else + camera_director.position.z() = -2; + } + } + + void loadClockSettings(const Settings& settings_json) + { + clock_type = settings_json.getString("ClockType", ""); + + if (clock_type == "") { + //default value + clock_type = "ScalableClock"; + + //override if multirotor simmode with simple_flight + if (simmode_name == kSimModeTypeMultirotor) { + //TODO: this won't work if simple_flight and PX4 is combined together! + + //for multirotors we select steppable fixed interval clock unless we have + //PX4 enabled vehicle + clock_type = "SteppableClock"; + for (auto const& vehicle : vehicles) { + if (vehicle.second->auto_create && + vehicle.second->vehicle_type == kVehicleTypePX4) { + clock_type = "ScalableClock"; + break; + } } } } + + clock_speed = settings_json.getFloat("ClockSpeed", 1.0f); } - clock_speed = settings_json.getFloat("ClockSpeed", 1.0f); - } + static std::shared_ptr createSensorSetting( + SensorBase::SensorType sensor_type, const std::string& sensor_name, + bool enabled) + { + std::shared_ptr sensor_setting; + + switch (sensor_type) { + case SensorBase::SensorType::Barometer: + sensor_setting = std::shared_ptr(new BarometerSetting()); + break; + case SensorBase::SensorType::Imu: + sensor_setting = std::shared_ptr(new ImuSetting()); + break; + case SensorBase::SensorType::Gps: + sensor_setting = std::shared_ptr(new GpsSetting()); + break; + case SensorBase::SensorType::Magnetometer: + sensor_setting = std::shared_ptr(new MagnetometerSetting()); + break; + case SensorBase::SensorType::Distance: + sensor_setting = std::shared_ptr(new DistanceSetting()); + break; + case SensorBase::SensorType::Lidar: + sensor_setting = std::shared_ptr(new LidarSetting()); + break; + default: + throw std::invalid_argument("Unexpected sensor type"); + } - static std::shared_ptr createSensorSetting( - SensorBase::SensorType sensor_type, const std::string& sensor_name, - bool enabled) - { - std::shared_ptr sensor_setting; - - switch (sensor_type) { - case SensorBase::SensorType::Barometer: - sensor_setting = std::shared_ptr(new BarometerSetting()); - break; - case SensorBase::SensorType::Imu: - sensor_setting = std::shared_ptr(new ImuSetting()); - break; - case SensorBase::SensorType::Gps: - sensor_setting = std::shared_ptr(new GpsSetting()); - break; - case SensorBase::SensorType::Magnetometer: - sensor_setting = std::shared_ptr(new MagnetometerSetting()); - break; - case SensorBase::SensorType::Distance: - sensor_setting = std::shared_ptr(new DistanceSetting()); - break; - case SensorBase::SensorType::Lidar: - sensor_setting = std::shared_ptr(new LidarSetting()); - break; - default: - throw std::invalid_argument("Unexpected sensor type"); + sensor_setting->sensor_type = sensor_type; + sensor_setting->sensor_name = sensor_name; + sensor_setting->enabled = enabled; + + return sensor_setting; } - sensor_setting->sensor_type = sensor_type; - sensor_setting->sensor_name = sensor_name; - sensor_setting->enabled = enabled; + static void initializeSensorSetting(SensorSetting* sensor_setting, const Settings& settings_json) + { + sensor_setting->enabled = settings_json.getBool("Enabled", sensor_setting->enabled); - return sensor_setting; - } + // pass the json Settings property bag through to the specific sensor params object where it is + // extracted there. This way default values can be kept in one place. For example, see the + // BarometerSimpleParams::initializeFromSettings method. + sensor_setting->settings = settings_json; + } - static void initializeSensorSetting(SensorSetting* sensor_setting, const Settings& settings_json) - { - sensor_setting->enabled = settings_json.getBool("Enabled", sensor_setting->enabled); - - // pass the json Settings property bag through to the specific sensor params object where it is - // extracted there. This way default values can be kept in one place. For example, see the - // BarometerSimpleParams::initializeFromSettings method. - sensor_setting->settings = settings_json; - } - - // creates and intializes sensor settings from json - static void loadSensorSettings( const Settings& settings_json, const std::string& collectionName, - std::map>& sensors, - std::map>& sensor_defaults) + // creates and intializes sensor settings from json + static void loadSensorSettings(const Settings& settings_json, const std::string& collectionName, + std::map>& sensors, + std::map>& sensor_defaults) - { - // start with defaults. - for (auto ptr = sensor_defaults.begin(); ptr != sensor_defaults.end(); ptr++) { - auto key = ptr->first; - sensors[key] = sensor_defaults[key]; - } + { + // start with defaults. + for (auto ptr = sensor_defaults.begin(); ptr != sensor_defaults.end(); ptr++) { + auto key = ptr->first; + sensors[key] = sensor_defaults[key]; + } - msr::airlib::Settings sensors_child; - if (settings_json.getChild(collectionName, sensors_child)) { - std::vector keys; - sensors_child.getChildNames(keys); + msr::airlib::Settings sensors_child; + if (settings_json.getChild(collectionName, sensors_child)) { + std::vector keys; + sensors_child.getChildNames(keys); - for (const auto& key : keys) { - msr::airlib::Settings child; - sensors_child.getChild(key, child); + for (const auto& key : keys) { + msr::airlib::Settings child; + sensors_child.getChild(key, child); - auto sensor_type = Utils::toEnum(child.getInt("SensorType", 0)); - auto enabled = child.getBool("Enabled", false); + auto sensor_type = Utils::toEnum(child.getInt("SensorType", 0)); + auto enabled = child.getBool("Enabled", false); - sensors[key] = createSensorSetting(sensor_type, key, enabled); - initializeSensorSetting(sensors[key].get(), child); + sensors[key] = createSensorSetting(sensor_type, key, enabled); + initializeSensorSetting(sensors[key].get(), child); + } } } - } - // creates default sensor list when none specified in json - static void createDefaultSensorSettings(const std::string& simmode_name, - std::map>& sensors) - { - if (simmode_name == kSimModeTypeMultirotor) { - sensors["imu"] = createSensorSetting(SensorBase::SensorType::Imu, "imu", true); - sensors["magnetometer"] = createSensorSetting(SensorBase::SensorType::Magnetometer, "magnetometer", true); - sensors["gps"] = createSensorSetting(SensorBase::SensorType::Gps, "gps", true); - sensors["barometer"] = createSensorSetting(SensorBase::SensorType::Barometer, "barometer", true); - } - else if (simmode_name == kSimModeTypeCar) { - sensors["gps"] = createSensorSetting(SensorBase::SensorType::Gps, "gps", true); + // creates default sensor list when none specified in json + static void createDefaultSensorSettings(const std::string& simmode_name, + std::map>& sensors) + { + if (simmode_name == kSimModeTypeMultirotor) { + sensors["imu"] = createSensorSetting(SensorBase::SensorType::Imu, "imu", true); + sensors["magnetometer"] = createSensorSetting(SensorBase::SensorType::Magnetometer, "magnetometer", true); + sensors["gps"] = createSensorSetting(SensorBase::SensorType::Gps, "gps", true); + sensors["barometer"] = createSensorSetting(SensorBase::SensorType::Barometer, "barometer", true); + } + else if (simmode_name == kSimModeTypeCar) { + sensors["gps"] = createSensorSetting(SensorBase::SensorType::Gps, "gps", true); + } + else { + // no sensors added for other modes + } } - else { - // no sensors added for other modes + + // loads or creates default sensor list + static void loadDefaultSensorSettings(const std::string& simmode_name, + const Settings& settings_json, + std::map>& sensors) + { + msr::airlib::Settings sensors_child; + if (settings_json.getChild("DefaultSensors", sensors_child)) + loadSensorSettings(settings_json, "DefaultSensors", sensors, sensors); + else + createDefaultSensorSettings(simmode_name, sensors); } - } + }; - // loads or creates default sensor list - static void loadDefaultSensorSettings(const std::string& simmode_name, - const Settings& settings_json, - std::map>& sensors) - { - msr::airlib::Settings sensors_child; - if (settings_json.getChild("DefaultSensors", sensors_child)) - loadSensorSettings(settings_json, "DefaultSensors", sensors, sensors); - else - createDefaultSensorSettings(simmode_name, sensors); - } -}; - -}} //namespace +} +} //namespace #endif diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp index 6e1977cee9..36bf96e088 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp @@ -63,7 +63,7 @@ namespace airlib connection_info_ = connection_info; sensors_ = sensors; is_simulation_mode_ = is_simulation; - + lock_step_enabled_ = connection_info.lock_step; try { openAllConnections(); is_ready_ = true; @@ -106,7 +106,7 @@ namespace airlib unsigned long long getSimTime() { // This ensures HIL_SENSOR and HIL_GPS have matching clocks. - if (lock_step_enabled_) { + if (lock_step_active_) { if (sim_time_us_ == 0) { sim_time_us_ = clock()->nowNanos() / 1000; } @@ -137,10 +137,10 @@ namespace airlib update_count_++; } - if (lock_step_enabled_) { - if (last_update_time_ + 100000 < now) { - // if 100 ms passes then something is terribly wrong, reset lockstep mode - lock_step_enabled_ = false; + if (lock_step_active_) { + if (last_update_time_ + 1000000 < now) { + // if 1 second passes then something is terribly wrong, reset lockstep mode + lock_step_active_ = false; { std::lock_guard guard(telemetry_mutex_); lock_step_resets_++; @@ -613,6 +613,7 @@ namespace airlib } else if (hil_message_timer_.seconds() > messageReceivedTimeout) { addStatusMessage("not receiving any messages from HIL, please restart your HIL node and try again"); + hil_message_timer_.stop(); } } else { @@ -1607,11 +1608,11 @@ namespace airlib { received_actuator_controls_ = true; // if the timestamps match then it means we are in lockstep mode. - if (!lock_step_enabled_) { + if (!lock_step_active_ && lock_step_enabled_) { // && (HilActuatorControlsMessage.flags & 0x1)) // todo: enable this check when this flag is widely available... if (last_hil_sensor_time_ == HilActuatorControlsMessage.time_usec) { addStatusMessage("Enabling lockstep mode"); - lock_step_enabled_ = true; + lock_step_active_ = true; } } else { @@ -1787,8 +1788,8 @@ namespace airlib if (hil_node_ != nullptr) { hil_node_->sendMessage(hil_sensor); received_actuator_controls_ = false; - if (lock_step_enabled_ && world_ != nullptr) { - world_->pauseForTime(0.1); // 100 millisecond delay max waiting for actuator controls. + if (lock_step_active_ && world_ != nullptr) { + world_->pauseForTime(1); // 1 second delay max waiting for actuator controls. } } @@ -1834,10 +1835,13 @@ namespace airlib distance_sensor.quaternion[3] = orientation.z(); //TODO: use covariance parameter? - - if (hil_node_ != nullptr) { - hil_node_->sendMessage(distance_sensor); - } + // PX4 doesn't support receiving simulated distance sensor messages this way. + // It results in lots of error messages from PX4. This code is still useful in that + // it sets last_distance_message_ and that is returned via Python API. + // + // if (hil_node_ != nullptr) { + // hil_node_->sendMessage(distance_sensor); + // } std::lock_guard guard(last_message_mutex_); last_distance_message_ = distance_sensor; @@ -1906,6 +1910,7 @@ namespace airlib Utils::setValue(rotor_controls_, 0.0f); was_reset_ = false; received_actuator_controls_ = false; + lock_step_active_ = false; lock_step_enabled_ = false; has_gps_lock_ = false; send_params_ = false; @@ -1982,6 +1987,7 @@ namespace airlib bool has_home_ = false; bool is_ready_ = false; bool has_gps_lock_ = false; + bool lock_step_active_ = false; bool lock_step_enabled_ = false; bool received_actuator_controls_ = false; std::string is_ready_message_; diff --git a/docs/px4_lockstep.md b/docs/px4_lockstep.md new file mode 100644 index 0000000000..c12d8b554c --- /dev/null +++ b/docs/px4_lockstep.md @@ -0,0 +1,40 @@ +# LockStep + +The latest version of PX4 supports a new [lockstep +feature](https://docs.px4.io/master/en/simulation/#lockstep-simulation) when communicating with the +simulator over TCP. Lockstep is an important feature because it synchronizes PX4 and the simulator +so they essentially use the same clock time. This makes PX4 behave normally even during unusually +long delays in Simulator performance. + +It is recommended that when you are running a lockstep enabled version of PX4 in SITL mode that you +tell AirSim to use a `SteppableClock`, and set `UseTcp` to `true` and `LockStep` to `true`. + +``` + { + "SettingsVersion": 1.2, + "SimMode": "Multirotor", + "ClockType": "SteppableClock", + "Vehicles": { + "PX4": { + "VehicleType": "PX4Multirotor", + "UseTcp": true, + "LockStep": true, + ... +``` + +This causes AirSim to not use a "realtime" clock, but instead it advances the clock in step which +each sensor update sent to PX4. This way PX4 thinks time is progressing smoothly no matter how long +it takes AirSim to really process that update loop. + +This has the following advantages: + +- AirSim can be used on slow machines that cannot process updates quickly. +- You can debug AirSim and hit a breakpoint, and when you resume PX4 will behave normally. +- You can enable very slow sensors like the Lidar with large number of simulated points, and PX4 + will still behave normally. + +There will be some side effects to `lockstep`, namely, slower update loops caused by running AirSim +on an underpowered machine or from expensive sensors (like Lidar) will create some visible jerkiness +in the simulated flight if you look at the updates on screen in realtime. + + diff --git a/docs/px4_setup.md b/docs/px4_setup.md index 03914471bf..b1ba3e454d 100644 --- a/docs/px4_setup.md +++ b/docs/px4_setup.md @@ -34,10 +34,12 @@ See also [initial firmware setup video](https://docs.px4.io/master/en/config/). { "SettingsVersion": 1.2, "SimMode": "Multirotor", + "ClockType": "SteppableClock", "Vehicles": { "PX4": { "VehicleType": "PX4Multirotor", "UseSerial": true, + "LockStep": true, "Sensors":{ "Barometer":{ "SensorType": 1, @@ -57,6 +59,8 @@ See also [initial firmware setup video](https://docs.px4.io/master/en/config/). } ``` +See [PX4 LockStep](px4_lockstep.md) for more information. + The "Barometer" setting keeps PX4 happy because the default AirSim barometer has a bit too much noise generation. This setting clamps that down a bit. diff --git a/docs/px4_sitl.md b/docs/px4_sitl.md index 2c664fa111..0fa2b8ce40 100644 --- a/docs/px4_sitl.md +++ b/docs/px4_sitl.md @@ -56,10 +56,12 @@ The default ports have changed recently, so check them closely to make sure AirS { "SettingsVersion": 1.2, "SimMode": "Multirotor", + "ClockType": "SteppableClock", "Vehicles": { "PX4": { "VehicleType": "PX4Multirotor", "UseSerial": false, + "LockStep": true, "UseTcp": true, "TcpPort": 4560, "ControlPort": 14580, @@ -82,6 +84,7 @@ The default ports have changed recently, so check them closely to make sure AirS } ``` Notice the PX4 `[simulator]` is using TCP, which is why we need to add: `"UseTcp": true,`. + See [PX4 LockStep](px4_lockstep.md) for more information. The "Barometer" setting keeps PX4 happy because the default AirSim barometer has a bit too much noise generation. This setting clamps that down a bit. diff --git a/docs/px4_sitl_wsl2.md b/docs/px4_sitl_wsl2.md index 03baaa8936..4627caae28 100644 --- a/docs/px4_sitl_wsl2.md +++ b/docs/px4_sitl_wsl2.md @@ -47,10 +47,12 @@ This resolves to the WSL 2 remote ip address found in the TCP socket. { "SettingsVersion": 1.2, "SimMode": "Multirotor", + "ClockType": "SteppableClock", "Vehicles": { "PX4": { "VehicleType": "PX4Multirotor", "UseSerial": false, + "LockStep": true, "UseTcp": true, "TcpPort": 4560, "ControlIp": "remote", @@ -74,7 +76,7 @@ This resolves to the WSL 2 remote ip address found in the TCP socket. } } ``` - +See [PX4 LockStep](px4_lockstep.md) for more information. The "Barometer" setting keeps PX4 happy because the default AirSim barometer has a bit too much noise generation. This setting clamps that down a bit. @@ -89,7 +91,7 @@ if [ -z "${PX4_SIM_HOST_ADDR}" ]; then simulator start -c $simulator_tcp_port else echo "PX4 SIM HOST: $PX4_SIM_HOST_ADDR" - simulator start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port + simulator start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port fi ``` From ef5a6a656f4a06b8489ee5d6bbb1b4d603378288 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Tue, 4 May 2021 12:25:05 -0700 Subject: [PATCH 36/37] add lockstep to toc --- mkdocs.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/mkdocs.yml b/mkdocs.yml index d0fb62d6a1..37f096a79f 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -87,6 +87,7 @@ nav: - "PX4 Setup for AirSim": 'px4_setup.md' - "PX4 in SITL": 'px4_sitl.md' - "PX4 SITL with WSL 2": 'px4_sitl_wsl2.md' + - "PX4 Lockstep": 'px4_lockstep.md' - "PX4 Multi-vehicle in SITL": 'px4_multi_vehicle.md' - "AirSim with Pixhawk": 'https://youtu.be/1oY8Qu5maQQ' - "PX4 Setup with AirSim": 'https://youtu.be/HNWdYrtw3f0' From 6db5c7f80f57ce04b068c8c2aebfd4e5fc3e3599 Mon Sep 17 00:00:00 2001 From: Chris Lovett Date: Wed, 5 May 2021 16:30:24 -0700 Subject: [PATCH 37/37] Make sure each buffer is zero'd out before reading bytes. Remove unnecessary metadata from mavlink messages and make tooltips show on top of close box in the charts. --- .gitignore | 1 - .../LogViewer/Controls/SimpleLineChart.xaml | 19 +- LogViewer/LogViewer/LogViewer.csproj | 2 +- LogViewer/LogViewer/Model/MavlinkLog.cs | 8 +- LogViewer/LogViewer/publish.cmd | 6 + LogViewer/Networking/Mavlink/MavlinkTypes.cs | 358 +++++++++--------- 6 files changed, 203 insertions(+), 191 deletions(-) create mode 100644 LogViewer/LogViewer/publish.cmd diff --git a/.gitignore b/.gitignore index 628c35995d..ec5b0897c7 100644 --- a/.gitignore +++ b/.gitignore @@ -386,4 +386,3 @@ build_docs/ # api docs PythonClient/docs/_build -/LogViewer/LogViewer/publish.cmd diff --git a/LogViewer/LogViewer/Controls/SimpleLineChart.xaml b/LogViewer/LogViewer/Controls/SimpleLineChart.xaml index ef8824b346..f4043fe64e 100644 --- a/LogViewer/LogViewer/Controls/SimpleLineChart.xaml +++ b/LogViewer/LogViewer/Controls/SimpleLineChart.xaml @@ -33,14 +33,6 @@ - - - - - - - @@ -54,5 +46,16 @@ + + + + + + + + + + diff --git a/LogViewer/LogViewer/LogViewer.csproj b/LogViewer/LogViewer/LogViewer.csproj index 3dd09bb285..a0a5065def 100644 --- a/LogViewer/LogViewer/LogViewer.csproj +++ b/LogViewer/LogViewer/LogViewer.csproj @@ -33,7 +33,7 @@ PX4 Log Viewer true publish.htm - 62 + 63 1.0.0.%2a false true diff --git a/LogViewer/LogViewer/Model/MavlinkLog.cs b/LogViewer/LogViewer/Model/MavlinkLog.cs index 7b92b7dfde..bb0572f0f8 100644 --- a/LogViewer/LogViewer/Model/MavlinkLog.cs +++ b/LogViewer/LogViewer/Model/MavlinkLog.cs @@ -584,7 +584,8 @@ public async Task Load(string file, ProgressUtility progress) this.duration = TimeSpan.Zero; bool first = true; // QT time is milliseconds from the following epoch. - byte[] msgBuf = new byte[256]; + const int BUFFER_SIZE = 8000; + byte[] msgBuf = new byte[BUFFER_SIZE]; GCHandle handle = GCHandle.Alloc(msgBuf, GCHandleType.Pinned); IntPtr ptr = handle.AddrOfPinnedObject(); @@ -605,14 +606,17 @@ await Task.Run(() => { MavLinkMessage header = new MavLinkMessage(); header.ReadHeader(reader); + + Array.Clear(msgBuf, 0, BUFFER_SIZE); int read = s.Read(msgBuf, 0, header.Length); if (read == header.Length) { + int id = (int)header.MsgId; header.Crc = reader.ReadUInt16(); bool checkCrc = true; - if ((int)header.MsgId == MAVLink.mavlink_telemetry.MessageId) + if (id == MAVLink.mavlink_telemetry.MessageId) { if (header.Crc == 0) // telemetry has no crc. { diff --git a/LogViewer/LogViewer/publish.cmd b/LogViewer/LogViewer/publish.cmd new file mode 100644 index 0000000000..7c55bbcb06 --- /dev/null +++ b/LogViewer/LogViewer/publish.cmd @@ -0,0 +1,6 @@ +@echo off +cd %~dp0 + +echo Uploading ClickOnce installer for Px4LogViewer +AzurePublishClickOnce %~dp0publish downloads/Px4LogViewer "%LOVETTSOFTWARE_STORAGE_CONNECTION_STRING%" +if ERRORLEVEL 1 goto :eof diff --git a/LogViewer/Networking/Mavlink/MavlinkTypes.cs b/LogViewer/Networking/Mavlink/MavlinkTypes.cs index 549f056b50..ceecab6229 100644 --- a/LogViewer/Networking/Mavlink/MavlinkTypes.cs +++ b/LogViewer/Networking/Mavlink/MavlinkTypes.cs @@ -2350,7 +2350,7 @@ public enum ADSB_FLAGS }; - [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 42)] + [StructLayout(LayoutKind.Sequential)] public struct mavlink_sensor_offsets_t { ///